diff --git a/.clang-format b/.clang-format
deleted file mode 100644
index 827c89b435020ccdca9a15eb06a972ac5947c742..0000000000000000000000000000000000000000
--- a/.clang-format
+++ /dev/null
@@ -1,13 +0,0 @@
-{
- BasedOnStyle: Google,
- AccessModifierOffset: -4,
- AlignConsecutiveAssignments: true,
- AllowShortIfStatementsOnASingleLine: false,
- AllowShortLoopsOnASingleLine: false,
- BreakBeforeBraces: Allman,
- ColumnLimit: 80,
- ConstructorInitializerAllOnOneLineOrOnePerLine: false,
- IndentCaseLabels: true,
- IndentWidth: 4,
- KeepEmptyLinesAtTheStartOfBlocks: true,
-}
diff --git a/.gitignore b/.gitignore
index 45f7d5708d689f77c2f325da11361bb2cbfbaf8e..43d4cb86fb5649a8ff1f7efd0af3d8e6a092029c 100644
--- a/.gitignore
+++ b/.gitignore
@@ -33,4 +33,4 @@
# ide folder & virtual environments
.venv/
-.vscode
\ No newline at end of file
+.vscode
diff --git a/.gitmodules b/.gitmodules
index 543c13196d8ad513b375d2bd7413934b5ef02b9e..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391 100644
--- a/.gitmodules
+++ b/.gitmodules
@@ -1,3 +0,0 @@
-[submodule "mavlink"]
- path = mavlink
- url = ../mavlink
diff --git a/CMakeLists.txt b/CMakeLists.txt
deleted file mode 100644
index 89cb2260f4486e39745e68e6d2038d79dc2e5821..0000000000000000000000000000000000000000
--- a/CMakeLists.txt
+++ /dev/null
@@ -1,27 +0,0 @@
-# Copyright (c) 2021 Skyward Experimental Rocketry
-# Author: Damiano Amatruda
-#
-# Permission is hereby granted, free of charge, to any person obtaining a copy
-# of this software and associated documentation files (the "Software"), to deal
-# in the Software without restriction, including without limitation the rights
-# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
-# copies of the Software, and to permit persons to whom the Software is
-# furnished to do so, subject to the following conditions:
-#
-# The above copyright notice and this permission notice shall be included in
-# all copies or substantial portions of the Software.
-#
-# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
-# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
-# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
-# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
-# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
-# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
-# THE SOFTWARE.
-
-cmake_minimum_required(VERSION 3.16)
-project(Mavlink C CXX ASM)
-
-add_library(mavlink INTERFACE)
-add_library(Mavlink::Mavlink ALIAS mavlink)
-target_include_directories(mavlink INTERFACE ${CMAKE_CURRENT_SOURCE_DIR})
diff --git a/bitpacking/BitPacker.h b/bitpacking/BitPacker.h
deleted file mode 100644
index c5df1679bd6aae262bdad175368aeda30c27c083..0000000000000000000000000000000000000000
--- a/bitpacking/BitPacker.h
+++ /dev/null
@@ -1,381 +0,0 @@
-/**
- * Copyright (c) 2019 Skyward Experimental Rocketry
- * Authors: Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-
-#pragma once
-
-#include <math.h>
-#include <string>
-
-class BitPacker {
-
- public:
- /* Constructor: receives an array (packet) and its size
- (if the size is not specified, the default one is used) */
- BitPacker(uint8_t *packet, unsigned int size = DEFAULT_PACKET_SIZE)
- : packet(packet), packet_size(size) {
- // do nothing
- }
-
- /*
- PAY ATTENTION TO THE POSITION AND THE NUMBER OF BITS YOU WRITE IN THE PACKET.
- IF THOSE TWO PARAMETERS ARE FOR SOME REASON NOT CORRECT, YOU MAY OVERWRITE
- VALUES THAT THE PACKET ARRAY ALREADY CONTAINS.
- IN THAT CASE YOU HAVE TO CLEAR THE PACKET (see the clear() method) AND RE-WRITE
- ALL THE VALUES YOU NEED.
- */
- /* Write a number of bits equal to bits_num of the
- parameter value to the packet array, starting from the
- position identified by bit_pos (first bit of the array
- in which the vlaue will be written).
- Return false in case some parameters are invalid, true if
- the value has been correctly written. */
- template<typename T>
- bool pack(unsigned int bit_pos, unsigned int bits_num, T value) {
-
- // check parameters validity
- if (!checkParameters(bit_pos, bits_num, value))
- return false;
-
- //uint64_t write_value = 0; // the actual variable that will be written in the packet
- // cast the received value to 64-bits variable
- // dest | source | number of bits
- //memcpy(&write_value, &value, sizeof(uint64_t));
-
- // reset the bits to 0 before writing in them
- reset(bit_pos, bits_num);
-
- uint8_t curr_byte; // the current extracted byte from the value paramter
- unsigned int byte_count = 0; /* the current number of extracted byte (i.e. iteration number)
- ---> byte_count must start from 0, since to extract the first
- byte there is no need to shift the value (1 for the second and so on)*/
- unsigned int byte_index = 0; // the index of the packet byte in which the value has to be written
- int remaining_bits_num = bits_num; // the current number of bits that remain to be written in the packet
-
- while (remaining_bits_num > 0) {
- /* extract the i-th byte (identified by byte_count)
- from value parameter (from right to left) */
- curr_byte = extractByte(byte_count, value);
-
- /* note that bytes need to be written in reverse
- order w.r.t. the order in which they are extracted from value,
- so this index is computed and used to know where to
- write the current byte inside the packet (from which bit) */
- unsigned int curr_byte_dest_index = 0;
- if (remaining_bits_num > 8) // necessary condition to avoid accessing the array at negative positions
- curr_byte_dest_index = bit_pos + bits_num - (byte_count+1) * 8;
- else
- curr_byte_dest_index = bit_pos;
-
- // compute the destination byte in the packet
- byte_index = (curr_byte_dest_index - (curr_byte_dest_index % 8)) / 8;
-
- /* set the byte starting at the bit identified
- by curr_byte_dest_index (not necessairily
- aligned with array elements) equal to curr_byte */
- writeByte(byte_index, curr_byte_dest_index, remaining_bits_num, curr_byte);
-
- remaining_bits_num = remaining_bits_num - 8; // write 1 byte at each iteration
- byte_count++; // go to the next byte to be extracted from value
- }
-
- return true;
- }
-
- /* Get a value contained in the packet, reading a number
- of bits equal to bits_num, starting from the bit specified by bit_pos.
- The read value is put in the result parameter.
- Return false in case some parameters are invalid, true if the value
- has been correctly read. */
- template<typename T>
- bool unpack(unsigned int bit_pos, unsigned int bits_num, T *result) {
-
- // check parameters validity
- if (!checkParameters(bit_pos, bits_num, *result))
- return false;
-
- unsigned int read_bits_num = 0; // current number of bits unpacked
- unsigned int byte_index = (bit_pos - (bit_pos % 8)) / 8; // packet element where to start reading data
- //unsigned int byte_count = 0; // counter used to know how many bytes have been read so far from the packet
- // (i.e. it indiscates the iteration number)
- *result = 0; // the value to be returned
-
- // until not all the bits have been read
- while(read_bits_num < bits_num) {
-
- // starting bit position of the current read, relative to the entire packet
- unsigned int starting_pos = bit_pos + read_bits_num;
-
- // read one element of the packet
- uint64_t read_value = readByte(byte_index, bits_num, &read_bits_num, starting_pos);
-
- // update the result
- *result |= read_value;
-
- // go to the next packet element
- byte_index++;
- }
-
- return true;
- }
-
- // return the current packet
- uint8_t * getPacket() {
- return packet;
- }
-
- // return the packet size
- unsigned int getPacketSize() {
- return packet_size;
- }
-
- // reset all the elements of packet to zero
- void resetAll() {
- for (unsigned int i = 0; i < packet_size; i++)
- packet[i] = 0;
- }
-
- // reset to zero a specific byte (element) of packet
- void resetByte(unsigned int index) {
- packet[index] = 0;
- }
-
- /* reset to zero a number of bits equal to bits_num,
- starting from position bit_index in the packet.
- */
- void reset(unsigned int bit_index, unsigned int bits_num) {
-
- // the byte where starting to reset the bits
- unsigned int byte_index = (bit_index - (bit_index % 8)) / 8;
-
- // the starting bit position, relative to the current byte
- uint8_t index_in_byte;
- // the number of remaining bits to be reset
- unsigned int remaining_bits_num = bits_num;
- // the number of bits to be reset in the current byte
- uint8_t to_be_reset;
- // the mask used to reset the wanted bits in the current byte
- uint8_t mask;
-
- while (remaining_bits_num > 0) {
-
- // index of the starting bit, relative to the current byte
- index_in_byte = bit_index % 8;
- // get the number of bits to be reset in the current bye
- to_be_reset = getRelevantBitsNum(remaining_bits_num, index_in_byte);
- // compute the mask
- mask = getMask(to_be_reset, index_in_byte);
- // invert mask bits to reset the wanted bits to zero
- mask = ~ mask;
- // in order to reset bits to zero perform an AND with the inverted mask
- packet[byte_index] &= mask;
-
- // update the number of remaining bits by removing the number of reset bits
- remaining_bits_num = remaining_bits_num - to_be_reset;
- byte_index++; // go to the next byte
- bit_index = bit_index + to_be_reset; // update the starting bit_index
- }
- }
-
- void printPacket() {
- printf("packet = [ ");
- for (unsigned int j = 0; j < packet_size; j++)
- printf("%d ", packet[j]);
- printf("]\n");
- }
-
- /* default number of bytes contained in one packet
- (used in case a different value is not passed to the constructor) */
- static const int DEFAULT_PACKET_SIZE = 25;
-
- private:
- // extract a specific byte from parameter val
- template<typename T>
- uint8_t extractByte(uint8_t index, T val) {
- uint8_t byte = (val >> (index * 8)) & 0xff;
- if (!byte)
- byte = 0x00; // needed, otherwise bytes containing all zeros are ignored
- return byte;
- }
-
- /* set a byte of packet to the given one, starting from a specific
- bit, given by the value of the paramter bit_index
- (not necessarly aligned with a packet element,
- the written byte can overlap with multiple ones)
- byte_index: the destination byte position
- bit_index: the destination bit position
- byte: the value to be written in bit_index
- bits_num: number of bits to be written (8 or less) */
- void writeByte(unsigned int byte_index, unsigned int bit_index, unsigned int bits_num, uint8_t byte) {
-
- /* get the relative index inside the found byte
- corresponding to the position given by bit_index */
- uint8_t index_in_byte = bit_index % 8;
-
- // in case we want to write less then 1 byte
- if (bits_num < 8) {
- // keep only the least significant bits_num of bits of the byte
- // (remove the unwanted bits on the left of the value to be written)
- byte = byte << (8-bits_num);
- }
-
- /* extract left and right part of the byte to be written
- (those two parts will go in subsequent bytes if the
- bit_index position is not multiple of 8, otherwise the
- entire value to be written would be contained in left_part) */
- // shift to move left_part aligned to the requested position
- packet[byte_index] |= getLeftPart(byte, index_in_byte);
-
- /* if index_in_byte == 0 means that the byte to be written
- is aligned with the destination byte in packet
- (i.e. right_part is empty and left_part contains the
- entire byte to be written) => useless to compute right_part
- in this case.
- Useless also to write a value that is 0 (in OR with what
- contained in the packet will not change the current
- packet content) */
- if (index_in_byte != 0 && byte != 0) {
- packet[byte_index+1] |= getRightPart(byte, index_in_byte);
- }
- }
-
- /* read a byte (8 bits, not necessarly aligned with packet's emlements)
- from the packet.
- bits_num: total number of bits to be read
- read_bits_num: current number of read bits
- byte_index: the current byte from which the bits have to be read
- starting_pos: position from which starting to read
- */
- uint64_t readByte(unsigned int byte_index, unsigned int bits_num, unsigned int * read_bits_num, unsigned int starting_pos) {
-
- // remaining bits number
- unsigned int remaining_bits_num = bits_num - *read_bits_num;
- // index of the starting bit, relative to the current byte
- uint8_t index_in_byte = starting_pos % 8;
- // number of bits to be read from the current byte
- uint8_t to_be_read = getRelevantBitsNum(remaining_bits_num, index_in_byte);
-
- // compute the bit mask
- uint8_t mask = getMask(to_be_read, index_in_byte);
- // Notice that this can be actually avoided: 0b11111111 >> index_in_byte would create a mask
- // that removes only unwanted bits on the left, but the possible unwanted bits on the right
- // are then removed in the following if...else statements
-
- // compute the resulting byte
- uint64_t read_value = packet[byte_index] & mask; // this only removes left unwanted bits
-
- /* the shift needed by the read value in order to
- align it with its correct position in the final result
- (in order to be returned) */
- uint8_t shift = 0;
- if (index_in_byte == 0 && to_be_read < 8) { // few bits on the left of the byte
- shift = 8 - to_be_read;
- read_value = read_value >> shift; // shift right to remove unwanted bits on the right
- }
- else if (index_in_byte != 0 && to_be_read < 8) { // few bits in the middle of a byte
- shift = 8 - index_in_byte - to_be_read;
- read_value = read_value >> shift; // shift right to remove unwanted bits on the right
- }
- // few bits on the right of the byte or 8 bits (the entire byte)
- // in case also one of the above if is executed, shift here becomes 0
- shift = bits_num - *read_bits_num - to_be_read;
- read_value = read_value << shift; // shift left to put the read byte in its correct position in the result
-
- // update the total number of read bits
- *read_bits_num = *read_bits_num + to_be_read;
-
- return read_value;
- }
-
- // shift parameter var by i positions to the right
- uint8_t getLeftPart(uint8_t var, uint8_t i) {
- return var >> i;
- }
-
- // shift parameter var by 8-i positions to the left
- uint8_t getRightPart(uint8_t var, uint8_t i) {
- return var << (8-i);
- }
-
- // get number of relevant bits (to be read/written) for the current byte
- uint8_t getRelevantBitsNum(unsigned int bits_num, uint8_t index_in_byte) {
- uint8_t relevant_bits_num = 0;
- if (bits_num > 8) { // if more than 8 bits are remaining
- if (index_in_byte != 0) // if the wanted bits don't start from the first bit of the current byte
- relevant_bits_num = 8 - index_in_byte; // only get the right ones (i.e. 8 - bit_position_relative_to_current_byte)
- else
- relevant_bits_num = 8; // get the entire byte
- }
- else { // if less than 8 bits are remaining
- if (index_in_byte + bits_num > 8) // if the remaining bits are split among the current byte and the following one
- relevant_bits_num = 8 - index_in_byte; // just take the ones contained in the current byte
- else
- relevant_bits_num = bits_num; // else if the remaining bits are entirely contained in the current byte, get all of them
- }
-
- return relevant_bits_num;
- }
-
- /* get a bit mask, given how many bits you want to
- read/write and the starting position, relative
- to a byte (from 0 to 7)
- */
- uint8_t getMask(uint8_t relevant_bits_num, uint8_t index_in_byte) {
- // create a mask with relevant_bits_num set to 1 as least significant bits
- uint8_t mask = pow(2, relevant_bits_num) - 1;
- // shift the mask to align it with the requested position
- mask = mask << (8 - index_in_byte - relevant_bits_num);
-
- return mask;
- }
-
- /* get the position where to write, number of bits to be written
- and value to be written in the packet and check some conditions */
- template<typename T>
- bool checkParameters(int pos, int num, T val) {
- (void)val; // Avoid unused warning
- // check that T is a numerical type
- static_assert(std::is_arithmetic<T>::value, "The specified value is not a number (T must be an arithmetic type)");
- // check that T is uintX_t
- static_assert(std::is_unsigned<T>::value, "The specified value is not unsigned (T must be an unsigned integer type)");
-
- // check if nothing to write or negative number of bits
- if (num <= 0)
- return false;
-
- // check if indexes exceed packet dimension
- if (pos < 0 || ((unsigned int)(pos + num) > packet_size * 8))
- return false;
-
- // error if trying to set more bytes than the val variable has
- if (num / 8.0 > sizeof(T)) // num / 8.0 converted to float for correct result
- return false;
-
- return true;
- }
-
- // the packet to be created
- uint8_t * packet;
- // size of the packet array (in bytes)
- unsigned int packet_size;
-};
\ No newline at end of file
diff --git a/bitpacking/generator.py b/bitpacking/generator.py
deleted file mode 100644
index bed399211d9e5a8fb03e5758a0671abfed6fa164..0000000000000000000000000000000000000000
--- a/bitpacking/generator.py
+++ /dev/null
@@ -1,351 +0,0 @@
-#!/usr/bin/python3
-
-# Copyright (c) 2018 Skyward Experimental Rocketry
-# Authors: Luca Erbetta
-#
-# Permission is hereby granted, free of charge, to any person obtaining a copy
-# of this software and associated documentation files (the "Software"), to deal
-# in the Software without restriction, including without limitation the rights
-# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
-# copies of the Software, and to permit persons to whom the Software is
-# furnished to do so, subject to the following conditions:
-#
-# The above copyright notice and this permission notice shall be included in
-# all copies or substantial portions of the Software.
-#
-# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
-# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
-# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
-# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
-# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
-# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
-# THE SOFTWARE.
-#
-
-from googleapiclient.discovery import build
-from httplib2 import Http
-from oauth2client import file, client, tools
-
-import math
-import re
-import datetime
-import sys
-from os.path import join
-import os
-from string import Template
-
-SCOPES = "https://www.googleapis.com/auth/spreadsheets.readonly"
-
-service = None
-
-# Spreadsheet file used to generate the events. The can be found in the link
-# to the spreadsheet, for example:
-# https://docs.google.com/spreadsheets/d/184kR2OAD7yWV0fYJdiGUDmHmy5_prY3nr-XgNA0Uge0/
-# -->
-# 184kR2OAD7yWV0fYJdiGUDmHmy5_prY3nr-XgNA0Uge0
-spreadsheet_id = "1D5m5WrNXxAL8XA6CKyfe5JcQ5IRnpNHg5ZG5bzt5G4I"
-output_folder = "hermes"
-
-RANGE_FIELD_NAME = "{sheet_name}!A2:A"
-RANGE_FIELD_TYPE = "{sheet_name}!B2:B"
-RANGE_FIELD_SIZE = "{sheet_name}!C2:C"
-RANGE_FIELD_MIN = "{sheet_name}!D2:D"
-RANGE_FIELD_MAX = "{sheet_name}!E2:E"
-RANGE_REPEAT_NUM = "{sheet_name}!J1"
-RANGE_MAV_NAME = "{sheet_name}!J2"
-
-with open("templates/TelemetryPacker.h.template", "r") as template_file:
- tm_packer_template = Template(template_file.read())
-with open("templates/packFunction.cpp.template", "r") as template_file:
- pack_fun_template = Template(template_file.read())
-with open("templates/unpackFunction.cpp.template", "r") as template_file:
- unpack_fun_template = Template(template_file.read())
-with open("templates/ConversionFunctions.h.template", "r") as template_file:
- convfuns_template = Template(template_file.read())
-with open("templates/Packets.h.template", "r") as template_file:
- header_template = Template(template_file.read())
-
-
-def auth():
- try:
- store = file.Storage("store.json")
- creds = store.get()
- if not creds or creds.invalid:
- flow = client.flow_from_clientsecrets("credentials.json", SCOPES)
- creds = tools.run_flow(flow, store)
-
- global service
- service = build("sheets", "v4", http=creds.authorize(Http()))
- return True
- except:
- print("Authentication error:", sys.exc_info()[0])
- return False
-
-
-def listSheets():
- result = service.spreadsheets().get(spreadsheetId=spreadsheet_id).execute()
-
- return [x["properties"]["title"] for x in result["sheets"]]
-
-
-def loadPacketFromSheet(packet_name: str):
- # Strip 'Packet' at the end
- packet = {"name": packet_name[0:-6]}
-
- result = (
- service.spreadsheets()
- .values()
- .get(
- spreadsheetId=spreadsheet_id,
- range=RANGE_FIELD_NAME.format(sheet_name=packet_name),
- )
- .execute()
- )
- fields = [x[0] for x in result["values"]]
-
- result = (
- service.spreadsheets()
- .values()
- .get(
- spreadsheetId=spreadsheet_id,
- range=RANGE_FIELD_SIZE.format(sheet_name=packet_name),
- )
- .execute()
- )
- sizes = [int(x[0]) for x in result["values"]]
-
- result = (
- service.spreadsheets()
- .values()
- .get(
- spreadsheetId=spreadsheet_id,
- range=RANGE_FIELD_TYPE.format(sheet_name=packet_name),
- )
- .execute()
- )
- types = [x[0] for x in result["values"]]
-
- result = (
- service.spreadsheets()
- .values()
- .get(
- spreadsheetId=spreadsheet_id,
- range=RANGE_FIELD_MIN.format(sheet_name=packet_name),
- )
- .execute()
- )
- rmins = [float(x[0]) for x in result["values"]]
-
- result = (
- service.spreadsheets()
- .values()
- .get(
- spreadsheetId=spreadsheet_id,
- range=RANGE_FIELD_MAX.format(sheet_name=packet_name),
- )
- .execute()
- )
- rmaxs = [float(x[0]) for x in result["values"]]
-
-
-
- result = (
- service.spreadsheets()
- .values()
- .get(
- spreadsheetId=spreadsheet_id,
- range=RANGE_REPEAT_NUM.format(sheet_name=packet_name),
- )
- .execute()
- )
-
- indices = [0]
- for i in range(1, len(sizes)):
- indices += [indices[i - 1] + sizes[i - 1]]
-
- packet["repeat"] = int(result["values"][0][0])
-
- result = (
- service.spreadsheets()
- .values()
- .get(
- spreadsheetId=spreadsheet_id,
- range=RANGE_MAV_NAME.format(sheet_name=packet_name),
- )
- .execute()
- )
-
- indices = [0]
- for i in range(1, len(sizes)):
- indices += [indices[i - 1] + sizes[i - 1]]
-
- packet["mav_tm_name"] = result["values"][0][0]
-
- packet["fields"] = [
- {"name": f, "size": s, "index": i, "type": t, "range": (rmin, rmax)}
- for f, s, i, t, rmin, rmax in zip(fields, sizes, indices, types, rmins, rmaxs)
- ]
- packet["partial_size"] = sum(sizes)
- packet["total_size"] = math.ceil((sum(sizes) * packet["repeat"]) / 8)
- return packet
-
-
-def generatePackFunction(packet_data, field):
- convert_fun_template = Template(
- "${telemetry_name}Conversion::${field_name_ccase}ToBits"
- )
-
- subs = {}
-
- subs["max_index"] = packet_data["repeat"]
-
- subs["type"] = field["type"]
- name = field["name"].replace("_", " ").title().replace(" ", "")
- name = name[0].lower() + name[1:]
- subs["convert_fun"] = convert_fun_template.substitute(
- telemetry_name=packet_data["name"], field_name_ccase=name,
- )
- subs["field_name_lcase"] = field["name"].lower()
- subs["field_name_ccase"] = field["name"].replace("_", " ").title().replace(" ", "")
- subs["field_name_ucase"] = field["name"].upper()
- subs["mav_tm_name"] = packet_data["mav_tm_name"]
-
- return pack_fun_template.substitute(**subs)
-
-
-def generateUnpackFunction(packet_data, field):
- convert_fun_template = Template(
- "${telemetry_name}Conversion::bitsTo${field_name_ccase}"
- )
-
- subs = {}
- subs["max_index"] = packet_data["repeat"]
-
- subs["type"] = field["type"]
- subs["convert_fun"] = convert_fun_template.substitute(
- telemetry_name=packet_data["name"],
- field_name_ccase=field["name"].replace("_", " ").title().replace(" ", ""),
- )
- subs["field_name_lcase"] = field["name"].lower()
- subs["field_name_ccase"] = field["name"].replace("_", " ").title().replace(" ", "")
- subs["field_name_ucase"] = field["name"].upper()
- subs["mav_tm_name"] = packet_data["mav_tm_name"]
-
- return unpack_fun_template.substitute(**subs)
-
-
-def generatePackerClass(packet_data, output_folder):
- index_template = Template(" INDEX_$field_name = $index")
- size_template = Template(" SIZE_$field_name = $size")
-
- indices = ""
- sizes = ""
- pack_funcs = ""
- unpack_funcs = ""
- for f in packet_data["fields"]:
- indices += index_template.substitute(field_name=f["name"].upper(), index=f["index"])
- sizes += size_template.substitute(field_name=f["name"].upper(), size=f["size"])
-
- if f != packet_data["fields"][-1]:
- indices += ",\n"
- sizes += ",\n"
-
- pack_funcs += generatePackFunction(packet_data, f)
- unpack_funcs += generateUnpackFunction(packet_data, f)
-
- out = tm_packer_template.substitute(
- mav_tm_name=packet_data["mav_tm_name"],
- telemetry_name_ccase=packet_data["name"],
- tm_total_size=packet_data["total_size"],
- tm_partial_size=packet_data["partial_size"],
- field_indices=indices,
- field_sizes=sizes,
- pack_functions=pack_funcs,
- unpack_functions=unpack_funcs,
- folder=output_folder
- )
-
- with open(join(output_folder, packet_data["name"] + "Packer.h"), "w") as out_file:
- out_file.write(out)
-
-
-def generateConversionFunctions(packet_data):
- class_template = Template(
- "\nclass ${telemetry_name_ccase}Conversion\n{\npublic:\n $functions\n};\n\n\n"
- )
-
- frombits_template = Template(
- "\n static $type bitsTo${field_name_ccase}(uint64_t bits)\n "
- + "{\n return ($type)bits;\n }\n"
- )
-
- tobits_template = Template(
- "\n static uint64_t ${field_name_ccase}ToBits($type $field_name_lcase)"
- + "\n {\n return (uint64_t)$field_name_lcase;\n }\n\n"
- )
-
- frombits_template_ranged = Template(
- "\n static $type bitsTo${field_name_ccase}(uint64_t bits)\n "
- + "{\n return undiscretizeRange<$type>(bits, $rmin, $rmax, $res);\n }\n"
- )
-
- tobits_template_ranged = Template(
- "\n static uint64_t ${field_name_ccase}ToBits($type $field_name_lcase)"
- + "\n {\n return discretizeRange<$type>($field_name_lcase, $rmin, $rmax, $res);\n }\n\n"
- )
-
- funs = ""
- for field in packet_data["fields"]:
- subs = {}
- subs["type"] = field["type"]
- subs["field_name_lcase"] = field["name"].lower()
- subs["field_name_ccase"] = field["name"].replace("_", " ").title().replace(" ", "")
- subs["field_name_ucase"] = field["name"].upper()
- subs["rmin"] = field["range"][0]
- subs["rmax"] = field["range"][1]
- subs["res"] = 2**field["size"]
- if subs["rmax"] - subs["rmin"] != 0:
- funs += frombits_template_ranged.substitute(**subs)
-
- subs["field_name_ccase"] = (
- subs["field_name_ccase"][0].lower() + subs["field_name_ccase"][1:]
- )
- funs += tobits_template_ranged.substitute(**subs)
- else:
- funs += frombits_template.substitute(**subs)
-
- subs["field_name_ccase"] = (
- subs["field_name_ccase"][0].lower() + subs["field_name_ccase"][1:]
- )
- funs += tobits_template.substitute(**subs)
-
- return class_template.substitute(
- functions=funs, telemetry_name_ccase=packet_data["name"]
- )
-
-
-print("Skyward telemetry packet generator")
-print("Google sheets API auth in progress...")
-
-if auth():
- print("Auth successfull.")
-else:
- print("Authentication failed.")
- exit()
-
-sheets = listSheets()
-packet_sheets = [x for x in sheets if x.endswith("Packet")]
-
-includes = ""
-conversion_classes = ""
-for p in packet_sheets:
- data = loadPacketFromSheet(p)
- generatePackerClass(data, output_folder)
- conversion_classes += generateConversionFunctions(data)
- includes += "#include \"{}\"\n".format(join("bitpacking",output_folder, data["name"] + "Packer.h"))
-
-with open(join(output_folder, "ConversionFuncions_generated.h"), "w") as out_file:
- out_file.write(convfuns_template.substitute(classes=conversion_classes))
-
-with open(join(output_folder, output_folder.title() + "Packets.h"), "w") as out_file:
- out_file.write(header_template.substitute(includes=includes))
diff --git a/bitpacking/hermes/ConversionFunctions.h b/bitpacking/hermes/ConversionFunctions.h
deleted file mode 100644
index 0304741009086fc35c323eb6583ef9e5baf84c27..0000000000000000000000000000000000000000
--- a/bitpacking/hermes/ConversionFunctions.h
+++ /dev/null
@@ -1,544 +0,0 @@
-/**
- * Copyright (c) 2019 Skyward Experimental Rocketry
- * Authors: Luca Erbetta
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-#include <cstdint>
-#include <type_traits>
-
-template<typename T>
-inline uint64_t discretizeRange(T value, T min, T max, unsigned int resolution)
-{
- static_assert(std::is_arithmetic<T>::value, "T must be an arithmetic type (float, int, etc)");
-
- if (value < min)
- {
- return 0;
- }
- else if (value > max)
- {
- return resolution - 1;
- }
-
- return static_cast<uint64_t>((value - min) * resolution / (max - min));
-
-}
-
-template <typename T>
-inline T undiscretizeRange(uint64_t value, T min, T max,
- unsigned int resolution)
-{
- static_assert(std::is_arithmetic<T>::value, "T must be an arithmetic type (float, int, etc)");
-
- return static_cast<T>(value * (max - min) / resolution + min);
-}
-
-
-
-class HighRateTMConversion
-{
-public:
-
- static long long bitsToTimestamp(uint64_t bits)
- {
- return (long long)bits;
- }
-
- static uint64_t timestampToBits(long long timestamp)
- {
- return (uint64_t)timestamp;
- }
-
-
- static float bitsToPressureAda(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, 50000.0, 105000.0, 4096);
- }
-
- static uint64_t pressureAdaToBits(float pressure_ada)
- {
- return discretizeRange<float>(pressure_ada, 50000.0, 105000.0, 4096);
- }
-
-
- static float bitsToPressureDigi(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, 50000.0, 105000.0, 8192);
- }
-
- static uint64_t pressureDigiToBits(float pressure_digi)
- {
- return discretizeRange<float>(pressure_digi, 50000.0, 105000.0, 8192);
- }
-
-
- static float bitsToMslAltitude(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, 0.0, 4096.0, 4096);
- }
-
- static uint64_t mslAltitudeToBits(float msl_altitude)
- {
- return discretizeRange<float>(msl_altitude, 0.0, 4096.0, 4096);
- }
-
-
- static float bitsToAglAltitude(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, -100.0, 3000.0, 512);
- }
-
- static uint64_t aglAltitudeToBits(float agl_altitude)
- {
- return discretizeRange<float>(agl_altitude, -100.0, 3000.0, 512);
- }
-
-
- static float bitsToVertSpeed(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, -300.0, 300.0, 1024);
- }
-
- static uint64_t vertSpeedToBits(float vert_speed)
- {
- return discretizeRange<float>(vert_speed, -300.0, 300.0, 1024);
- }
-
-
- static float bitsToVertSpeed2(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, -256.0, 256.0, 1024);
- }
-
- static uint64_t vertSpeed2ToBits(float vert_speed_2)
- {
- return discretizeRange<float>(vert_speed_2, -256.0, 256.0, 1024);
- }
-
-
- static float bitsToAccX(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, -157.0, 157.0, 2048);
- }
-
- static uint64_t accXToBits(float acc_x)
- {
- return discretizeRange<float>(acc_x, -157.0, 157.0, 2048);
- }
-
-
- static float bitsToAccY(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, -157.0, 157.0, 2048);
- }
-
- static uint64_t accYToBits(float acc_y)
- {
- return discretizeRange<float>(acc_y, -157.0, 157.0, 2048);
- }
-
-
- static float bitsToAccZ(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, -157.0, 157.0, 2048);
- }
-
- static uint64_t accZToBits(float acc_z)
- {
- return discretizeRange<float>(acc_z, -157.0, 157.0, 2048);
- }
-
-
- static float bitsToGyroX(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, -2000.0, 2000.0, 2048);
- }
-
- static uint64_t gyroXToBits(float gyro_x)
- {
- return discretizeRange<float>(gyro_x, -2000.0, 2000.0, 2048);
- }
-
-
- static float bitsToGyroY(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, -2000.0, 2000.0, 2048);
- }
-
- static uint64_t gyroYToBits(float gyro_y)
- {
- return discretizeRange<float>(gyro_y, -2000.0, 2000.0, 2048);
- }
-
-
- static float bitsToGyroZ(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, -2000.0, 2000.0, 2048);
- }
-
- static uint64_t gyroZToBits(float gyro_z)
- {
- return discretizeRange<float>(gyro_z, -2000.0, 2000.0, 2048);
- }
-
-
- static double bitsToGpsLat(uint64_t bits)
- {
- return undiscretizeRange<double>(bits, 41.777944, 41.835281, 2048);
- }
-
- static uint64_t gpsLatToBits(double gps_lat)
- {
- return discretizeRange<double>(gps_lat, 41.777944, 41.835281, 2048);
- }
-
-
- static double bitsToGpsLon(uint64_t bits)
- {
- return undiscretizeRange<double>(bits, 14.019528, 14.094634, 2048);
- }
-
- static uint64_t gpsLonToBits(double gps_lon)
- {
- return discretizeRange<double>(gps_lon, 14.019528, 14.094634, 2048);
- }
-
-
- static float bitsToGpsAlt(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, 0.0, 5120.0, 1024);
- }
-
- static uint64_t gpsAltToBits(float gps_alt)
- {
- return discretizeRange<float>(gps_alt, 0.0, 5120.0, 1024);
- }
-
-
- static float bitsToTemperature(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, -10.0, 70.0, 128);
- }
-
- static uint64_t temperatureToBits(float temperature)
- {
- return discretizeRange<float>(temperature, -10.0, 70.0, 128);
- }
-
-
- static uint8_t bitsToFmmState(uint64_t bits)
- {
- return (uint8_t)bits;
- }
-
- static uint64_t fmmStateToBits(uint8_t fmm_state)
- {
- return (uint64_t)fmm_state;
- }
-
-
- static uint8_t bitsToDplState(uint64_t bits)
- {
- return (uint8_t)bits;
- }
-
- static uint64_t dplStateToBits(uint8_t dpl_state)
- {
- return (uint64_t)dpl_state;
- }
-
-
- static uint8_t bitsToPinLaunch(uint64_t bits)
- {
- return (uint8_t)bits;
- }
-
- static uint64_t pinLaunchToBits(uint8_t pin_launch)
- {
- return (uint64_t)pin_launch;
- }
-
-
- static uint8_t bitsToPinNosecone(uint64_t bits)
- {
- return (uint8_t)bits;
- }
-
- static uint64_t pinNoseconeToBits(uint8_t pin_nosecone)
- {
- return (uint64_t)pin_nosecone;
- }
-
-
- static uint8_t bitsToGpsFix(uint64_t bits)
- {
- return (uint8_t)bits;
- }
-
- static uint64_t gpsFixToBits(uint8_t gps_fix)
- {
- return (uint64_t)gps_fix;
- }
-
-
-};
-
-
-
-class LowRateTMConversion
-{
-public:
-
- static long long bitsToLiftoffTs(uint64_t bits)
- {
- return (long long)bits;
- }
-
- static uint64_t liftoffTsToBits(long long liftoff_ts)
- {
- return (uint64_t)liftoff_ts;
- }
-
-
- static long long bitsToLiftoffMaxAccTs(uint64_t bits)
- {
- return (long long)bits;
- }
-
- static uint64_t liftoffMaxAccTsToBits(long long liftoff_max_acc_ts)
- {
- return (uint64_t)liftoff_max_acc_ts;
- }
-
-
- static float bitsToLiftoffMaxAcc(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, -157.0, 157.0, 2048);
- }
-
- static uint64_t liftoffMaxAccToBits(float liftoff_max_acc)
- {
- return discretizeRange<float>(liftoff_max_acc, -157.0, 157.0, 2048);
- }
-
-
- static long long bitsToMaxZspeedTs(uint64_t bits)
- {
- return (long long)bits;
- }
-
- static uint64_t maxZspeedTsToBits(long long max_zspeed_ts)
- {
- return (uint64_t)max_zspeed_ts;
- }
-
-
- static float bitsToMaxZspeed(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, -512.0, 512.0, 1024);
- }
-
- static uint64_t maxZspeedToBits(float max_zspeed)
- {
- return discretizeRange<float>(max_zspeed, -512.0, 512.0, 1024);
- }
-
-
- static float bitsToMaxSpeedAltitude(uint64_t bits)
- {
- return (float)bits;
- }
-
- static uint64_t maxSpeedAltitudeToBits(float max_speed_altitude)
- {
- return (uint64_t)max_speed_altitude;
- }
-
-
- static long long bitsToApogeeTs(uint64_t bits)
- {
- return (long long)bits;
- }
-
- static uint64_t apogeeTsToBits(long long apogee_ts)
- {
- return (uint64_t)apogee_ts;
- }
-
-
- static float bitsToNxpMinPressure(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, 50000.0, 100000.0, 4096);
- }
-
- static uint64_t nxpMinPressureToBits(float nxp_min_pressure)
- {
- return discretizeRange<float>(nxp_min_pressure, 50000.0, 100000.0, 4096);
- }
-
-
- static float bitsToHwMinPressure(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, 50000.0, 100000.0, 4096);
- }
-
- static uint64_t hwMinPressureToBits(float hw_min_pressure)
- {
- return discretizeRange<float>(hw_min_pressure, 50000.0, 100000.0, 4096);
- }
-
-
- static float bitsToKalmanMinPressure(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, 50000.0, 100000.0, 4096);
- }
-
- static uint64_t kalmanMinPressureToBits(float kalman_min_pressure)
- {
- return discretizeRange<float>(kalman_min_pressure, 50000.0, 100000.0, 4096);
- }
-
-
- static float bitsToDigitalMinPressure(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, 50000.0, 100000.0, 8192);
- }
-
- static uint64_t digitalMinPressureToBits(float digital_min_pressure)
- {
- return discretizeRange<float>(digital_min_pressure, 50000.0, 100000.0, 8192);
- }
-
-
- static float bitsToBaroMaxAltitutde(uint64_t bits)
- {
- return (float)bits;
- }
-
- static uint64_t baroMaxAltitutdeToBits(float baro_max_altitutde )
- {
- return (uint64_t)baro_max_altitutde ;
- }
-
-
- static float bitsToGpsMaxAltitude(uint64_t bits)
- {
- return (float)bits;
- }
-
- static uint64_t gpsMaxAltitudeToBits(float gps_max_altitude)
- {
- return (uint64_t)gps_max_altitude;
- }
-
-
- static float bitsToApogeeLat(uint64_t bits)
- {
- return (float)bits;
- }
-
- static uint64_t apogeeLatToBits(float apogee_lat)
- {
- return (uint64_t)apogee_lat;
- }
-
-
- static float bitsToApogeeLon(uint64_t bits)
- {
- return (float)bits;
- }
-
- static uint64_t apogeeLonToBits(float apogee_lon)
- {
- return (uint64_t)apogee_lon;
- }
-
-
- static long long bitsToDrogueDplTs(uint64_t bits)
- {
- return (long long)bits;
- }
-
- static uint64_t drogueDplTsToBits(long long drogue_dpl_ts)
- {
- return (uint64_t)drogue_dpl_ts;
- }
-
-
- static float bitsToDrogueDplMaxAcc(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, -157.0, 157.0, 2048);
- }
-
- static uint64_t drogueDplMaxAccToBits(float drogue_dpl_max_acc)
- {
- return discretizeRange<float>(drogue_dpl_max_acc, -157.0, 157.0, 2048);
- }
-
-
- static long long bitsToMainDplTs(uint64_t bits)
- {
- return (long long)bits;
- }
-
- static uint64_t mainDplTsToBits(long long main_dpl_ts)
- {
- return (uint64_t)main_dpl_ts;
- }
-
-
- static float bitsToMainDplAltitude(uint64_t bits)
- {
- return (float)bits;
- }
-
- static uint64_t mainDplAltitudeToBits(float main_dpl_altitude)
- {
- return (uint64_t)main_dpl_altitude;
- }
-
-
- static float bitsToMainDplZspeed(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, -512.0, 512.0, 1024);
- }
-
- static uint64_t mainDplZspeedToBits(float main_dpl_zspeed)
- {
- return discretizeRange<float>(main_dpl_zspeed, -512.0, 512.0, 1024);
- }
-
-
- static float bitsToMainDplAcc(uint64_t bits)
- {
- return undiscretizeRange<float>(bits, -16.0, 16.0, 2048);
- }
-
- static uint64_t mainDplAccToBits(float main_dpl_acc)
- {
- return discretizeRange<float>(main_dpl_acc, -16.0, 16.0, 2048);
- }
-
-
-};
-
-
diff --git a/bitpacking/hermes/HermesPackets.h b/bitpacking/hermes/HermesPackets.h
deleted file mode 100644
index 2f14e50d978d70960758e63f52d1836fb72b8c81..0000000000000000000000000000000000000000
--- a/bitpacking/hermes/HermesPackets.h
+++ /dev/null
@@ -1,27 +0,0 @@
-/**
- * Copyright (c) 2019 Skyward Experimental Rocketry
- * Authors: Luca Erbetta
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include "bitpacking/hermes/HighRateTMPacker.h"
-#include "bitpacking/hermes/LowRateTMPacker.h"
diff --git a/bitpacking/hermes/HighRateTMPacker.h b/bitpacking/hermes/HighRateTMPacker.h
deleted file mode 100644
index ef9f3f5f7cc07d3fa4c669a54844653632a94a99..0000000000000000000000000000000000000000
--- a/bitpacking/hermes/HighRateTMPacker.h
+++ /dev/null
@@ -1,985 +0,0 @@
-/**
- * Copyright (c) 2019 Skyward Experimental Rocketry
- * Authors: Luca Conterio, Luca Erbetta
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include "bitpacking/BitPacker.h"
-#include "mavlink_lib/hermes/mavlink.h"
-#include "bitpacking/hermes/ConversionFunctions.h"
-
-class HighRateTMPacker
-{
-public:
- static constexpr int HR_TM_PACKET_SIZE = 104;
- static constexpr int HR_TM_SINGLE_PACKET_SIZE_BITS = 208;
-
- static_assert(MAVLINK_MSG_HR_TM_FIELD_PAYLOAD_LEN == HR_TM_PACKET_SIZE,
- "Payload size mismatch! Mavlnk payload size differes from declared size. Maybe your mavlink definitions are outdated?");
-
-
-
-
- HighRateTMPacker(uint8_t *packet) : packet(packet), bitpacker(packet, HR_TM_PACKET_SIZE)
- {
- }
-
-
- bool packTimestamp(long long timestamp, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::timestampToBits(timestamp);
-
- return bitpacker.pack(
- INDEX_TIMESTAMP + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_TIMESTAMP, bits);
- }
-
- bool packPressureAda(float pressure_ada, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::pressureAdaToBits(pressure_ada);
-
- return bitpacker.pack(
- INDEX_PRESSURE_ADA + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_PRESSURE_ADA, bits);
- }
-
- bool packPressureDigi(float pressure_digi, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::pressureDigiToBits(pressure_digi);
-
- return bitpacker.pack(
- INDEX_PRESSURE_DIGI + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_PRESSURE_DIGI, bits);
- }
-
- bool packMslAltitude(float msl_altitude, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::mslAltitudeToBits(msl_altitude);
-
- return bitpacker.pack(
- INDEX_MSL_ALTITUDE + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_MSL_ALTITUDE, bits);
- }
-
- bool packAglAltitude(float agl_altitude, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::aglAltitudeToBits(agl_altitude);
-
- return bitpacker.pack(
- INDEX_AGL_ALTITUDE + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_AGL_ALTITUDE, bits);
- }
-
- bool packVertSpeed(float vert_speed, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::vertSpeedToBits(vert_speed);
-
- return bitpacker.pack(
- INDEX_VERT_SPEED + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_VERT_SPEED, bits);
- }
-
- bool packVertSpeed2(float vert_speed_2, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::vertSpeed2ToBits(vert_speed_2);
-
- return bitpacker.pack(
- INDEX_VERT_SPEED_2 + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_VERT_SPEED_2, bits);
- }
-
- bool packAccX(float acc_x, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::accXToBits(acc_x);
-
- return bitpacker.pack(
- INDEX_ACC_X + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_ACC_X, bits);
- }
-
- bool packAccY(float acc_y, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::accYToBits(acc_y);
-
- return bitpacker.pack(
- INDEX_ACC_Y + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_ACC_Y, bits);
- }
-
- bool packAccZ(float acc_z, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::accZToBits(acc_z);
-
- return bitpacker.pack(
- INDEX_ACC_Z + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_ACC_Z, bits);
- }
-
- bool packGyroX(float gyro_x, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::gyroXToBits(gyro_x);
-
- return bitpacker.pack(
- INDEX_GYRO_X + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_GYRO_X, bits);
- }
-
- bool packGyroY(float gyro_y, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::gyroYToBits(gyro_y);
-
- return bitpacker.pack(
- INDEX_GYRO_Y + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_GYRO_Y, bits);
- }
-
- bool packGyroZ(float gyro_z, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::gyroZToBits(gyro_z);
-
- return bitpacker.pack(
- INDEX_GYRO_Z + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_GYRO_Z, bits);
- }
-
- bool packGpsLat(double gps_lat, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::gpsLatToBits(gps_lat);
-
- return bitpacker.pack(
- INDEX_GPS_LAT + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_GPS_LAT, bits);
- }
-
- bool packGpsLon(double gps_lon, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::gpsLonToBits(gps_lon);
-
- return bitpacker.pack(
- INDEX_GPS_LON + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_GPS_LON, bits);
- }
-
- bool packGpsAlt(float gps_alt, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::gpsAltToBits(gps_alt);
-
- return bitpacker.pack(
- INDEX_GPS_ALT + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_GPS_ALT, bits);
- }
-
- bool packTemperature(float temperature, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::temperatureToBits(temperature);
-
- return bitpacker.pack(
- INDEX_TEMPERATURE + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_TEMPERATURE, bits);
- }
-
- bool packFmmState(uint8_t fmm_state, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::fmmStateToBits(fmm_state);
-
- return bitpacker.pack(
- INDEX_FMM_STATE + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_FMM_STATE, bits);
- }
-
- bool packDplState(uint8_t dpl_state, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::dplStateToBits(dpl_state);
-
- return bitpacker.pack(
- INDEX_DPL_STATE + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_DPL_STATE, bits);
- }
-
- bool packPinLaunch(uint8_t pin_launch, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::pinLaunchToBits(pin_launch);
-
- return bitpacker.pack(
- INDEX_PIN_LAUNCH + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_PIN_LAUNCH, bits);
- }
-
- bool packPinNosecone(uint8_t pin_nosecone, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::pinNoseconeToBits(pin_nosecone);
-
- return bitpacker.pack(
- INDEX_PIN_NOSECONE + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_PIN_NOSECONE, bits);
- }
-
- bool packGpsFix(uint8_t gps_fix, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = HighRateTMConversion::gpsFixToBits(gps_fix);
-
- return bitpacker.pack(
- INDEX_GPS_FIX + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_GPS_FIX, bits);
- }
-
-
-
- bool unpackTimestamp(long long* timestamp, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_TIMESTAMP + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_TIMESTAMP, &bits);
-
- if(success)
- {
- *timestamp = HighRateTMConversion::bitsToTimestamp(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackPressureAda(float* pressure_ada, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_PRESSURE_ADA + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_PRESSURE_ADA, &bits);
-
- if(success)
- {
- *pressure_ada = HighRateTMConversion::bitsToPressureAda(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackPressureDigi(float* pressure_digi, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_PRESSURE_DIGI + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_PRESSURE_DIGI, &bits);
-
- if(success)
- {
- *pressure_digi = HighRateTMConversion::bitsToPressureDigi(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackMslAltitude(float* msl_altitude, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_MSL_ALTITUDE + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_MSL_ALTITUDE, &bits);
-
- if(success)
- {
- *msl_altitude = HighRateTMConversion::bitsToMslAltitude(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackAglAltitude(float* agl_altitude, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_AGL_ALTITUDE + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_AGL_ALTITUDE, &bits);
-
- if(success)
- {
- *agl_altitude = HighRateTMConversion::bitsToAglAltitude(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackVertSpeed(float* vert_speed, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_VERT_SPEED + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_VERT_SPEED, &bits);
-
- if(success)
- {
- *vert_speed = HighRateTMConversion::bitsToVertSpeed(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackVertSpeed2(float* vert_speed_2, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_VERT_SPEED_2 + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_VERT_SPEED_2, &bits);
-
- if(success)
- {
- *vert_speed_2 = HighRateTMConversion::bitsToVertSpeed2(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackAccX(float* acc_x, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_ACC_X + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_ACC_X, &bits);
-
- if(success)
- {
- *acc_x = HighRateTMConversion::bitsToAccX(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackAccY(float* acc_y, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_ACC_Y + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_ACC_Y, &bits);
-
- if(success)
- {
- *acc_y = HighRateTMConversion::bitsToAccY(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackAccZ(float* acc_z, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_ACC_Z + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_ACC_Z, &bits);
-
- if(success)
- {
- *acc_z = HighRateTMConversion::bitsToAccZ(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackGyroX(float* gyro_x, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_GYRO_X + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_GYRO_X, &bits);
-
- if(success)
- {
- *gyro_x = HighRateTMConversion::bitsToGyroX(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackGyroY(float* gyro_y, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_GYRO_Y + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_GYRO_Y, &bits);
-
- if(success)
- {
- *gyro_y = HighRateTMConversion::bitsToGyroY(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackGyroZ(float* gyro_z, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_GYRO_Z + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_GYRO_Z, &bits);
-
- if(success)
- {
- *gyro_z = HighRateTMConversion::bitsToGyroZ(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackGpsLat(double* gps_lat, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_GPS_LAT + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_GPS_LAT, &bits);
-
- if(success)
- {
- *gps_lat = HighRateTMConversion::bitsToGpsLat(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackGpsLon(double* gps_lon, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_GPS_LON + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_GPS_LON, &bits);
-
- if(success)
- {
- *gps_lon = HighRateTMConversion::bitsToGpsLon(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackGpsAlt(float* gps_alt, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_GPS_ALT + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_GPS_ALT, &bits);
-
- if(success)
- {
- *gps_alt = HighRateTMConversion::bitsToGpsAlt(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackTemperature(float* temperature, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_TEMPERATURE + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_TEMPERATURE, &bits);
-
- if(success)
- {
- *temperature = HighRateTMConversion::bitsToTemperature(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackFmmState(uint8_t* fmm_state, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_FMM_STATE + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_FMM_STATE, &bits);
-
- if(success)
- {
- *fmm_state = HighRateTMConversion::bitsToFmmState(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackDplState(uint8_t* dpl_state, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_DPL_STATE + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_DPL_STATE, &bits);
-
- if(success)
- {
- *dpl_state = HighRateTMConversion::bitsToDplState(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackPinLaunch(uint8_t* pin_launch, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_PIN_LAUNCH + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_PIN_LAUNCH, &bits);
-
- if(success)
- {
- *pin_launch = HighRateTMConversion::bitsToPinLaunch(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackPinNosecone(uint8_t* pin_nosecone, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_PIN_NOSECONE + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_PIN_NOSECONE, &bits);
-
- if(success)
- {
- *pin_nosecone = HighRateTMConversion::bitsToPinNosecone(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackGpsFix(uint8_t* gps_fix, size_t packet_index)
- {
- if(packet_index >= 4)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_GPS_FIX + packet_index * HR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_GPS_FIX, &bits);
-
- if(success)
- {
- *gps_fix = HighRateTMConversion::bitsToGpsFix(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
-
-private:
- enum FieldIndex
- {
- INDEX_TIMESTAMP = 0,
- INDEX_PRESSURE_ADA = 25,
- INDEX_PRESSURE_DIGI = 37,
- INDEX_MSL_ALTITUDE = 50,
- INDEX_AGL_ALTITUDE = 62,
- INDEX_VERT_SPEED = 71,
- INDEX_VERT_SPEED_2 = 81,
- INDEX_ACC_X = 91,
- INDEX_ACC_Y = 102,
- INDEX_ACC_Z = 113,
- INDEX_GYRO_X = 124,
- INDEX_GYRO_Y = 135,
- INDEX_GYRO_Z = 146,
- INDEX_GPS_LAT = 157,
- INDEX_GPS_LON = 168,
- INDEX_GPS_ALT = 179,
- INDEX_TEMPERATURE = 189,
- INDEX_FMM_STATE = 196,
- INDEX_DPL_STATE = 201,
- INDEX_PIN_LAUNCH = 205,
- INDEX_PIN_NOSECONE = 206,
- INDEX_GPS_FIX = 207
- };
-
- enum FieldSize
- {
- SIZE_TIMESTAMP = 25,
- SIZE_PRESSURE_ADA = 12,
- SIZE_PRESSURE_DIGI = 13,
- SIZE_MSL_ALTITUDE = 12,
- SIZE_AGL_ALTITUDE = 9,
- SIZE_VERT_SPEED = 10,
- SIZE_VERT_SPEED_2 = 10,
- SIZE_ACC_X = 11,
- SIZE_ACC_Y = 11,
- SIZE_ACC_Z = 11,
- SIZE_GYRO_X = 11,
- SIZE_GYRO_Y = 11,
- SIZE_GYRO_Z = 11,
- SIZE_GPS_LAT = 11,
- SIZE_GPS_LON = 11,
- SIZE_GPS_ALT = 10,
- SIZE_TEMPERATURE = 7,
- SIZE_FMM_STATE = 5,
- SIZE_DPL_STATE = 4,
- SIZE_PIN_LAUNCH = 1,
- SIZE_PIN_NOSECONE = 1,
- SIZE_GPS_FIX = 1
- };
-
- uint8_t *packet;
- BitPacker bitpacker;
-};
\ No newline at end of file
diff --git a/bitpacking/hermes/LowRateTMPacker.h b/bitpacking/hermes/LowRateTMPacker.h
deleted file mode 100644
index cd2b41637355a99a7c132dfdd5f4e29e14af9c3f..0000000000000000000000000000000000000000
--- a/bitpacking/hermes/LowRateTMPacker.h
+++ /dev/null
@@ -1,943 +0,0 @@
-/**
- * Copyright (c) 2019 Skyward Experimental Rocketry
- * Authors: Luca Conterio, Luca Erbetta
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include "bitpacking/BitPacker.h"
-#include "mavlink_lib/hermes/mavlink.h"
-#include "bitpacking/hermes/ConversionFunctions.h"
-
-class LowRateTMPacker
-{
-public:
- static constexpr int LR_TM_PACKET_SIZE = 40;
- static constexpr int LR_TM_SINGLE_PACKET_SIZE_BITS = 319;
-
- static_assert(MAVLINK_MSG_LR_TM_FIELD_PAYLOAD_LEN == LR_TM_PACKET_SIZE,
- "Payload size mismatch! Mavlnk payload size differes from declared size. Maybe your mavlink definitions are outdated?");
-
-
-
-
- LowRateTMPacker(uint8_t *packet) : packet(packet), bitpacker(packet, LR_TM_PACKET_SIZE)
- {
- }
-
-
- bool packLiftoffTs(long long liftoff_ts, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::liftoffTsToBits(liftoff_ts);
-
- return bitpacker.pack(
- INDEX_LIFTOFF_TS + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_LIFTOFF_TS, bits);
- }
-
- bool packLiftoffMaxAccTs(long long liftoff_max_acc_ts, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::liftoffMaxAccTsToBits(liftoff_max_acc_ts);
-
- return bitpacker.pack(
- INDEX_LIFTOFF_MAX_ACC_TS + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_LIFTOFF_MAX_ACC_TS, bits);
- }
-
- bool packLiftoffMaxAcc(float liftoff_max_acc, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::liftoffMaxAccToBits(liftoff_max_acc);
-
- return bitpacker.pack(
- INDEX_LIFTOFF_MAX_ACC + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_LIFTOFF_MAX_ACC, bits);
- }
-
- bool packMaxZspeedTs(long long max_zspeed_ts, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::maxZspeedTsToBits(max_zspeed_ts);
-
- return bitpacker.pack(
- INDEX_MAX_ZSPEED_TS + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_MAX_ZSPEED_TS, bits);
- }
-
- bool packMaxZspeed(float max_zspeed, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::maxZspeedToBits(max_zspeed);
-
- return bitpacker.pack(
- INDEX_MAX_ZSPEED + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_MAX_ZSPEED, bits);
- }
-
- bool packMaxSpeedAltitude(float max_speed_altitude, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::maxSpeedAltitudeToBits(max_speed_altitude);
-
- return bitpacker.pack(
- INDEX_MAX_SPEED_ALTITUDE + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_MAX_SPEED_ALTITUDE, bits);
- }
-
- bool packApogeeTs(long long apogee_ts, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::apogeeTsToBits(apogee_ts);
-
- return bitpacker.pack(
- INDEX_APOGEE_TS + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_APOGEE_TS, bits);
- }
-
- bool packNxpMinPressure(float nxp_min_pressure, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::nxpMinPressureToBits(nxp_min_pressure);
-
- return bitpacker.pack(
- INDEX_NXP_MIN_PRESSURE + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_NXP_MIN_PRESSURE, bits);
- }
-
- bool packHwMinPressure(float hw_min_pressure, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::hwMinPressureToBits(hw_min_pressure);
-
- return bitpacker.pack(
- INDEX_HW_MIN_PRESSURE + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_HW_MIN_PRESSURE, bits);
- }
-
- bool packKalmanMinPressure(float kalman_min_pressure, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::kalmanMinPressureToBits(kalman_min_pressure);
-
- return bitpacker.pack(
- INDEX_KALMAN_MIN_PRESSURE + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_KALMAN_MIN_PRESSURE, bits);
- }
-
- bool packDigitalMinPressure(float digital_min_pressure, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::digitalMinPressureToBits(digital_min_pressure);
-
- return bitpacker.pack(
- INDEX_DIGITAL_MIN_PRESSURE + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_DIGITAL_MIN_PRESSURE, bits);
- }
-
- bool packBaroMaxAltitutde(float baro_max_altitutde , size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::baroMaxAltitutdeToBits(baro_max_altitutde );
-
- return bitpacker.pack(
- INDEX_BARO_MAX_ALTITUTDE + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_BARO_MAX_ALTITUTDE , bits);
- }
-
- bool packGpsMaxAltitude(float gps_max_altitude, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::gpsMaxAltitudeToBits(gps_max_altitude);
-
- return bitpacker.pack(
- INDEX_GPS_MAX_ALTITUDE + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_GPS_MAX_ALTITUDE, bits);
- }
-
- bool packApogeeLat(float apogee_lat, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::apogeeLatToBits(apogee_lat);
-
- return bitpacker.pack(
- INDEX_APOGEE_LAT + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_APOGEE_LAT, bits);
- }
-
- bool packApogeeLon(float apogee_lon, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::apogeeLonToBits(apogee_lon);
-
- return bitpacker.pack(
- INDEX_APOGEE_LON + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_APOGEE_LON, bits);
- }
-
- bool packDrogueDplTs(long long drogue_dpl_ts, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::drogueDplTsToBits(drogue_dpl_ts);
-
- return bitpacker.pack(
- INDEX_DROGUE_DPL_TS + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_DROGUE_DPL_TS, bits);
- }
-
- bool packDrogueDplMaxAcc(float drogue_dpl_max_acc, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::drogueDplMaxAccToBits(drogue_dpl_max_acc);
-
- return bitpacker.pack(
- INDEX_DROGUE_DPL_MAX_ACC + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_DROGUE_DPL_MAX_ACC, bits);
- }
-
- bool packMainDplTs(long long main_dpl_ts, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::mainDplTsToBits(main_dpl_ts);
-
- return bitpacker.pack(
- INDEX_MAIN_DPL_TS + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_MAIN_DPL_TS, bits);
- }
-
- bool packMainDplAltitude(float main_dpl_altitude, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::mainDplAltitudeToBits(main_dpl_altitude);
-
- return bitpacker.pack(
- INDEX_MAIN_DPL_ALTITUDE + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_MAIN_DPL_ALTITUDE, bits);
- }
-
- bool packMainDplZspeed(float main_dpl_zspeed, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::mainDplZspeedToBits(main_dpl_zspeed);
-
- return bitpacker.pack(
- INDEX_MAIN_DPL_ZSPEED + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_MAIN_DPL_ZSPEED, bits);
- }
-
- bool packMainDplAcc(float main_dpl_acc, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = LowRateTMConversion::mainDplAccToBits(main_dpl_acc);
-
- return bitpacker.pack(
- INDEX_MAIN_DPL_ACC + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_MAIN_DPL_ACC, bits);
- }
-
-
-
- bool unpackLiftoffTs(long long* liftoff_ts, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_LIFTOFF_TS + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_LIFTOFF_TS, &bits);
-
- if(success)
- {
- *liftoff_ts = LowRateTMConversion::bitsToLiftoffTs(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackLiftoffMaxAccTs(long long* liftoff_max_acc_ts, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_LIFTOFF_MAX_ACC_TS + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_LIFTOFF_MAX_ACC_TS, &bits);
-
- if(success)
- {
- *liftoff_max_acc_ts = LowRateTMConversion::bitsToLiftoffMaxAccTs(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackLiftoffMaxAcc(float* liftoff_max_acc, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_LIFTOFF_MAX_ACC + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_LIFTOFF_MAX_ACC, &bits);
-
- if(success)
- {
- *liftoff_max_acc = LowRateTMConversion::bitsToLiftoffMaxAcc(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackMaxZspeedTs(long long* max_zspeed_ts, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_MAX_ZSPEED_TS + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_MAX_ZSPEED_TS, &bits);
-
- if(success)
- {
- *max_zspeed_ts = LowRateTMConversion::bitsToMaxZspeedTs(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackMaxZspeed(float* max_zspeed, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_MAX_ZSPEED + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_MAX_ZSPEED, &bits);
-
- if(success)
- {
- *max_zspeed = LowRateTMConversion::bitsToMaxZspeed(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackMaxSpeedAltitude(float* max_speed_altitude, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_MAX_SPEED_ALTITUDE + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_MAX_SPEED_ALTITUDE, &bits);
-
- if(success)
- {
- *max_speed_altitude = LowRateTMConversion::bitsToMaxSpeedAltitude(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackApogeeTs(long long* apogee_ts, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_APOGEE_TS + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_APOGEE_TS, &bits);
-
- if(success)
- {
- *apogee_ts = LowRateTMConversion::bitsToApogeeTs(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackNxpMinPressure(float* nxp_min_pressure, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_NXP_MIN_PRESSURE + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_NXP_MIN_PRESSURE, &bits);
-
- if(success)
- {
- *nxp_min_pressure = LowRateTMConversion::bitsToNxpMinPressure(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackHwMinPressure(float* hw_min_pressure, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_HW_MIN_PRESSURE + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_HW_MIN_PRESSURE, &bits);
-
- if(success)
- {
- *hw_min_pressure = LowRateTMConversion::bitsToHwMinPressure(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackKalmanMinPressure(float* kalman_min_pressure, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_KALMAN_MIN_PRESSURE + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_KALMAN_MIN_PRESSURE, &bits);
-
- if(success)
- {
- *kalman_min_pressure = LowRateTMConversion::bitsToKalmanMinPressure(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackDigitalMinPressure(float* digital_min_pressure, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_DIGITAL_MIN_PRESSURE + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_DIGITAL_MIN_PRESSURE, &bits);
-
- if(success)
- {
- *digital_min_pressure = LowRateTMConversion::bitsToDigitalMinPressure(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackBaroMaxAltitutde(float* baro_max_altitutde , size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_BARO_MAX_ALTITUTDE + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_BARO_MAX_ALTITUTDE , &bits);
-
- if(success)
- {
- *baro_max_altitutde = LowRateTMConversion::bitsToBaroMaxAltitutde(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackGpsMaxAltitude(float* gps_max_altitude, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_GPS_MAX_ALTITUDE + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_GPS_MAX_ALTITUDE, &bits);
-
- if(success)
- {
- *gps_max_altitude = LowRateTMConversion::bitsToGpsMaxAltitude(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackApogeeLat(float* apogee_lat, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_APOGEE_LAT + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_APOGEE_LAT, &bits);
-
- if(success)
- {
- *apogee_lat = LowRateTMConversion::bitsToApogeeLat(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackApogeeLon(float* apogee_lon, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_APOGEE_LON + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_APOGEE_LON, &bits);
-
- if(success)
- {
- *apogee_lon = LowRateTMConversion::bitsToApogeeLon(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackDrogueDplTs(long long* drogue_dpl_ts, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_DROGUE_DPL_TS + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_DROGUE_DPL_TS, &bits);
-
- if(success)
- {
- *drogue_dpl_ts = LowRateTMConversion::bitsToDrogueDplTs(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackDrogueDplMaxAcc(float* drogue_dpl_max_acc, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_DROGUE_DPL_MAX_ACC + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_DROGUE_DPL_MAX_ACC, &bits);
-
- if(success)
- {
- *drogue_dpl_max_acc = LowRateTMConversion::bitsToDrogueDplMaxAcc(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackMainDplTs(long long* main_dpl_ts, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_MAIN_DPL_TS + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_MAIN_DPL_TS, &bits);
-
- if(success)
- {
- *main_dpl_ts = LowRateTMConversion::bitsToMainDplTs(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackMainDplAltitude(float* main_dpl_altitude, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_MAIN_DPL_ALTITUDE + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_MAIN_DPL_ALTITUDE, &bits);
-
- if(success)
- {
- *main_dpl_altitude = LowRateTMConversion::bitsToMainDplAltitude(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackMainDplZspeed(float* main_dpl_zspeed, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_MAIN_DPL_ZSPEED + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_MAIN_DPL_ZSPEED, &bits);
-
- if(success)
- {
- *main_dpl_zspeed = LowRateTMConversion::bitsToMainDplZspeed(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
- bool unpackMainDplAcc(float* main_dpl_acc, size_t packet_index)
- {
- if(packet_index >= 1)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_MAIN_DPL_ACC + packet_index * LR_TM_SINGLE_PACKET_SIZE_BITS,
- SIZE_MAIN_DPL_ACC, &bits);
-
- if(success)
- {
- *main_dpl_acc = LowRateTMConversion::bitsToMainDplAcc(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
-
-
-private:
- enum FieldIndex
- {
- INDEX_LIFTOFF_TS = 0,
- INDEX_LIFTOFF_MAX_ACC_TS = 25,
- INDEX_LIFTOFF_MAX_ACC = 50,
- INDEX_MAX_ZSPEED_TS = 61,
- INDEX_MAX_ZSPEED = 86,
- INDEX_MAX_SPEED_ALTITUDE = 96,
- INDEX_APOGEE_TS = 108,
- INDEX_NXP_MIN_PRESSURE = 133,
- INDEX_HW_MIN_PRESSURE = 145,
- INDEX_KALMAN_MIN_PRESSURE = 157,
- INDEX_DIGITAL_MIN_PRESSURE = 169,
- INDEX_BARO_MAX_ALTITUTDE = 182,
- INDEX_GPS_MAX_ALTITUDE = 194,
- INDEX_APOGEE_LAT = 204,
- INDEX_APOGEE_LON = 214,
- INDEX_DROGUE_DPL_TS = 224,
- INDEX_DROGUE_DPL_MAX_ACC = 249,
- INDEX_MAIN_DPL_TS = 260,
- INDEX_MAIN_DPL_ALTITUDE = 285,
- INDEX_MAIN_DPL_ZSPEED = 298,
- INDEX_MAIN_DPL_ACC = 308
- };
-
- enum FieldSize
- {
- SIZE_LIFTOFF_TS = 25,
- SIZE_LIFTOFF_MAX_ACC_TS = 25,
- SIZE_LIFTOFF_MAX_ACC = 11,
- SIZE_MAX_ZSPEED_TS = 25,
- SIZE_MAX_ZSPEED = 10,
- SIZE_MAX_SPEED_ALTITUDE = 12,
- SIZE_APOGEE_TS = 25,
- SIZE_NXP_MIN_PRESSURE = 12,
- SIZE_HW_MIN_PRESSURE = 12,
- SIZE_KALMAN_MIN_PRESSURE = 12,
- SIZE_DIGITAL_MIN_PRESSURE = 13,
- SIZE_BARO_MAX_ALTITUTDE = 12,
- SIZE_GPS_MAX_ALTITUDE = 10,
- SIZE_APOGEE_LAT = 10,
- SIZE_APOGEE_LON = 10,
- SIZE_DROGUE_DPL_TS = 25,
- SIZE_DROGUE_DPL_MAX_ACC = 11,
- SIZE_MAIN_DPL_TS = 25,
- SIZE_MAIN_DPL_ALTITUDE = 13,
- SIZE_MAIN_DPL_ZSPEED = 10,
- SIZE_MAIN_DPL_ACC = 11
- };
-
- uint8_t *packet;
- BitPacker bitpacker;
-};
\ No newline at end of file
diff --git a/bitpacking/requirements.txt b/bitpacking/requirements.txt
deleted file mode 100644
index b4e01569861fa5001ba712bfb61688ed45a3f451..0000000000000000000000000000000000000000
--- a/bitpacking/requirements.txt
+++ /dev/null
@@ -1,20 +0,0 @@
-cachetools==3.1.0
-certifi==2019.3.9
-chardet==3.0.4
-google-api-python-client==1.7.8
-google-auth==1.6.3
-google-auth-httplib2==0.0.3
-google-auth-oauthlib==0.3.0
-httplib2==0.12.3
-idna==2.8
-oauth2client==4.1.3
-oauthlib==3.0.1
-pkg-resources==0.0.0
-pyasn1==0.4.5
-pyasn1-modules==0.2.5
-requests==2.21.0
-requests-oauthlib==1.2.0
-rsa==4.0
-six==1.12.0
-uritemplate==3.0.0
-urllib3==1.24.2
diff --git a/bitpacking/store.json b/bitpacking/store.json
deleted file mode 100644
index 802f29a16dd1153b97453832a6bb8c3c6e8fd01e..0000000000000000000000000000000000000000
--- a/bitpacking/store.json
+++ /dev/null
@@ -1 +0,0 @@
-{"access_token": "ya29.ImGvB5F2SeIodAYzxfVfaJCrXtFsbOevEHpYDv5cx-ZYlSrTejQihtvcMQ-s6WVKkuuP-EM71-Z2Xz8PflJ1-qmrWFKac9E-_EUa7YdlBOrw7JQLLh0d9YSoMxCeEVoXEnxY", "client_id": "1025168905991-tv31etsgm3lecodc5c798shqciekad40.apps.googleusercontent.com", "client_secret": "Yhaf67HuHR4DyXZKNXWu2lre", "refresh_token": "1/GVZfj7UPkTTZg9juq5hDEvwprbaeD8UbHjyrphyuFR4", "token_expiry": "2019-11-03T23:32:51Z", "token_uri": "https://www.googleapis.com/oauth2/v3/token", "user_agent": null, "revoke_uri": "https://oauth2.googleapis.com/revoke", "id_token": null, "id_token_jwt": null, "token_response": {"access_token": "ya29.ImGvB5F2SeIodAYzxfVfaJCrXtFsbOevEHpYDv5cx-ZYlSrTejQihtvcMQ-s6WVKkuuP-EM71-Z2Xz8PflJ1-qmrWFKac9E-_EUa7YdlBOrw7JQLLh0d9YSoMxCeEVoXEnxY", "expires_in": 3600, "scope": "https://www.googleapis.com/auth/spreadsheets.readonly", "token_type": "Bearer"}, "scopes": ["https://www.googleapis.com/auth/spreadsheets.readonly"], "token_info_uri": "https://oauth2.googleapis.com/tokeninfo", "invalid": false, "_class": "OAuth2Credentials", "_module": "oauth2client.client"}
\ No newline at end of file
diff --git a/bitpacking/templates/ConversionFunctions.h.template b/bitpacking/templates/ConversionFunctions.h.template
deleted file mode 100644
index f0ab1f3d16c4ac8690de5c0f5e30f10da6234332..0000000000000000000000000000000000000000
--- a/bitpacking/templates/ConversionFunctions.h.template
+++ /dev/null
@@ -1,56 +0,0 @@
-/**
- * Copyright (c) 2019 Skyward Experimental Rocketry
- * Authors: Luca Erbetta
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-#include <cstdint>
-#include <type_traits>
-
-template<typename T>
-inline uint64_t discretizeRange(T value, T min, T max, unsigned int resolution)
-{
- static_assert(std::is_arithmetic<T>::value, "T must be an arithmetic type (float, int, etc)");
-
- if (value < min)
- {
- return 0;
- }
- else if (value > max)
- {
- return resolution - 1;
- }
-
- return static_cast<uint64_t>((value - min) * resolution / (max - min));
-
-}
-
-template <typename T>
-inline T undiscretizeRange(uint64_t value, T min, T max,
- unsigned int resolution)
-{
- static_assert(std::is_arithmetic<T>::value, "T must be an arithmetic type (float, int, etc)");
-
- return static_cast<T>(value * (max - min) / resolution + min);
-}
-
-
-$classes
\ No newline at end of file
diff --git a/bitpacking/templates/Packets.h.template b/bitpacking/templates/Packets.h.template
deleted file mode 100644
index a5943b8e4e04dfc735e9e042896833341a4850a2..0000000000000000000000000000000000000000
--- a/bitpacking/templates/Packets.h.template
+++ /dev/null
@@ -1,26 +0,0 @@
-/**
- * Copyright (c) 2019 Skyward Experimental Rocketry
- * Authors: Luca Erbetta
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-$includes
\ No newline at end of file
diff --git a/bitpacking/templates/TelemetryPacker.h.template b/bitpacking/templates/TelemetryPacker.h.template
deleted file mode 100644
index 2efd57d86875850c2cc4d9b26fb5009065b51123..0000000000000000000000000000000000000000
--- a/bitpacking/templates/TelemetryPacker.h.template
+++ /dev/null
@@ -1,63 +0,0 @@
-/**
- * Copyright (c) 2019 Skyward Experimental Rocketry
- * Authors: Luca Conterio, Luca Erbetta
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include "bitpacking/BitPacker.h"
-#include "mavlink_lib/$folder/mavlink.h"
-#include "bitpacking/$folder/ConversionFunctions.h"
-
-class ${telemetry_name_ccase}Packer
-{
-public:
- static constexpr int ${mav_tm_name}_PACKET_SIZE = $tm_total_size;
- static constexpr int ${mav_tm_name}_SINGLE_PACKET_SIZE_BITS = $tm_partial_size;
-
- static_assert(MAVLINK_MSG_${mav_tm_name}_FIELD_PAYLOAD_LEN == ${mav_tm_name}_PACKET_SIZE,
- "Payload size mismatch! Mavlnk payload size differes from declared size. Maybe your mavlink definitions are outdated?");
-
-
-
-
- ${telemetry_name_ccase}Packer(uint8_t *packet) : packet(packet), bitpacker(packet, ${mav_tm_name}_PACKET_SIZE)
- {
- }
-
- $pack_functions
-
- $unpack_functions
-
-private:
- enum FieldIndex
- {
-$field_indices
- };
-
- enum FieldSize
- {
-$field_sizes
- };
-
- uint8_t *packet;
- BitPacker bitpacker;
-};
\ No newline at end of file
diff --git a/bitpacking/templates/packFunction.cpp.template b/bitpacking/templates/packFunction.cpp.template
deleted file mode 100644
index d8cfd768f48f433916f39891029b048794c1b671..0000000000000000000000000000000000000000
--- a/bitpacking/templates/packFunction.cpp.template
+++ /dev/null
@@ -1,15 +0,0 @@
-
- bool pack${field_name_ccase}($type $field_name_lcase, size_t packet_index)
- {
- if(packet_index >= $max_index)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits = $convert_fun($field_name_lcase);
-
- return bitpacker.pack(
- INDEX_$field_name_ucase + packet_index * ${mav_tm_name}_SINGLE_PACKET_SIZE_BITS,
- SIZE_$field_name_ucase, bits);
- }
diff --git a/bitpacking/templates/unpackFunction.cpp.template b/bitpacking/templates/unpackFunction.cpp.template
deleted file mode 100644
index ecdb4b65d606db04c9704e0bfe42da38d12b7bed..0000000000000000000000000000000000000000
--- a/bitpacking/templates/unpackFunction.cpp.template
+++ /dev/null
@@ -1,25 +0,0 @@
-
- bool unpack${field_name_ccase}($type* $field_name_lcase, size_t packet_index)
- {
- if(packet_index >= $max_index)
- {
- return false;
- }
-
- // Convert data to a suitable format and store in an unsigned int
- uint64_t bits;
-
- bool success = bitpacker.unpack(
- INDEX_$field_name_ucase + packet_index * ${mav_tm_name}_SINGLE_PACKET_SIZE_BITS,
- SIZE_$field_name_ucase, &bits);
-
- if(success)
- {
- *$field_name_lcase = $convert_fun(bits);
- return true;
- }else
- {
- return false;
- }
-
- }
diff --git a/bitpacking/tests/Makefile b/bitpacking/tests/Makefile
deleted file mode 100644
index 0772b9ec19e897d22fe52a162e5518b71759768e..0000000000000000000000000000000000000000
--- a/bitpacking/tests/Makefile
+++ /dev/null
@@ -1,25 +0,0 @@
-
-TESTS = include/catch.hpp
-REQUIREMENTS = test-bitpacker.cpp manual-test-bitpacker.cpp test-telemetry.cpp $(wildcard ../hermes/*.h) $(TESTS)
-
-all: $(REQUIREMENTS)
- g++ -O2 -o test-bitpacker test-bitpacker.cpp
- g++ -O2 -o manual-test-bitpacker manual-test-bitpacker.cpp
- g++ -O2 -o test-telemetry test-telemetry.cpp -I../ -I../../
-
-warning-all: $(REQUIREMENTS)
- g++ -O2 -Wall -Wextra -pedantic -o test-bitpacker test-bitpacker.cpp
- g++ -O2 -Wall -Wextra -pedantic -o manual-test-bitpacker manual-test-bitpacker.cpp
- g++ -O2 -Wall -Wextra -pedantic -o test-telemetry test-telemetry.cpp -I../ -I../../
-
-test-bitpacker: test-bitpacker.cpp $(TESTS)
- g++ -O2 -o test-bitpacker test-bitpacker.cpp
-
-manual-test-bitpacker: manual-test-bitpacker.cpp $(TESTS)
- g++ -O2 -o manual-test-bitpacker manual-test-bitpacker.cpp
-
-test-telemetry: test-telemetry.cpp $(wildcard ../hermes/*.h) $(TESTS)
- g++ -O2 -o test-telemetry test-telemetry.cpp -I../ -I../../
-
-clean:
- rm -rvf test-bitpacker manual-test-bitpacker test-telemetry
diff --git a/bitpacking/tests/include/catch.hpp b/bitpacking/tests/include/catch.hpp
deleted file mode 100644
index fdb046fe442822af5f7b8de14db3ee242cee18a8..0000000000000000000000000000000000000000
--- a/bitpacking/tests/include/catch.hpp
+++ /dev/null
@@ -1,11689 +0,0 @@
-/*
- * Catch v1.12.2
- * Generated: 2018-05-14 15:10:01.112442
- * ----------------------------------------------------------
- * This file has been merged from multiple headers. Please don't edit it directly
- * Copyright (c) 2012 Two Blue Cubes Ltd. All rights reserved.
- *
- * Distributed under the Boost Software License, Version 1.0. (See accompanying
- * file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt)
- */
-#ifndef TWOBLUECUBES_SINGLE_INCLUDE_CATCH_HPP_INCLUDED
-#define TWOBLUECUBES_SINGLE_INCLUDE_CATCH_HPP_INCLUDED
-
-#define TWOBLUECUBES_CATCH_HPP_INCLUDED
-
-#ifdef __clang__
-# pragma clang system_header
-#elif defined __GNUC__
-# pragma GCC system_header
-#endif
-
-// #included from: internal/catch_suppress_warnings.h
-
-#ifdef __clang__
-# ifdef __ICC // icpc defines the __clang__ macro
-# pragma warning(push)
-# pragma warning(disable: 161 1682)
-# else // __ICC
-# pragma clang diagnostic ignored "-Wglobal-constructors"
-# pragma clang diagnostic ignored "-Wvariadic-macros"
-# pragma clang diagnostic ignored "-Wc99-extensions"
-# pragma clang diagnostic ignored "-Wunused-variable"
-# pragma clang diagnostic push
-# pragma clang diagnostic ignored "-Wpadded"
-# pragma clang diagnostic ignored "-Wc++98-compat"
-# pragma clang diagnostic ignored "-Wc++98-compat-pedantic"
-# pragma clang diagnostic ignored "-Wswitch-enum"
-# pragma clang diagnostic ignored "-Wcovered-switch-default"
-# endif
-#elif defined __GNUC__
-# pragma GCC diagnostic ignored "-Wvariadic-macros"
-# pragma GCC diagnostic ignored "-Wunused-variable"
-# pragma GCC diagnostic ignored "-Wparentheses"
-
-# pragma GCC diagnostic push
-# pragma GCC diagnostic ignored "-Wpadded"
-#endif
-#if defined(CATCH_CONFIG_MAIN) || defined(CATCH_CONFIG_RUNNER)
-# define CATCH_IMPL
-#endif
-
-#ifdef CATCH_IMPL
-# ifndef CLARA_CONFIG_MAIN
-# define CLARA_CONFIG_MAIN_NOT_DEFINED
-# define CLARA_CONFIG_MAIN
-# endif
-#endif
-
-// #included from: internal/catch_notimplemented_exception.h
-#define TWOBLUECUBES_CATCH_NOTIMPLEMENTED_EXCEPTION_H_INCLUDED
-
-// #included from: catch_common.h
-#define TWOBLUECUBES_CATCH_COMMON_H_INCLUDED
-
-// #included from: catch_compiler_capabilities.h
-#define TWOBLUECUBES_CATCH_COMPILER_CAPABILITIES_HPP_INCLUDED
-
-// Detect a number of compiler features - mostly C++11/14 conformance - by compiler
-// The following features are defined:
-//
-// CATCH_CONFIG_CPP11_NULLPTR : is nullptr supported?
-// CATCH_CONFIG_CPP11_NOEXCEPT : is noexcept supported?
-// CATCH_CONFIG_CPP11_GENERATED_METHODS : The delete and default keywords for compiler generated methods
-// CATCH_CONFIG_CPP11_IS_ENUM : std::is_enum is supported?
-// CATCH_CONFIG_CPP11_TUPLE : std::tuple is supported
-// CATCH_CONFIG_CPP11_LONG_LONG : is long long supported?
-// CATCH_CONFIG_CPP11_OVERRIDE : is override supported?
-// CATCH_CONFIG_CPP11_UNIQUE_PTR : is unique_ptr supported (otherwise use auto_ptr)
-// CATCH_CONFIG_CPP11_SHUFFLE : is std::shuffle supported?
-// CATCH_CONFIG_CPP11_TYPE_TRAITS : are type_traits and enable_if supported?
-
-// CATCH_CONFIG_CPP11_OR_GREATER : Is C++11 supported?
-
-// CATCH_CONFIG_VARIADIC_MACROS : are variadic macros supported?
-// CATCH_CONFIG_COUNTER : is the __COUNTER__ macro supported?
-// CATCH_CONFIG_WINDOWS_SEH : is Windows SEH supported?
-// CATCH_CONFIG_POSIX_SIGNALS : are POSIX signals supported?
-// ****************
-// Note to maintainers: if new toggles are added please document them
-// in configuration.md, too
-// ****************
-
-// In general each macro has a _NO_<feature name> form
-// (e.g. CATCH_CONFIG_CPP11_NO_NULLPTR) which disables the feature.
-// Many features, at point of detection, define an _INTERNAL_ macro, so they
-// can be combined, en-mass, with the _NO_ forms later.
-
-// All the C++11 features can be disabled with CATCH_CONFIG_NO_CPP11
-
-#ifdef __cplusplus
-
-# if __cplusplus >= 201103L
-# define CATCH_CPP11_OR_GREATER
-# endif
-
-# if __cplusplus >= 201402L
-# define CATCH_CPP14_OR_GREATER
-# endif
-
-#endif
-
-#ifdef __clang__
-
-# if __has_feature(cxx_nullptr)
-# define CATCH_INTERNAL_CONFIG_CPP11_NULLPTR
-# endif
-
-# if __has_feature(cxx_noexcept)
-# define CATCH_INTERNAL_CONFIG_CPP11_NOEXCEPT
-# endif
-
-# if defined(CATCH_CPP11_OR_GREATER)
-# define CATCH_INTERNAL_SUPPRESS_ETD_WARNINGS \
- _Pragma( "clang diagnostic push" ) \
- _Pragma( "clang diagnostic ignored \"-Wexit-time-destructors\"" )
-# define CATCH_INTERNAL_UNSUPPRESS_ETD_WARNINGS \
- _Pragma( "clang diagnostic pop" )
-
-# define CATCH_INTERNAL_SUPPRESS_PARENTHESES_WARNINGS \
- _Pragma( "clang diagnostic push" ) \
- _Pragma( "clang diagnostic ignored \"-Wparentheses\"" )
-# define CATCH_INTERNAL_UNSUPPRESS_PARENTHESES_WARNINGS \
- _Pragma( "clang diagnostic pop" )
-# endif
-
-#endif // __clang__
-
-////////////////////////////////////////////////////////////////////////////////
-// We know some environments not to support full POSIX signals
-#if defined(__CYGWIN__) || defined(__QNX__)
-
-# if !defined(CATCH_CONFIG_POSIX_SIGNALS)
-# define CATCH_INTERNAL_CONFIG_NO_POSIX_SIGNALS
-# endif
-
-#endif
-
-#ifdef __OS400__
-# define CATCH_INTERNAL_CONFIG_NO_POSIX_SIGNALS
-# define CATCH_CONFIG_COLOUR_NONE
-#endif
-
-////////////////////////////////////////////////////////////////////////////////
-// Cygwin
-#ifdef __CYGWIN__
-
-// Required for some versions of Cygwin to declare gettimeofday
-// see: http://stackoverflow.com/questions/36901803/gettimeofday-not-declared-in-this-scope-cygwin
-# define _BSD_SOURCE
-
-#endif // __CYGWIN__
-
-////////////////////////////////////////////////////////////////////////////////
-// Borland
-#ifdef __BORLANDC__
-
-#endif // __BORLANDC__
-
-////////////////////////////////////////////////////////////////////////////////
-// EDG
-#ifdef __EDG_VERSION__
-
-#endif // __EDG_VERSION__
-
-////////////////////////////////////////////////////////////////////////////////
-// Digital Mars
-#ifdef __DMC__
-
-#endif // __DMC__
-
-////////////////////////////////////////////////////////////////////////////////
-// GCC
-#ifdef __GNUC__
-
-# if __GNUC__ == 4 && __GNUC_MINOR__ >= 6 && defined(__GXX_EXPERIMENTAL_CXX0X__)
-# define CATCH_INTERNAL_CONFIG_CPP11_NULLPTR
-# endif
-
-// - otherwise more recent versions define __cplusplus >= 201103L
-// and will get picked up below
-
-#endif // __GNUC__
-
-////////////////////////////////////////////////////////////////////////////////
-// Visual C++
-#ifdef _MSC_VER
-
-#define CATCH_INTERNAL_CONFIG_WINDOWS_SEH
-
-#if (_MSC_VER >= 1600)
-# define CATCH_INTERNAL_CONFIG_CPP11_NULLPTR
-# define CATCH_INTERNAL_CONFIG_CPP11_UNIQUE_PTR
-#endif
-
-#if (_MSC_VER >= 1900 ) // (VC++ 13 (VS2015))
-#define CATCH_INTERNAL_CONFIG_CPP11_NOEXCEPT
-#define CATCH_INTERNAL_CONFIG_CPP11_GENERATED_METHODS
-#define CATCH_INTERNAL_CONFIG_CPP11_SHUFFLE
-#define CATCH_INTERNAL_CONFIG_CPP11_TYPE_TRAITS
-#endif
-
-#endif // _MSC_VER
-
-////////////////////////////////////////////////////////////////////////////////
-
-// Use variadic macros if the compiler supports them
-#if ( defined _MSC_VER && _MSC_VER > 1400 && !defined __EDGE__) || \
- ( defined __WAVE__ && __WAVE_HAS_VARIADICS ) || \
- ( defined __GNUC__ && __GNUC__ >= 3 ) || \
- ( !defined __cplusplus && __STDC_VERSION__ >= 199901L || __cplusplus >= 201103L )
-
-#define CATCH_INTERNAL_CONFIG_VARIADIC_MACROS
-
-#endif
-
-// Use __COUNTER__ if the compiler supports it
-#if ( defined _MSC_VER && _MSC_VER >= 1300 ) || \
- ( defined __GNUC__ && ( __GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3 )) ) || \
- ( defined __clang__ && __clang_major__ >= 3 )
-
-// Use of __COUNTER__ is suppressed during code analysis in CLion/AppCode 2017.2.x and former,
-// because __COUNTER__ is not properly handled by it.
-// This does not affect compilation
-#if ( !defined __JETBRAINS_IDE__ || __JETBRAINS_IDE__ >= 20170300L )
- #define CATCH_INTERNAL_CONFIG_COUNTER
-#endif
-
-#endif
-
-////////////////////////////////////////////////////////////////////////////////
-// C++ language feature support
-
-// catch all support for C++11
-#if defined(CATCH_CPP11_OR_GREATER)
-
-# if !defined(CATCH_INTERNAL_CONFIG_CPP11_NULLPTR)
-# define CATCH_INTERNAL_CONFIG_CPP11_NULLPTR
-# endif
-
-# ifndef CATCH_INTERNAL_CONFIG_CPP11_NOEXCEPT
-# define CATCH_INTERNAL_CONFIG_CPP11_NOEXCEPT
-# endif
-
-# ifndef CATCH_INTERNAL_CONFIG_CPP11_GENERATED_METHODS
-# define CATCH_INTERNAL_CONFIG_CPP11_GENERATED_METHODS
-# endif
-
-# ifndef CATCH_INTERNAL_CONFIG_CPP11_IS_ENUM
-# define CATCH_INTERNAL_CONFIG_CPP11_IS_ENUM
-# endif
-
-# ifndef CATCH_INTERNAL_CONFIG_CPP11_TUPLE
-# define CATCH_INTERNAL_CONFIG_CPP11_TUPLE
-# endif
-
-# ifndef CATCH_INTERNAL_CONFIG_VARIADIC_MACROS
-# define CATCH_INTERNAL_CONFIG_VARIADIC_MACROS
-# endif
-
-# if !defined(CATCH_INTERNAL_CONFIG_CPP11_LONG_LONG)
-# define CATCH_INTERNAL_CONFIG_CPP11_LONG_LONG
-# endif
-
-# if !defined(CATCH_INTERNAL_CONFIG_CPP11_OVERRIDE)
-# define CATCH_INTERNAL_CONFIG_CPP11_OVERRIDE
-# endif
-# if !defined(CATCH_INTERNAL_CONFIG_CPP11_UNIQUE_PTR)
-# define CATCH_INTERNAL_CONFIG_CPP11_UNIQUE_PTR
-# endif
-# if !defined(CATCH_INTERNAL_CONFIG_CPP11_SHUFFLE)
-# define CATCH_INTERNAL_CONFIG_CPP11_SHUFFLE
-# endif
-# if !defined(CATCH_INTERNAL_CONFIG_CPP11_TYPE_TRAITS)
-# define CATCH_INTERNAL_CONFIG_CPP11_TYPE_TRAITS
-# endif
-
-#endif // __cplusplus >= 201103L
-
-// Now set the actual defines based on the above + anything the user has configured
-#if defined(CATCH_INTERNAL_CONFIG_CPP11_NULLPTR) && !defined(CATCH_CONFIG_CPP11_NO_NULLPTR) && !defined(CATCH_CONFIG_CPP11_NULLPTR) && !defined(CATCH_CONFIG_NO_CPP11)
-# define CATCH_CONFIG_CPP11_NULLPTR
-#endif
-#if defined(CATCH_INTERNAL_CONFIG_CPP11_NOEXCEPT) && !defined(CATCH_CONFIG_CPP11_NO_NOEXCEPT) && !defined(CATCH_CONFIG_CPP11_NOEXCEPT) && !defined(CATCH_CONFIG_NO_CPP11)
-# define CATCH_CONFIG_CPP11_NOEXCEPT
-#endif
-#if defined(CATCH_INTERNAL_CONFIG_CPP11_GENERATED_METHODS) && !defined(CATCH_CONFIG_CPP11_NO_GENERATED_METHODS) && !defined(CATCH_CONFIG_CPP11_GENERATED_METHODS) && !defined(CATCH_CONFIG_NO_CPP11)
-# define CATCH_CONFIG_CPP11_GENERATED_METHODS
-#endif
-#if defined(CATCH_INTERNAL_CONFIG_CPP11_IS_ENUM) && !defined(CATCH_CONFIG_CPP11_NO_IS_ENUM) && !defined(CATCH_CONFIG_CPP11_IS_ENUM) && !defined(CATCH_CONFIG_NO_CPP11)
-# define CATCH_CONFIG_CPP11_IS_ENUM
-#endif
-#if defined(CATCH_INTERNAL_CONFIG_CPP11_TUPLE) && !defined(CATCH_CONFIG_CPP11_NO_TUPLE) && !defined(CATCH_CONFIG_CPP11_TUPLE) && !defined(CATCH_CONFIG_NO_CPP11)
-# define CATCH_CONFIG_CPP11_TUPLE
-#endif
-#if defined(CATCH_INTERNAL_CONFIG_VARIADIC_MACROS) && !defined(CATCH_CONFIG_NO_VARIADIC_MACROS) && !defined(CATCH_CONFIG_VARIADIC_MACROS)
-# define CATCH_CONFIG_VARIADIC_MACROS
-#endif
-#if defined(CATCH_INTERNAL_CONFIG_CPP11_LONG_LONG) && !defined(CATCH_CONFIG_CPP11_NO_LONG_LONG) && !defined(CATCH_CONFIG_CPP11_LONG_LONG) && !defined(CATCH_CONFIG_NO_CPP11)
-# define CATCH_CONFIG_CPP11_LONG_LONG
-#endif
-#if defined(CATCH_INTERNAL_CONFIG_CPP11_OVERRIDE) && !defined(CATCH_CONFIG_CPP11_NO_OVERRIDE) && !defined(CATCH_CONFIG_CPP11_OVERRIDE) && !defined(CATCH_CONFIG_NO_CPP11)
-# define CATCH_CONFIG_CPP11_OVERRIDE
-#endif
-#if defined(CATCH_INTERNAL_CONFIG_CPP11_UNIQUE_PTR) && !defined(CATCH_CONFIG_CPP11_NO_UNIQUE_PTR) && !defined(CATCH_CONFIG_CPP11_UNIQUE_PTR) && !defined(CATCH_CONFIG_NO_CPP11)
-# define CATCH_CONFIG_CPP11_UNIQUE_PTR
-#endif
-#if defined(CATCH_INTERNAL_CONFIG_COUNTER) && !defined(CATCH_CONFIG_NO_COUNTER) && !defined(CATCH_CONFIG_COUNTER)
-# define CATCH_CONFIG_COUNTER
-#endif
-#if defined(CATCH_INTERNAL_CONFIG_CPP11_SHUFFLE) && !defined(CATCH_CONFIG_CPP11_NO_SHUFFLE) && !defined(CATCH_CONFIG_CPP11_SHUFFLE) && !defined(CATCH_CONFIG_NO_CPP11)
-# define CATCH_CONFIG_CPP11_SHUFFLE
-#endif
-# if defined(CATCH_INTERNAL_CONFIG_CPP11_TYPE_TRAITS) && !defined(CATCH_CONFIG_CPP11_NO_TYPE_TRAITS) && !defined(CATCH_CONFIG_CPP11_TYPE_TRAITS) && !defined(CATCH_CONFIG_NO_CPP11)
-# define CATCH_CONFIG_CPP11_TYPE_TRAITS
-# endif
-#if defined(CATCH_INTERNAL_CONFIG_WINDOWS_SEH) && !defined(CATCH_CONFIG_NO_WINDOWS_SEH) && !defined(CATCH_CONFIG_WINDOWS_SEH)
-# define CATCH_CONFIG_WINDOWS_SEH
-#endif
-// This is set by default, because we assume that unix compilers are posix-signal-compatible by default.
-#if !defined(CATCH_INTERNAL_CONFIG_NO_POSIX_SIGNALS) && !defined(CATCH_CONFIG_NO_POSIX_SIGNALS) && !defined(CATCH_CONFIG_POSIX_SIGNALS)
-# define CATCH_CONFIG_POSIX_SIGNALS
-#endif
-
-#if !defined(CATCH_INTERNAL_SUPPRESS_PARENTHESES_WARNINGS)
-# define CATCH_INTERNAL_SUPPRESS_PARENTHESES_WARNINGS
-# define CATCH_INTERNAL_UNSUPPRESS_PARENTHESES_WARNINGS
-#endif
-#if !defined(CATCH_INTERNAL_SUPPRESS_ETD_WARNINGS)
-# define CATCH_INTERNAL_SUPPRESS_ETD_WARNINGS
-# define CATCH_INTERNAL_UNSUPPRESS_ETD_WARNINGS
-#endif
-
-// noexcept support:
-#if defined(CATCH_CONFIG_CPP11_NOEXCEPT) && !defined(CATCH_NOEXCEPT)
-# define CATCH_NOEXCEPT noexcept
-# define CATCH_NOEXCEPT_IS(x) noexcept(x)
-#else
-# define CATCH_NOEXCEPT throw()
-# define CATCH_NOEXCEPT_IS(x)
-#endif
-
-// nullptr support
-#ifdef CATCH_CONFIG_CPP11_NULLPTR
-# define CATCH_NULL nullptr
-#else
-# define CATCH_NULL NULL
-#endif
-
-// override support
-#ifdef CATCH_CONFIG_CPP11_OVERRIDE
-# define CATCH_OVERRIDE override
-#else
-# define CATCH_OVERRIDE
-#endif
-
-// unique_ptr support
-#ifdef CATCH_CONFIG_CPP11_UNIQUE_PTR
-# define CATCH_AUTO_PTR( T ) std::unique_ptr<T>
-#else
-# define CATCH_AUTO_PTR( T ) std::auto_ptr<T>
-#endif
-
-#define INTERNAL_CATCH_UNIQUE_NAME_LINE2( name, line ) name##line
-#define INTERNAL_CATCH_UNIQUE_NAME_LINE( name, line ) INTERNAL_CATCH_UNIQUE_NAME_LINE2( name, line )
-#ifdef CATCH_CONFIG_COUNTER
-# define INTERNAL_CATCH_UNIQUE_NAME( name ) INTERNAL_CATCH_UNIQUE_NAME_LINE( name, __COUNTER__ )
-#else
-# define INTERNAL_CATCH_UNIQUE_NAME( name ) INTERNAL_CATCH_UNIQUE_NAME_LINE( name, __LINE__ )
-#endif
-
-#define INTERNAL_CATCH_STRINGIFY2( expr ) #expr
-#define INTERNAL_CATCH_STRINGIFY( expr ) INTERNAL_CATCH_STRINGIFY2( expr )
-
-#include <sstream>
-#include <algorithm>
-
-namespace Catch {
-
- struct IConfig;
-
- struct CaseSensitive { enum Choice {
- Yes,
- No
- }; };
-
- class NonCopyable {
-#ifdef CATCH_CONFIG_CPP11_GENERATED_METHODS
- NonCopyable( NonCopyable const& ) = delete;
- NonCopyable( NonCopyable && ) = delete;
- NonCopyable& operator = ( NonCopyable const& ) = delete;
- NonCopyable& operator = ( NonCopyable && ) = delete;
-#else
- NonCopyable( NonCopyable const& info );
- NonCopyable& operator = ( NonCopyable const& );
-#endif
-
- protected:
- NonCopyable() {}
- virtual ~NonCopyable();
- };
-
- class SafeBool {
- public:
- typedef void (SafeBool::*type)() const;
-
- static type makeSafe( bool value ) {
- return value ? &SafeBool::trueValue : 0;
- }
- private:
- void trueValue() const {}
- };
-
- template<typename ContainerT>
- void deleteAll( ContainerT& container ) {
- typename ContainerT::const_iterator it = container.begin();
- typename ContainerT::const_iterator itEnd = container.end();
- for(; it != itEnd; ++it )
- delete *it;
- }
- template<typename AssociativeContainerT>
- void deleteAllValues( AssociativeContainerT& container ) {
- typename AssociativeContainerT::const_iterator it = container.begin();
- typename AssociativeContainerT::const_iterator itEnd = container.end();
- for(; it != itEnd; ++it )
- delete it->second;
- }
-
- bool startsWith( std::string const& s, std::string const& prefix );
- bool startsWith( std::string const& s, char prefix );
- bool endsWith( std::string const& s, std::string const& suffix );
- bool endsWith( std::string const& s, char suffix );
- bool contains( std::string const& s, std::string const& infix );
- void toLowerInPlace( std::string& s );
- std::string toLower( std::string const& s );
- std::string trim( std::string const& str );
- bool replaceInPlace( std::string& str, std::string const& replaceThis, std::string const& withThis );
-
- struct pluralise {
- pluralise( std::size_t count, std::string const& label );
-
- friend std::ostream& operator << ( std::ostream& os, pluralise const& pluraliser );
-
- std::size_t m_count;
- std::string m_label;
- };
-
- struct SourceLineInfo {
-
- SourceLineInfo();
- SourceLineInfo( char const* _file, std::size_t _line );
-# ifdef CATCH_CONFIG_CPP11_GENERATED_METHODS
- SourceLineInfo(SourceLineInfo const& other) = default;
- SourceLineInfo( SourceLineInfo && ) = default;
- SourceLineInfo& operator = ( SourceLineInfo const& ) = default;
- SourceLineInfo& operator = ( SourceLineInfo && ) = default;
-# endif
- bool empty() const;
- bool operator == ( SourceLineInfo const& other ) const;
- bool operator < ( SourceLineInfo const& other ) const;
-
- char const* file;
- std::size_t line;
- };
-
- std::ostream& operator << ( std::ostream& os, SourceLineInfo const& info );
-
- // This is just here to avoid compiler warnings with macro constants and boolean literals
- inline bool isTrue( bool value ){ return value; }
- inline bool alwaysTrue() { return true; }
- inline bool alwaysFalse() { return false; }
-
- void throwLogicError( std::string const& message, SourceLineInfo const& locationInfo );
-
- void seedRng( IConfig const& config );
- unsigned int rngSeed();
-
- // Use this in variadic streaming macros to allow
- // >> +StreamEndStop
- // as well as
- // >> stuff +StreamEndStop
- struct StreamEndStop {
- std::string operator+() {
- return std::string();
- }
- };
- template<typename T>
- T const& operator + ( T const& value, StreamEndStop ) {
- return value;
- }
-}
-
-#define CATCH_INTERNAL_LINEINFO ::Catch::SourceLineInfo( __FILE__, static_cast<std::size_t>( __LINE__ ) )
-#define CATCH_INTERNAL_ERROR( msg ) ::Catch::throwLogicError( msg, CATCH_INTERNAL_LINEINFO );
-
-namespace Catch {
-
- class NotImplementedException : public std::exception
- {
- public:
- NotImplementedException( SourceLineInfo const& lineInfo );
-
- virtual ~NotImplementedException() CATCH_NOEXCEPT {}
-
- virtual const char* what() const CATCH_NOEXCEPT;
-
- private:
- std::string m_what;
- SourceLineInfo m_lineInfo;
- };
-
-} // end namespace Catch
-
-///////////////////////////////////////////////////////////////////////////////
-#define CATCH_NOT_IMPLEMENTED throw Catch::NotImplementedException( CATCH_INTERNAL_LINEINFO )
-
-// #included from: internal/catch_context.h
-#define TWOBLUECUBES_CATCH_CONTEXT_H_INCLUDED
-
-// #included from: catch_interfaces_generators.h
-#define TWOBLUECUBES_CATCH_INTERFACES_GENERATORS_H_INCLUDED
-
-#include <string>
-
-namespace Catch {
-
- struct IGeneratorInfo {
- virtual ~IGeneratorInfo();
- virtual bool moveNext() = 0;
- virtual std::size_t getCurrentIndex() const = 0;
- };
-
- struct IGeneratorsForTest {
- virtual ~IGeneratorsForTest();
-
- virtual IGeneratorInfo& getGeneratorInfo( std::string const& fileInfo, std::size_t size ) = 0;
- virtual bool moveNext() = 0;
- };
-
- IGeneratorsForTest* createGeneratorsForTest();
-
-} // end namespace Catch
-
-// #included from: catch_ptr.hpp
-#define TWOBLUECUBES_CATCH_PTR_HPP_INCLUDED
-
-#ifdef __clang__
-#pragma clang diagnostic push
-#pragma clang diagnostic ignored "-Wpadded"
-#endif
-
-namespace Catch {
-
- // An intrusive reference counting smart pointer.
- // T must implement addRef() and release() methods
- // typically implementing the IShared interface
- template<typename T>
- class Ptr {
- public:
- Ptr() : m_p( CATCH_NULL ){}
- Ptr( T* p ) : m_p( p ){
- if( m_p )
- m_p->addRef();
- }
- Ptr( Ptr const& other ) : m_p( other.m_p ){
- if( m_p )
- m_p->addRef();
- }
- ~Ptr(){
- if( m_p )
- m_p->release();
- }
- void reset() {
- if( m_p )
- m_p->release();
- m_p = CATCH_NULL;
- }
- Ptr& operator = ( T* p ){
- Ptr temp( p );
- swap( temp );
- return *this;
- }
- Ptr& operator = ( Ptr const& other ){
- Ptr temp( other );
- swap( temp );
- return *this;
- }
- void swap( Ptr& other ) { std::swap( m_p, other.m_p ); }
- T* get() const{ return m_p; }
- T& operator*() const { return *m_p; }
- T* operator->() const { return m_p; }
- bool operator !() const { return m_p == CATCH_NULL; }
- operator SafeBool::type() const { return SafeBool::makeSafe( m_p != CATCH_NULL ); }
-
- private:
- T* m_p;
- };
-
- struct IShared : NonCopyable {
- virtual ~IShared();
- virtual void addRef() const = 0;
- virtual void release() const = 0;
- };
-
- template<typename T = IShared>
- struct SharedImpl : T {
-
- SharedImpl() : m_rc( 0 ){}
-
- virtual void addRef() const {
- ++m_rc;
- }
- virtual void release() const {
- if( --m_rc == 0 )
- delete this;
- }
-
- mutable unsigned int m_rc;
- };
-
-} // end namespace Catch
-
-#ifdef __clang__
-#pragma clang diagnostic pop
-#endif
-
-namespace Catch {
-
- class TestCase;
- class Stream;
- struct IResultCapture;
- struct IRunner;
- struct IGeneratorsForTest;
- struct IConfig;
-
- struct IContext
- {
- virtual ~IContext();
-
- virtual IResultCapture* getResultCapture() = 0;
- virtual IRunner* getRunner() = 0;
- virtual size_t getGeneratorIndex( std::string const& fileInfo, size_t totalSize ) = 0;
- virtual bool advanceGeneratorsForCurrentTest() = 0;
- virtual Ptr<IConfig const> getConfig() const = 0;
- };
-
- struct IMutableContext : IContext
- {
- virtual ~IMutableContext();
- virtual void setResultCapture( IResultCapture* resultCapture ) = 0;
- virtual void setRunner( IRunner* runner ) = 0;
- virtual void setConfig( Ptr<IConfig const> const& config ) = 0;
- };
-
- IContext& getCurrentContext();
- IMutableContext& getCurrentMutableContext();
- void cleanUpContext();
- Stream createStream( std::string const& streamName );
-
-}
-
-// #included from: internal/catch_test_registry.hpp
-#define TWOBLUECUBES_CATCH_TEST_REGISTRY_HPP_INCLUDED
-
-// #included from: catch_interfaces_testcase.h
-#define TWOBLUECUBES_CATCH_INTERFACES_TESTCASE_H_INCLUDED
-
-#include <vector>
-
-namespace Catch {
-
- class TestSpec;
-
- struct ITestCase : IShared {
- virtual void invoke () const = 0;
- protected:
- virtual ~ITestCase();
- };
-
- class TestCase;
- struct IConfig;
-
- struct ITestCaseRegistry {
- virtual ~ITestCaseRegistry();
- virtual std::vector<TestCase> const& getAllTests() const = 0;
- virtual std::vector<TestCase> const& getAllTestsSorted( IConfig const& config ) const = 0;
- };
-
- bool matchTest( TestCase const& testCase, TestSpec const& testSpec, IConfig const& config );
- std::vector<TestCase> filterTests( std::vector<TestCase> const& testCases, TestSpec const& testSpec, IConfig const& config );
- std::vector<TestCase> const& getAllTestCasesSorted( IConfig const& config );
-
-}
-
-namespace Catch {
-
-template<typename C>
-class MethodTestCase : public SharedImpl<ITestCase> {
-
-public:
- MethodTestCase( void (C::*method)() ) : m_method( method ) {}
-
- virtual void invoke() const {
- C obj;
- (obj.*m_method)();
- }
-
-private:
- virtual ~MethodTestCase() {}
-
- void (C::*m_method)();
-};
-
-typedef void(*TestFunction)();
-
-struct NameAndDesc {
- NameAndDesc( const char* _name = "", const char* _description= "" )
- : name( _name ), description( _description )
- {}
-
- const char* name;
- const char* description;
-};
-
-void registerTestCase
- ( ITestCase* testCase,
- char const* className,
- NameAndDesc const& nameAndDesc,
- SourceLineInfo const& lineInfo );
-
-struct AutoReg {
-
- AutoReg
- ( TestFunction function,
- SourceLineInfo const& lineInfo,
- NameAndDesc const& nameAndDesc );
-
- template<typename C>
- AutoReg
- ( void (C::*method)(),
- char const* className,
- NameAndDesc const& nameAndDesc,
- SourceLineInfo const& lineInfo ) {
-
- registerTestCase
- ( new MethodTestCase<C>( method ),
- className,
- nameAndDesc,
- lineInfo );
- }
-
- ~AutoReg();
-
-private:
- AutoReg( AutoReg const& );
- void operator= ( AutoReg const& );
-};
-
-void registerTestCaseFunction
- ( TestFunction function,
- SourceLineInfo const& lineInfo,
- NameAndDesc const& nameAndDesc );
-
-} // end namespace Catch
-
-#ifdef CATCH_CONFIG_VARIADIC_MACROS
- ///////////////////////////////////////////////////////////////////////////////
- #define INTERNAL_CATCH_TESTCASE2( TestName, ... ) \
- static void TestName(); \
- CATCH_INTERNAL_SUPPRESS_ETD_WARNINGS \
- namespace{ Catch::AutoReg INTERNAL_CATCH_UNIQUE_NAME( autoRegistrar )( &TestName, CATCH_INTERNAL_LINEINFO, Catch::NameAndDesc( __VA_ARGS__ ) ); } /* NOLINT */ \
- CATCH_INTERNAL_UNSUPPRESS_ETD_WARNINGS \
- static void TestName()
- #define INTERNAL_CATCH_TESTCASE( ... ) \
- INTERNAL_CATCH_TESTCASE2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ), __VA_ARGS__ )
-
- ///////////////////////////////////////////////////////////////////////////////
- #define INTERNAL_CATCH_METHOD_AS_TEST_CASE( QualifiedMethod, ... ) \
- CATCH_INTERNAL_SUPPRESS_ETD_WARNINGS \
- namespace{ Catch::AutoReg INTERNAL_CATCH_UNIQUE_NAME( autoRegistrar )( &QualifiedMethod, "&" #QualifiedMethod, Catch::NameAndDesc( __VA_ARGS__ ), CATCH_INTERNAL_LINEINFO ); } /* NOLINT */ \
- CATCH_INTERNAL_UNSUPPRESS_ETD_WARNINGS
-
- ///////////////////////////////////////////////////////////////////////////////
- #define INTERNAL_CATCH_TEST_CASE_METHOD2( TestName, ClassName, ... )\
- CATCH_INTERNAL_SUPPRESS_ETD_WARNINGS \
- namespace{ \
- struct TestName : ClassName{ \
- void test(); \
- }; \
- Catch::AutoReg INTERNAL_CATCH_UNIQUE_NAME( autoRegistrar ) ( &TestName::test, #ClassName, Catch::NameAndDesc( __VA_ARGS__ ), CATCH_INTERNAL_LINEINFO ); /* NOLINT */ \
- } \
- CATCH_INTERNAL_UNSUPPRESS_ETD_WARNINGS \
- void TestName::test()
- #define INTERNAL_CATCH_TEST_CASE_METHOD( ClassName, ... ) \
- INTERNAL_CATCH_TEST_CASE_METHOD2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ), ClassName, __VA_ARGS__ )
-
- ///////////////////////////////////////////////////////////////////////////////
- #define INTERNAL_CATCH_REGISTER_TESTCASE( Function, ... ) \
- CATCH_INTERNAL_SUPPRESS_ETD_WARNINGS \
- Catch::AutoReg( Function, CATCH_INTERNAL_LINEINFO, Catch::NameAndDesc( __VA_ARGS__ ) ); /* NOLINT */ \
- CATCH_INTERNAL_UNSUPPRESS_ETD_WARNINGS
-
-#else
- ///////////////////////////////////////////////////////////////////////////////
- #define INTERNAL_CATCH_TESTCASE2( TestName, Name, Desc ) \
- static void TestName(); \
- CATCH_INTERNAL_SUPPRESS_ETD_WARNINGS \
- namespace{ Catch::AutoReg INTERNAL_CATCH_UNIQUE_NAME( autoRegistrar )( &TestName, CATCH_INTERNAL_LINEINFO, Catch::NameAndDesc( Name, Desc ) ); } /* NOLINT */ \
- CATCH_INTERNAL_UNSUPPRESS_ETD_WARNINGS \
- static void TestName()
- #define INTERNAL_CATCH_TESTCASE( Name, Desc ) \
- INTERNAL_CATCH_TESTCASE2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ), Name, Desc )
-
- ///////////////////////////////////////////////////////////////////////////////
- #define INTERNAL_CATCH_METHOD_AS_TEST_CASE( QualifiedMethod, Name, Desc ) \
- CATCH_INTERNAL_SUPPRESS_ETD_WARNINGS \
- namespace{ Catch::AutoReg INTERNAL_CATCH_UNIQUE_NAME( autoRegistrar )( &QualifiedMethod, "&" #QualifiedMethod, Catch::NameAndDesc( Name, Desc ), CATCH_INTERNAL_LINEINFO ); } /* NOLINT */ \
- CATCH_INTERNAL_UNSUPPRESS_ETD_WARNINGS
-
- ///////////////////////////////////////////////////////////////////////////////
- #define INTERNAL_CATCH_TEST_CASE_METHOD2( TestCaseName, ClassName, TestName, Desc )\
- CATCH_INTERNAL_SUPPRESS_ETD_WARNINGS \
- namespace{ \
- struct TestCaseName : ClassName{ \
- void test(); \
- }; \
- Catch::AutoReg INTERNAL_CATCH_UNIQUE_NAME( autoRegistrar ) ( &TestCaseName::test, #ClassName, Catch::NameAndDesc( TestName, Desc ), CATCH_INTERNAL_LINEINFO ); /* NOLINT */ \
- } \
- CATCH_INTERNAL_UNSUPPRESS_ETD_WARNINGS \
- void TestCaseName::test()
- #define INTERNAL_CATCH_TEST_CASE_METHOD( ClassName, TestName, Desc )\
- INTERNAL_CATCH_TEST_CASE_METHOD2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ), ClassName, TestName, Desc )
-
- ///////////////////////////////////////////////////////////////////////////////
- #define INTERNAL_CATCH_REGISTER_TESTCASE( Function, Name, Desc ) \
- CATCH_INTERNAL_SUPPRESS_ETD_WARNINGS \
- Catch::AutoReg( Function, CATCH_INTERNAL_LINEINFO, Catch::NameAndDesc( Name, Desc ) ); /* NOLINT */ \
- CATCH_INTERNAL_UNSUPPRESS_ETD_WARNINGS
-
-#endif
-
-// #included from: internal/catch_capture.hpp
-#define TWOBLUECUBES_CATCH_CAPTURE_HPP_INCLUDED
-
-// #included from: catch_result_builder.h
-#define TWOBLUECUBES_CATCH_RESULT_BUILDER_H_INCLUDED
-
-// #included from: catch_result_type.h
-#define TWOBLUECUBES_CATCH_RESULT_TYPE_H_INCLUDED
-
-namespace Catch {
-
- // ResultWas::OfType enum
- struct ResultWas { enum OfType {
- Unknown = -1,
- Ok = 0,
- Info = 1,
- Warning = 2,
-
- FailureBit = 0x10,
-
- ExpressionFailed = FailureBit | 1,
- ExplicitFailure = FailureBit | 2,
-
- Exception = 0x100 | FailureBit,
-
- ThrewException = Exception | 1,
- DidntThrowException = Exception | 2,
-
- FatalErrorCondition = 0x200 | FailureBit
-
- }; };
-
- inline bool isOk( ResultWas::OfType resultType ) {
- return ( resultType & ResultWas::FailureBit ) == 0;
- }
- inline bool isJustInfo( int flags ) {
- return flags == ResultWas::Info;
- }
-
- // ResultDisposition::Flags enum
- struct ResultDisposition { enum Flags {
- Normal = 0x01,
-
- ContinueOnFailure = 0x02, // Failures fail test, but execution continues
- FalseTest = 0x04, // Prefix expression with !
- SuppressFail = 0x08 // Failures are reported but do not fail the test
- }; };
-
- inline ResultDisposition::Flags operator | ( ResultDisposition::Flags lhs, ResultDisposition::Flags rhs ) {
- return static_cast<ResultDisposition::Flags>( static_cast<int>( lhs ) | static_cast<int>( rhs ) );
- }
-
- inline bool shouldContinueOnFailure( int flags ) { return ( flags & ResultDisposition::ContinueOnFailure ) != 0; }
- inline bool isFalseTest( int flags ) { return ( flags & ResultDisposition::FalseTest ) != 0; }
- inline bool shouldSuppressFailure( int flags ) { return ( flags & ResultDisposition::SuppressFail ) != 0; }
-
-} // end namespace Catch
-
-// #included from: catch_assertionresult.h
-#define TWOBLUECUBES_CATCH_ASSERTIONRESULT_H_INCLUDED
-
-#include <string>
-
-namespace Catch {
-
- struct STATIC_ASSERT_Expression_Too_Complex_Please_Rewrite_As_Binary_Comparison;
-
- struct DecomposedExpression
- {
- virtual ~DecomposedExpression() {}
- virtual bool isBinaryExpression() const {
- return false;
- }
- virtual void reconstructExpression( std::string& dest ) const = 0;
-
- // Only simple binary comparisons can be decomposed.
- // If more complex check is required then wrap sub-expressions in parentheses.
- template<typename T> STATIC_ASSERT_Expression_Too_Complex_Please_Rewrite_As_Binary_Comparison& operator + ( T const& );
- template<typename T> STATIC_ASSERT_Expression_Too_Complex_Please_Rewrite_As_Binary_Comparison& operator - ( T const& );
- template<typename T> STATIC_ASSERT_Expression_Too_Complex_Please_Rewrite_As_Binary_Comparison& operator * ( T const& );
- template<typename T> STATIC_ASSERT_Expression_Too_Complex_Please_Rewrite_As_Binary_Comparison& operator / ( T const& );
- template<typename T> STATIC_ASSERT_Expression_Too_Complex_Please_Rewrite_As_Binary_Comparison& operator % ( T const& );
- template<typename T> STATIC_ASSERT_Expression_Too_Complex_Please_Rewrite_As_Binary_Comparison& operator && ( T const& );
- template<typename T> STATIC_ASSERT_Expression_Too_Complex_Please_Rewrite_As_Binary_Comparison& operator || ( T const& );
-
- private:
- DecomposedExpression& operator = (DecomposedExpression const&);
- };
-
- struct AssertionInfo
- {
- AssertionInfo();
- AssertionInfo( char const * _macroName,
- SourceLineInfo const& _lineInfo,
- char const * _capturedExpression,
- ResultDisposition::Flags _resultDisposition,
- char const * _secondArg = "");
-
- char const * macroName;
- SourceLineInfo lineInfo;
- char const * capturedExpression;
- ResultDisposition::Flags resultDisposition;
- char const * secondArg;
- };
-
- struct AssertionResultData
- {
- AssertionResultData() : decomposedExpression( CATCH_NULL )
- , resultType( ResultWas::Unknown )
- , negated( false )
- , parenthesized( false ) {}
-
- void negate( bool parenthesize ) {
- negated = !negated;
- parenthesized = parenthesize;
- if( resultType == ResultWas::Ok )
- resultType = ResultWas::ExpressionFailed;
- else if( resultType == ResultWas::ExpressionFailed )
- resultType = ResultWas::Ok;
- }
-
- std::string const& reconstructExpression() const {
- if( decomposedExpression != CATCH_NULL ) {
- decomposedExpression->reconstructExpression( reconstructedExpression );
- if( parenthesized ) {
- reconstructedExpression.insert( 0, 1, '(' );
- reconstructedExpression.append( 1, ')' );
- }
- if( negated ) {
- reconstructedExpression.insert( 0, 1, '!' );
- }
- decomposedExpression = CATCH_NULL;
- }
- return reconstructedExpression;
- }
-
- mutable DecomposedExpression const* decomposedExpression;
- mutable std::string reconstructedExpression;
- std::string message;
- ResultWas::OfType resultType;
- bool negated;
- bool parenthesized;
- };
-
- class AssertionResult {
- public:
- AssertionResult();
- AssertionResult( AssertionInfo const& info, AssertionResultData const& data );
- ~AssertionResult();
-# ifdef CATCH_CONFIG_CPP11_GENERATED_METHODS
- AssertionResult( AssertionResult const& ) = default;
- AssertionResult( AssertionResult && ) = default;
- AssertionResult& operator = ( AssertionResult const& ) = default;
- AssertionResult& operator = ( AssertionResult && ) = default;
-# endif
-
- bool isOk() const;
- bool succeeded() const;
- ResultWas::OfType getResultType() const;
- bool hasExpression() const;
- bool hasMessage() const;
- std::string getExpression() const;
- std::string getExpressionInMacro() const;
- bool hasExpandedExpression() const;
- std::string getExpandedExpression() const;
- std::string getMessage() const;
- SourceLineInfo getSourceInfo() const;
- std::string getTestMacroName() const;
- void discardDecomposedExpression() const;
- void expandDecomposedExpression() const;
-
- protected:
- AssertionInfo m_info;
- AssertionResultData m_resultData;
- };
-
-} // end namespace Catch
-
-// #included from: catch_matchers.hpp
-#define TWOBLUECUBES_CATCH_MATCHERS_HPP_INCLUDED
-
-namespace Catch {
-namespace Matchers {
- namespace Impl {
-
- template<typename ArgT> struct MatchAllOf;
- template<typename ArgT> struct MatchAnyOf;
- template<typename ArgT> struct MatchNotOf;
-
- class MatcherUntypedBase {
- public:
- std::string toString() const {
- if( m_cachedToString.empty() )
- m_cachedToString = describe();
- return m_cachedToString;
- }
-
- protected:
- virtual ~MatcherUntypedBase();
- virtual std::string describe() const = 0;
- mutable std::string m_cachedToString;
- private:
- MatcherUntypedBase& operator = ( MatcherUntypedBase const& );
- };
-
- template<typename ObjectT>
- struct MatcherMethod {
- virtual bool match( ObjectT const& arg ) const = 0;
- };
- template<typename PtrT>
- struct MatcherMethod<PtrT*> {
- virtual bool match( PtrT* arg ) const = 0;
- };
-
- template<typename ObjectT, typename ComparatorT = ObjectT>
- struct MatcherBase : MatcherUntypedBase, MatcherMethod<ObjectT> {
-
- MatchAllOf<ComparatorT> operator && ( MatcherBase const& other ) const;
- MatchAnyOf<ComparatorT> operator || ( MatcherBase const& other ) const;
- MatchNotOf<ComparatorT> operator ! () const;
- };
-
- template<typename ArgT>
- struct MatchAllOf : MatcherBase<ArgT> {
- virtual bool match( ArgT const& arg ) const CATCH_OVERRIDE {
- for( std::size_t i = 0; i < m_matchers.size(); ++i ) {
- if (!m_matchers[i]->match(arg))
- return false;
- }
- return true;
- }
- virtual std::string describe() const CATCH_OVERRIDE {
- std::string description;
- description.reserve( 4 + m_matchers.size()*32 );
- description += "( ";
- for( std::size_t i = 0; i < m_matchers.size(); ++i ) {
- if( i != 0 )
- description += " and ";
- description += m_matchers[i]->toString();
- }
- description += " )";
- return description;
- }
-
- MatchAllOf<ArgT>& operator && ( MatcherBase<ArgT> const& other ) {
- m_matchers.push_back( &other );
- return *this;
- }
-
- std::vector<MatcherBase<ArgT> const*> m_matchers;
- };
- template<typename ArgT>
- struct MatchAnyOf : MatcherBase<ArgT> {
-
- virtual bool match( ArgT const& arg ) const CATCH_OVERRIDE {
- for( std::size_t i = 0; i < m_matchers.size(); ++i ) {
- if (m_matchers[i]->match(arg))
- return true;
- }
- return false;
- }
- virtual std::string describe() const CATCH_OVERRIDE {
- std::string description;
- description.reserve( 4 + m_matchers.size()*32 );
- description += "( ";
- for( std::size_t i = 0; i < m_matchers.size(); ++i ) {
- if( i != 0 )
- description += " or ";
- description += m_matchers[i]->toString();
- }
- description += " )";
- return description;
- }
-
- MatchAnyOf<ArgT>& operator || ( MatcherBase<ArgT> const& other ) {
- m_matchers.push_back( &other );
- return *this;
- }
-
- std::vector<MatcherBase<ArgT> const*> m_matchers;
- };
-
- template<typename ArgT>
- struct MatchNotOf : MatcherBase<ArgT> {
-
- MatchNotOf( MatcherBase<ArgT> const& underlyingMatcher ) : m_underlyingMatcher( underlyingMatcher ) {}
-
- virtual bool match( ArgT const& arg ) const CATCH_OVERRIDE {
- return !m_underlyingMatcher.match( arg );
- }
-
- virtual std::string describe() const CATCH_OVERRIDE {
- return "not " + m_underlyingMatcher.toString();
- }
- MatcherBase<ArgT> const& m_underlyingMatcher;
- };
-
- template<typename ObjectT, typename ComparatorT>
- MatchAllOf<ComparatorT> MatcherBase<ObjectT, ComparatorT>::operator && ( MatcherBase const& other ) const {
- return MatchAllOf<ComparatorT>() && *this && other;
- }
- template<typename ObjectT, typename ComparatorT>
- MatchAnyOf<ComparatorT> MatcherBase<ObjectT, ComparatorT>::operator || ( MatcherBase const& other ) const {
- return MatchAnyOf<ComparatorT>() || *this || other;
- }
- template<typename ObjectT, typename ComparatorT>
- MatchNotOf<ComparatorT> MatcherBase<ObjectT, ComparatorT>::operator ! () const {
- return MatchNotOf<ComparatorT>( *this );
- }
-
- } // namespace Impl
-
- // The following functions create the actual matcher objects.
- // This allows the types to be inferred
- // - deprecated: prefer ||, && and !
- template<typename T>
- Impl::MatchNotOf<T> Not( Impl::MatcherBase<T> const& underlyingMatcher ) {
- return Impl::MatchNotOf<T>( underlyingMatcher );
- }
- template<typename T>
- Impl::MatchAllOf<T> AllOf( Impl::MatcherBase<T> const& m1, Impl::MatcherBase<T> const& m2 ) {
- return Impl::MatchAllOf<T>() && m1 && m2;
- }
- template<typename T>
- Impl::MatchAllOf<T> AllOf( Impl::MatcherBase<T> const& m1, Impl::MatcherBase<T> const& m2, Impl::MatcherBase<T> const& m3 ) {
- return Impl::MatchAllOf<T>() && m1 && m2 && m3;
- }
- template<typename T>
- Impl::MatchAnyOf<T> AnyOf( Impl::MatcherBase<T> const& m1, Impl::MatcherBase<T> const& m2 ) {
- return Impl::MatchAnyOf<T>() || m1 || m2;
- }
- template<typename T>
- Impl::MatchAnyOf<T> AnyOf( Impl::MatcherBase<T> const& m1, Impl::MatcherBase<T> const& m2, Impl::MatcherBase<T> const& m3 ) {
- return Impl::MatchAnyOf<T>() || m1 || m2 || m3;
- }
-
-} // namespace Matchers
-
-using namespace Matchers;
-using Matchers::Impl::MatcherBase;
-
-} // namespace Catch
-
-namespace Catch {
-
- struct TestFailureException{};
-
- template<typename T> class ExpressionLhs;
-
- struct CopyableStream {
- CopyableStream() {}
- CopyableStream( CopyableStream const& other ) {
- oss << other.oss.str();
- }
- CopyableStream& operator=( CopyableStream const& other ) {
- oss.str(std::string());
- oss << other.oss.str();
- return *this;
- }
- std::ostringstream oss;
- };
-
- class ResultBuilder : public DecomposedExpression {
- public:
- ResultBuilder( char const* macroName,
- SourceLineInfo const& lineInfo,
- char const* capturedExpression,
- ResultDisposition::Flags resultDisposition,
- char const* secondArg = "" );
- ~ResultBuilder();
-
- template<typename T>
- ExpressionLhs<T const&> operator <= ( T const& operand );
- ExpressionLhs<bool> operator <= ( bool value );
-
- template<typename T>
- ResultBuilder& operator << ( T const& value ) {
- stream().oss << value;
- return *this;
- }
-
- ResultBuilder& setResultType( ResultWas::OfType result );
- ResultBuilder& setResultType( bool result );
-
- void endExpression( DecomposedExpression const& expr );
-
- virtual void reconstructExpression( std::string& dest ) const CATCH_OVERRIDE;
-
- AssertionResult build() const;
- AssertionResult build( DecomposedExpression const& expr ) const;
-
- void useActiveException( ResultDisposition::Flags resultDisposition = ResultDisposition::Normal );
- void captureResult( ResultWas::OfType resultType );
- void captureExpression();
- void captureExpectedException( std::string const& expectedMessage );
- void captureExpectedException( Matchers::Impl::MatcherBase<std::string> const& matcher );
- void handleResult( AssertionResult const& result );
- void react();
- bool shouldDebugBreak() const;
- bool allowThrows() const;
-
- template<typename ArgT, typename MatcherT>
- void captureMatch( ArgT const& arg, MatcherT const& matcher, char const* matcherString );
-
- void setExceptionGuard();
- void unsetExceptionGuard();
-
- private:
- AssertionInfo m_assertionInfo;
- AssertionResultData m_data;
-
- CopyableStream &stream()
- {
- if(!m_usedStream)
- {
- m_usedStream = true;
- m_stream().oss.str("");
- }
- return m_stream();
- }
-
- static CopyableStream &m_stream()
- {
- static CopyableStream s;
- return s;
- }
-
- bool m_shouldDebugBreak;
- bool m_shouldThrow;
- bool m_guardException;
- bool m_usedStream;
- };
-
-} // namespace Catch
-
-// Include after due to circular dependency:
-// #included from: catch_expression_lhs.hpp
-#define TWOBLUECUBES_CATCH_EXPRESSION_LHS_HPP_INCLUDED
-
-// #included from: catch_evaluate.hpp
-#define TWOBLUECUBES_CATCH_EVALUATE_HPP_INCLUDED
-
-#ifdef _MSC_VER
-#pragma warning(push)
-#pragma warning(disable:4389) // '==' : signed/unsigned mismatch
-#pragma warning(disable:4018) // more "signed/unsigned mismatch"
-#pragma warning(disable:4312) // Converting int to T* using reinterpret_cast (issue on x64 platform)
-#endif
-
-#include <cstddef>
-
-namespace Catch {
-namespace Internal {
-
- enum Operator {
- IsEqualTo,
- IsNotEqualTo,
- IsLessThan,
- IsGreaterThan,
- IsLessThanOrEqualTo,
- IsGreaterThanOrEqualTo
- };
-
- template<Operator Op> struct OperatorTraits { static const char* getName(){ return "*error*"; } };
- template<> struct OperatorTraits<IsEqualTo> { static const char* getName(){ return "=="; } };
- template<> struct OperatorTraits<IsNotEqualTo> { static const char* getName(){ return "!="; } };
- template<> struct OperatorTraits<IsLessThan> { static const char* getName(){ return "<"; } };
- template<> struct OperatorTraits<IsGreaterThan> { static const char* getName(){ return ">"; } };
- template<> struct OperatorTraits<IsLessThanOrEqualTo> { static const char* getName(){ return "<="; } };
- template<> struct OperatorTraits<IsGreaterThanOrEqualTo>{ static const char* getName(){ return ">="; } };
-
- template<typename T>
- T& opCast(T const& t) { return const_cast<T&>(t); }
-
-// nullptr_t support based on pull request #154 from Konstantin Baumann
-#ifdef CATCH_CONFIG_CPP11_NULLPTR
- inline std::nullptr_t opCast(std::nullptr_t) { return nullptr; }
-#endif // CATCH_CONFIG_CPP11_NULLPTR
-
- // So the compare overloads can be operator agnostic we convey the operator as a template
- // enum, which is used to specialise an Evaluator for doing the comparison.
- template<typename T1, typename T2, Operator Op>
- struct Evaluator{};
-
- template<typename T1, typename T2>
- struct Evaluator<T1, T2, IsEqualTo> {
- static bool evaluate( T1 const& lhs, T2 const& rhs) {
- return bool( opCast( lhs ) == opCast( rhs ) );
- }
- };
- template<typename T1, typename T2>
- struct Evaluator<T1, T2, IsNotEqualTo> {
- static bool evaluate( T1 const& lhs, T2 const& rhs ) {
- return bool( opCast( lhs ) != opCast( rhs ) );
- }
- };
- template<typename T1, typename T2>
- struct Evaluator<T1, T2, IsLessThan> {
- static bool evaluate( T1 const& lhs, T2 const& rhs ) {
- return bool( opCast( lhs ) < opCast( rhs ) );
- }
- };
- template<typename T1, typename T2>
- struct Evaluator<T1, T2, IsGreaterThan> {
- static bool evaluate( T1 const& lhs, T2 const& rhs ) {
- return bool( opCast( lhs ) > opCast( rhs ) );
- }
- };
- template<typename T1, typename T2>
- struct Evaluator<T1, T2, IsGreaterThanOrEqualTo> {
- static bool evaluate( T1 const& lhs, T2 const& rhs ) {
- return bool( opCast( lhs ) >= opCast( rhs ) );
- }
- };
- template<typename T1, typename T2>
- struct Evaluator<T1, T2, IsLessThanOrEqualTo> {
- static bool evaluate( T1 const& lhs, T2 const& rhs ) {
- return bool( opCast( lhs ) <= opCast( rhs ) );
- }
- };
-
- template<Operator Op, typename T1, typename T2>
- bool applyEvaluator( T1 const& lhs, T2 const& rhs ) {
- return Evaluator<T1, T2, Op>::evaluate( lhs, rhs );
- }
-
- // This level of indirection allows us to specialise for integer types
- // to avoid signed/ unsigned warnings
-
- // "base" overload
- template<Operator Op, typename T1, typename T2>
- bool compare( T1 const& lhs, T2 const& rhs ) {
- return Evaluator<T1, T2, Op>::evaluate( lhs, rhs );
- }
-
- // unsigned X to int
- template<Operator Op> bool compare( unsigned int lhs, int rhs ) {
- return applyEvaluator<Op>( lhs, static_cast<unsigned int>( rhs ) );
- }
- template<Operator Op> bool compare( unsigned long lhs, int rhs ) {
- return applyEvaluator<Op>( lhs, static_cast<unsigned int>( rhs ) );
- }
- template<Operator Op> bool compare( unsigned char lhs, int rhs ) {
- return applyEvaluator<Op>( lhs, static_cast<unsigned int>( rhs ) );
- }
-
- // unsigned X to long
- template<Operator Op> bool compare( unsigned int lhs, long rhs ) {
- return applyEvaluator<Op>( lhs, static_cast<unsigned long>( rhs ) );
- }
- template<Operator Op> bool compare( unsigned long lhs, long rhs ) {
- return applyEvaluator<Op>( lhs, static_cast<unsigned long>( rhs ) );
- }
- template<Operator Op> bool compare( unsigned char lhs, long rhs ) {
- return applyEvaluator<Op>( lhs, static_cast<unsigned long>( rhs ) );
- }
-
- // int to unsigned X
- template<Operator Op> bool compare( int lhs, unsigned int rhs ) {
- return applyEvaluator<Op>( static_cast<unsigned int>( lhs ), rhs );
- }
- template<Operator Op> bool compare( int lhs, unsigned long rhs ) {
- return applyEvaluator<Op>( static_cast<unsigned int>( lhs ), rhs );
- }
- template<Operator Op> bool compare( int lhs, unsigned char rhs ) {
- return applyEvaluator<Op>( static_cast<unsigned int>( lhs ), rhs );
- }
-
- // long to unsigned X
- template<Operator Op> bool compare( long lhs, unsigned int rhs ) {
- return applyEvaluator<Op>( static_cast<unsigned long>( lhs ), rhs );
- }
- template<Operator Op> bool compare( long lhs, unsigned long rhs ) {
- return applyEvaluator<Op>( static_cast<unsigned long>( lhs ), rhs );
- }
- template<Operator Op> bool compare( long lhs, unsigned char rhs ) {
- return applyEvaluator<Op>( static_cast<unsigned long>( lhs ), rhs );
- }
-
- // pointer to long (when comparing against NULL)
- template<Operator Op, typename T> bool compare( long lhs, T* rhs ) {
- return Evaluator<T*, T*, Op>::evaluate( reinterpret_cast<T*>( lhs ), rhs );
- }
- template<Operator Op, typename T> bool compare( T* lhs, long rhs ) {
- return Evaluator<T*, T*, Op>::evaluate( lhs, reinterpret_cast<T*>( rhs ) );
- }
-
- // pointer to int (when comparing against NULL)
- template<Operator Op, typename T> bool compare( int lhs, T* rhs ) {
- return Evaluator<T*, T*, Op>::evaluate( reinterpret_cast<T*>( lhs ), rhs );
- }
- template<Operator Op, typename T> bool compare( T* lhs, int rhs ) {
- return Evaluator<T*, T*, Op>::evaluate( lhs, reinterpret_cast<T*>( rhs ) );
- }
-
-#ifdef CATCH_CONFIG_CPP11_LONG_LONG
- // long long to unsigned X
- template<Operator Op> bool compare( long long lhs, unsigned int rhs ) {
- return applyEvaluator<Op>( static_cast<unsigned long>( lhs ), rhs );
- }
- template<Operator Op> bool compare( long long lhs, unsigned long rhs ) {
- return applyEvaluator<Op>( static_cast<unsigned long>( lhs ), rhs );
- }
- template<Operator Op> bool compare( long long lhs, unsigned long long rhs ) {
- return applyEvaluator<Op>( static_cast<unsigned long>( lhs ), rhs );
- }
- template<Operator Op> bool compare( long long lhs, unsigned char rhs ) {
- return applyEvaluator<Op>( static_cast<unsigned long>( lhs ), rhs );
- }
-
- // unsigned long long to X
- template<Operator Op> bool compare( unsigned long long lhs, int rhs ) {
- return applyEvaluator<Op>( static_cast<long>( lhs ), rhs );
- }
- template<Operator Op> bool compare( unsigned long long lhs, long rhs ) {
- return applyEvaluator<Op>( static_cast<long>( lhs ), rhs );
- }
- template<Operator Op> bool compare( unsigned long long lhs, long long rhs ) {
- return applyEvaluator<Op>( static_cast<long>( lhs ), rhs );
- }
- template<Operator Op> bool compare( unsigned long long lhs, char rhs ) {
- return applyEvaluator<Op>( static_cast<long>( lhs ), rhs );
- }
-
- // pointer to long long (when comparing against NULL)
- template<Operator Op, typename T> bool compare( long long lhs, T* rhs ) {
- return Evaluator<T*, T*, Op>::evaluate( reinterpret_cast<T*>( lhs ), rhs );
- }
- template<Operator Op, typename T> bool compare( T* lhs, long long rhs ) {
- return Evaluator<T*, T*, Op>::evaluate( lhs, reinterpret_cast<T*>( rhs ) );
- }
-#endif // CATCH_CONFIG_CPP11_LONG_LONG
-
-#ifdef CATCH_CONFIG_CPP11_NULLPTR
- // pointer to nullptr_t (when comparing against nullptr)
- template<Operator Op, typename T> bool compare( std::nullptr_t, T* rhs ) {
- return Evaluator<T*, T*, Op>::evaluate( nullptr, rhs );
- }
- template<Operator Op, typename T> bool compare( T* lhs, std::nullptr_t ) {
- return Evaluator<T*, T*, Op>::evaluate( lhs, nullptr );
- }
-#endif // CATCH_CONFIG_CPP11_NULLPTR
-
-} // end of namespace Internal
-} // end of namespace Catch
-
-#ifdef _MSC_VER
-#pragma warning(pop)
-#endif
-
-// #included from: catch_tostring.h
-#define TWOBLUECUBES_CATCH_TOSTRING_H_INCLUDED
-
-#include <sstream>
-#include <iomanip>
-#include <limits>
-#include <vector>
-#include <cstddef>
-
-#ifdef __OBJC__
-// #included from: catch_objc_arc.hpp
-#define TWOBLUECUBES_CATCH_OBJC_ARC_HPP_INCLUDED
-
-#import <Foundation/Foundation.h>
-
-#ifdef __has_feature
-#define CATCH_ARC_ENABLED __has_feature(objc_arc)
-#else
-#define CATCH_ARC_ENABLED 0
-#endif
-
-void arcSafeRelease( NSObject* obj );
-id performOptionalSelector( id obj, SEL sel );
-
-#if !CATCH_ARC_ENABLED
-inline void arcSafeRelease( NSObject* obj ) {
- [obj release];
-}
-inline id performOptionalSelector( id obj, SEL sel ) {
- if( [obj respondsToSelector: sel] )
- return [obj performSelector: sel];
- return nil;
-}
-#define CATCH_UNSAFE_UNRETAINED
-#define CATCH_ARC_STRONG
-#else
-inline void arcSafeRelease( NSObject* ){}
-inline id performOptionalSelector( id obj, SEL sel ) {
-#ifdef __clang__
-#pragma clang diagnostic push
-#pragma clang diagnostic ignored "-Warc-performSelector-leaks"
-#endif
- if( [obj respondsToSelector: sel] )
- return [obj performSelector: sel];
-#ifdef __clang__
-#pragma clang diagnostic pop
-#endif
- return nil;
-}
-#define CATCH_UNSAFE_UNRETAINED __unsafe_unretained
-#define CATCH_ARC_STRONG __strong
-#endif
-
-#endif
-
-#ifdef CATCH_CONFIG_CPP11_TUPLE
-#include <tuple>
-#endif
-
-#ifdef CATCH_CONFIG_CPP11_IS_ENUM
-#include <type_traits>
-#endif
-
-namespace Catch {
-
-// Why we're here.
-template<typename T>
-std::string toString( T const& value );
-
-// Built in overloads
-
-std::string toString( std::string const& value );
-std::string toString( std::wstring const& value );
-std::string toString( const char* const value );
-std::string toString( char* const value );
-std::string toString( const wchar_t* const value );
-std::string toString( wchar_t* const value );
-std::string toString( int value );
-std::string toString( unsigned long value );
-std::string toString( unsigned int value );
-std::string toString( const double value );
-std::string toString( const float value );
-std::string toString( bool value );
-std::string toString( char value );
-std::string toString( signed char value );
-std::string toString( unsigned char value );
-
-#ifdef CATCH_CONFIG_CPP11_LONG_LONG
-std::string toString( long long value );
-std::string toString( unsigned long long value );
-#endif
-
-#ifdef CATCH_CONFIG_CPP11_NULLPTR
-std::string toString( std::nullptr_t );
-#endif
-
-#ifdef __OBJC__
- std::string toString( NSString const * const& nsstring );
- std::string toString( NSString * CATCH_ARC_STRONG & nsstring );
- std::string toString( NSObject* const& nsObject );
-#endif
-
-namespace Detail {
-
- extern const std::string unprintableString;
-
- #if !defined(CATCH_CONFIG_CPP11_STREAM_INSERTABLE_CHECK)
- struct BorgType {
- template<typename T> BorgType( T const& );
- };
-
- struct TrueType { char sizer[1]; };
- struct FalseType { char sizer[2]; };
-
- TrueType& testStreamable( std::ostream& );
- FalseType testStreamable( FalseType );
-
- FalseType operator<<( std::ostream const&, BorgType const& );
-
- template<typename T>
- struct IsStreamInsertable {
- static std::ostream &s;
- static T const&t;
- enum { value = sizeof( testStreamable(s << t) ) == sizeof( TrueType ) };
- };
-#else
- template<typename T>
- class IsStreamInsertable {
- template<typename SS, typename TT>
- static auto test(int)
- -> decltype( std::declval<SS&>() << std::declval<TT>(), std::true_type() );
-
- template<typename, typename>
- static auto test(...) -> std::false_type;
-
- public:
- static const bool value = decltype(test<std::ostream,const T&>(0))::value;
- };
-#endif
-
-#if defined(CATCH_CONFIG_CPP11_IS_ENUM)
- template<typename T,
- bool IsEnum = std::is_enum<T>::value
- >
- struct EnumStringMaker
- {
- static std::string convert( T const& ) { return unprintableString; }
- };
-
- template<typename T>
- struct EnumStringMaker<T,true>
- {
- static std::string convert( T const& v )
- {
- return ::Catch::toString(
- static_cast<typename std::underlying_type<T>::type>(v)
- );
- }
- };
-#endif
- template<bool C>
- struct StringMakerBase {
-#if defined(CATCH_CONFIG_CPP11_IS_ENUM)
- template<typename T>
- static std::string convert( T const& v )
- {
- return EnumStringMaker<T>::convert( v );
- }
-#else
- template<typename T>
- static std::string convert( T const& ) { return unprintableString; }
-#endif
- };
-
- template<>
- struct StringMakerBase<true> {
- template<typename T>
- static std::string convert( T const& _value ) {
- std::ostringstream oss;
- oss << _value;
- return oss.str();
- }
- };
-
- std::string rawMemoryToString( const void *object, std::size_t size );
-
- template<typename T>
- std::string rawMemoryToString( const T& object ) {
- return rawMemoryToString( &object, sizeof(object) );
- }
-
-} // end namespace Detail
-
-template<typename T>
-struct StringMaker :
- Detail::StringMakerBase<Detail::IsStreamInsertable<T>::value> {};
-
-template<typename T>
-struct StringMaker<T*> {
- template<typename U>
- static std::string convert( U* p ) {
- if( !p )
- return "NULL";
- else
- return Detail::rawMemoryToString( p );
- }
-};
-
-template<typename R, typename C>
-struct StringMaker<R C::*> {
- static std::string convert( R C::* p ) {
- if( !p )
- return "NULL";
- else
- return Detail::rawMemoryToString( p );
- }
-};
-
-namespace Detail {
- template<typename InputIterator>
- std::string rangeToString( InputIterator first, InputIterator last );
-}
-
-//template<typename T, typename Allocator>
-//struct StringMaker<std::vector<T, Allocator> > {
-// static std::string convert( std::vector<T,Allocator> const& v ) {
-// return Detail::rangeToString( v.begin(), v.end() );
-// }
-//};
-
-template<typename T, typename Allocator>
-std::string toString( std::vector<T,Allocator> const& v ) {
- return Detail::rangeToString( v.begin(), v.end() );
-}
-
-#ifdef CATCH_CONFIG_CPP11_TUPLE
-
-// toString for tuples
-namespace TupleDetail {
- template<
- typename Tuple,
- std::size_t N = 0,
- bool = (N < std::tuple_size<Tuple>::value)
- >
- struct ElementPrinter {
- static void print( const Tuple& tuple, std::ostream& os )
- {
- os << ( N ? ", " : " " )
- << Catch::toString(std::get<N>(tuple));
- ElementPrinter<Tuple,N+1>::print(tuple,os);
- }
- };
-
- template<
- typename Tuple,
- std::size_t N
- >
- struct ElementPrinter<Tuple,N,false> {
- static void print( const Tuple&, std::ostream& ) {}
- };
-
-}
-
-template<typename ...Types>
-struct StringMaker<std::tuple<Types...>> {
-
- static std::string convert( const std::tuple<Types...>& tuple )
- {
- std::ostringstream os;
- os << '{';
- TupleDetail::ElementPrinter<std::tuple<Types...>>::print( tuple, os );
- os << " }";
- return os.str();
- }
-};
-#endif // CATCH_CONFIG_CPP11_TUPLE
-
-namespace Detail {
- template<typename T>
- std::string makeString( T const& value ) {
- return StringMaker<T>::convert( value );
- }
-} // end namespace Detail
-
-/// \brief converts any type to a string
-///
-/// The default template forwards on to ostringstream - except when an
-/// ostringstream overload does not exist - in which case it attempts to detect
-/// that and writes {?}.
-/// Overload (not specialise) this template for custom typs that you don't want
-/// to provide an ostream overload for.
-template<typename T>
-std::string toString( T const& value ) {
- return StringMaker<T>::convert( value );
-}
-
- namespace Detail {
- template<typename InputIterator>
- std::string rangeToString( InputIterator first, InputIterator last ) {
- std::ostringstream oss;
- oss << "{ ";
- if( first != last ) {
- oss << Catch::toString( *first );
- for( ++first ; first != last ; ++first )
- oss << ", " << Catch::toString( *first );
- }
- oss << " }";
- return oss.str();
- }
-}
-
-} // end namespace Catch
-
-namespace Catch {
-
-template<typename LhsT, Internal::Operator Op, typename RhsT>
-class BinaryExpression;
-
-template<typename ArgT, typename MatcherT>
-class MatchExpression;
-
-// Wraps the LHS of an expression and overloads comparison operators
-// for also capturing those and RHS (if any)
-template<typename T>
-class ExpressionLhs : public DecomposedExpression {
-public:
- ExpressionLhs( ResultBuilder& rb, T lhs ) : m_rb( rb ), m_lhs( lhs ), m_truthy(false) {}
-
- ExpressionLhs& operator = ( const ExpressionLhs& );
-
- template<typename RhsT>
- BinaryExpression<T, Internal::IsEqualTo, RhsT const&>
- operator == ( RhsT const& rhs ) {
- return captureExpression<Internal::IsEqualTo>( rhs );
- }
-
- template<typename RhsT>
- BinaryExpression<T, Internal::IsNotEqualTo, RhsT const&>
- operator != ( RhsT const& rhs ) {
- return captureExpression<Internal::IsNotEqualTo>( rhs );
- }
-
- template<typename RhsT>
- BinaryExpression<T, Internal::IsLessThan, RhsT const&>
- operator < ( RhsT const& rhs ) {
- return captureExpression<Internal::IsLessThan>( rhs );
- }
-
- template<typename RhsT>
- BinaryExpression<T, Internal::IsGreaterThan, RhsT const&>
- operator > ( RhsT const& rhs ) {
- return captureExpression<Internal::IsGreaterThan>( rhs );
- }
-
- template<typename RhsT>
- BinaryExpression<T, Internal::IsLessThanOrEqualTo, RhsT const&>
- operator <= ( RhsT const& rhs ) {
- return captureExpression<Internal::IsLessThanOrEqualTo>( rhs );
- }
-
- template<typename RhsT>
- BinaryExpression<T, Internal::IsGreaterThanOrEqualTo, RhsT const&>
- operator >= ( RhsT const& rhs ) {
- return captureExpression<Internal::IsGreaterThanOrEqualTo>( rhs );
- }
-
- BinaryExpression<T, Internal::IsEqualTo, bool> operator == ( bool rhs ) {
- return captureExpression<Internal::IsEqualTo>( rhs );
- }
-
- BinaryExpression<T, Internal::IsNotEqualTo, bool> operator != ( bool rhs ) {
- return captureExpression<Internal::IsNotEqualTo>( rhs );
- }
-
- void endExpression() {
- m_truthy = m_lhs ? true : false;
- m_rb
- .setResultType( m_truthy )
- .endExpression( *this );
- }
-
- virtual void reconstructExpression( std::string& dest ) const CATCH_OVERRIDE {
- dest = Catch::toString( m_lhs );
- }
-
-private:
- template<Internal::Operator Op, typename RhsT>
- BinaryExpression<T, Op, RhsT&> captureExpression( RhsT& rhs ) const {
- return BinaryExpression<T, Op, RhsT&>( m_rb, m_lhs, rhs );
- }
-
- template<Internal::Operator Op>
- BinaryExpression<T, Op, bool> captureExpression( bool rhs ) const {
- return BinaryExpression<T, Op, bool>( m_rb, m_lhs, rhs );
- }
-
-private:
- ResultBuilder& m_rb;
- T m_lhs;
- bool m_truthy;
-};
-
-template<typename LhsT, Internal::Operator Op, typename RhsT>
-class BinaryExpression : public DecomposedExpression {
-public:
- BinaryExpression( ResultBuilder& rb, LhsT lhs, RhsT rhs )
- : m_rb( rb ), m_lhs( lhs ), m_rhs( rhs ) {}
-
- BinaryExpression& operator = ( BinaryExpression& );
-
- void endExpression() const {
- m_rb
- .setResultType( Internal::compare<Op>( m_lhs, m_rhs ) )
- .endExpression( *this );
- }
-
- virtual bool isBinaryExpression() const CATCH_OVERRIDE {
- return true;
- }
-
- virtual void reconstructExpression( std::string& dest ) const CATCH_OVERRIDE {
- std::string lhs = Catch::toString( m_lhs );
- std::string rhs = Catch::toString( m_rhs );
- char delim = lhs.size() + rhs.size() < 40 &&
- lhs.find('\n') == std::string::npos &&
- rhs.find('\n') == std::string::npos ? ' ' : '\n';
- dest.reserve( 7 + lhs.size() + rhs.size() );
- // 2 for spaces around operator
- // 2 for operator
- // 2 for parentheses (conditionally added later)
- // 1 for negation (conditionally added later)
- dest = lhs;
- dest += delim;
- dest += Internal::OperatorTraits<Op>::getName();
- dest += delim;
- dest += rhs;
- }
-
-private:
- ResultBuilder& m_rb;
- LhsT m_lhs;
- RhsT m_rhs;
-};
-
-template<typename ArgT, typename MatcherT>
-class MatchExpression : public DecomposedExpression {
-public:
- MatchExpression( ArgT arg, MatcherT matcher, char const* matcherString )
- : m_arg( arg ), m_matcher( matcher ), m_matcherString( matcherString ) {}
-
- virtual bool isBinaryExpression() const CATCH_OVERRIDE {
- return true;
- }
-
- virtual void reconstructExpression( std::string& dest ) const CATCH_OVERRIDE {
- std::string matcherAsString = m_matcher.toString();
- dest = Catch::toString( m_arg );
- dest += ' ';
- if( matcherAsString == Detail::unprintableString )
- dest += m_matcherString;
- else
- dest += matcherAsString;
- }
-
-private:
- ArgT m_arg;
- MatcherT m_matcher;
- char const* m_matcherString;
-};
-
-} // end namespace Catch
-
-
-namespace Catch {
-
- template<typename T>
- ExpressionLhs<T const&> ResultBuilder::operator <= ( T const& operand ) {
- return ExpressionLhs<T const&>( *this, operand );
- }
-
- inline ExpressionLhs<bool> ResultBuilder::operator <= ( bool value ) {
- return ExpressionLhs<bool>( *this, value );
- }
-
- template<typename ArgT, typename MatcherT>
- void ResultBuilder::captureMatch( ArgT const& arg, MatcherT const& matcher,
- char const* matcherString ) {
- MatchExpression<ArgT const&, MatcherT const&> expr( arg, matcher, matcherString );
- setResultType( matcher.match( arg ) );
- endExpression( expr );
- }
-
-} // namespace Catch
-
-// #included from: catch_message.h
-#define TWOBLUECUBES_CATCH_MESSAGE_H_INCLUDED
-
-#include <string>
-
-namespace Catch {
-
- struct MessageInfo {
- MessageInfo( std::string const& _macroName,
- SourceLineInfo const& _lineInfo,
- ResultWas::OfType _type );
-
- std::string macroName;
- SourceLineInfo lineInfo;
- ResultWas::OfType type;
- std::string message;
- unsigned int sequence;
-
- bool operator == ( MessageInfo const& other ) const {
- return sequence == other.sequence;
- }
- bool operator < ( MessageInfo const& other ) const {
- return sequence < other.sequence;
- }
- private:
- static unsigned int globalCount;
- };
-
- struct MessageBuilder {
- MessageBuilder( std::string const& macroName,
- SourceLineInfo const& lineInfo,
- ResultWas::OfType type )
- : m_info( macroName, lineInfo, type )
- {}
-
- template<typename T>
- MessageBuilder& operator << ( T const& value ) {
- m_stream << value;
- return *this;
- }
-
- MessageInfo m_info;
- std::ostringstream m_stream;
- };
-
- class ScopedMessage {
- public:
- ScopedMessage( MessageBuilder const& builder );
- ScopedMessage( ScopedMessage const& other );
- ~ScopedMessage();
-
- MessageInfo m_info;
- };
-
-} // end namespace Catch
-
-// #included from: catch_interfaces_capture.h
-#define TWOBLUECUBES_CATCH_INTERFACES_CAPTURE_H_INCLUDED
-
-#include <string>
-
-namespace Catch {
-
- class TestCase;
- class AssertionResult;
- struct AssertionInfo;
- struct SectionInfo;
- struct SectionEndInfo;
- struct MessageInfo;
- class ScopedMessageBuilder;
- struct Counts;
-
- struct IResultCapture {
-
- virtual ~IResultCapture();
-
- virtual void assertionEnded( AssertionResult const& result ) = 0;
- virtual bool sectionStarted( SectionInfo const& sectionInfo,
- Counts& assertions ) = 0;
- virtual void sectionEnded( SectionEndInfo const& endInfo ) = 0;
- virtual void sectionEndedEarly( SectionEndInfo const& endInfo ) = 0;
- virtual void pushScopedMessage( MessageInfo const& message ) = 0;
- virtual void popScopedMessage( MessageInfo const& message ) = 0;
-
- virtual std::string getCurrentTestName() const = 0;
- virtual const AssertionResult* getLastResult() const = 0;
-
- virtual void exceptionEarlyReported() = 0;
-
- virtual void handleFatalErrorCondition( std::string const& message ) = 0;
-
- virtual bool lastAssertionPassed() = 0;
- virtual void assertionPassed() = 0;
- virtual void assertionRun() = 0;
- };
-
- IResultCapture& getResultCapture();
-}
-
-// #included from: catch_debugger.h
-#define TWOBLUECUBES_CATCH_DEBUGGER_H_INCLUDED
-
-// #included from: catch_platform.h
-#define TWOBLUECUBES_CATCH_PLATFORM_H_INCLUDED
-
-#if defined(__MAC_OS_X_VERSION_MIN_REQUIRED)
-# define CATCH_PLATFORM_MAC
-#elif defined(__IPHONE_OS_VERSION_MIN_REQUIRED)
-# define CATCH_PLATFORM_IPHONE
-#elif defined(linux) || defined(__linux) || defined(__linux__)
-# define CATCH_PLATFORM_LINUX
-#elif defined(WIN32) || defined(__WIN32__) || defined(_WIN32) || defined(_MSC_VER)
-# define CATCH_PLATFORM_WINDOWS
-# if !defined(NOMINMAX) && !defined(CATCH_CONFIG_NO_NOMINMAX)
-# define CATCH_DEFINES_NOMINMAX
-# endif
-# if !defined(WIN32_LEAN_AND_MEAN) && !defined(CATCH_CONFIG_NO_WIN32_LEAN_AND_MEAN)
-# define CATCH_DEFINES_WIN32_LEAN_AND_MEAN
-# endif
-#endif
-
-#include <string>
-
-namespace Catch{
-
- bool isDebuggerActive();
- void writeToDebugConsole( std::string const& text );
-}
-
-#ifdef CATCH_PLATFORM_MAC
-
- // The following code snippet based on:
- // http://cocoawithlove.com/2008/03/break-into-debugger.html
- #if defined(__ppc64__) || defined(__ppc__)
- #define CATCH_TRAP() \
- __asm__("li r0, 20\nsc\nnop\nli r0, 37\nli r4, 2\nsc\nnop\n" \
- : : : "memory","r0","r3","r4" ) /* NOLINT */
- #else
- #define CATCH_TRAP() __asm__("int $3\n" : : /* NOLINT */ )
- #endif
-
-#elif defined(CATCH_PLATFORM_LINUX)
- // If we can use inline assembler, do it because this allows us to break
- // directly at the location of the failing check instead of breaking inside
- // raise() called from it, i.e. one stack frame below.
- #if defined(__GNUC__) && (defined(__i386) || defined(__x86_64))
- #define CATCH_TRAP() asm volatile ("int $3") /* NOLINT */
- #else // Fall back to the generic way.
- #include <signal.h>
-
- #define CATCH_TRAP() raise(SIGTRAP)
- #endif
-#elif defined(_MSC_VER)
- #define CATCH_TRAP() __debugbreak()
-#elif defined(__MINGW32__)
- extern "C" __declspec(dllimport) void __stdcall DebugBreak();
- #define CATCH_TRAP() DebugBreak()
-#endif
-
-#ifdef CATCH_TRAP
- #define CATCH_BREAK_INTO_DEBUGGER() if( Catch::isDebuggerActive() ) { CATCH_TRAP(); }
-#else
- #define CATCH_BREAK_INTO_DEBUGGER() Catch::alwaysTrue();
-#endif
-
-// #included from: catch_interfaces_runner.h
-#define TWOBLUECUBES_CATCH_INTERFACES_RUNNER_H_INCLUDED
-
-namespace Catch {
- class TestCase;
-
- struct IRunner {
- virtual ~IRunner();
- virtual bool aborting() const = 0;
- };
-}
-
-#if !defined(CATCH_CONFIG_DISABLE_STRINGIFICATION)
-# define CATCH_INTERNAL_STRINGIFY(expr) #expr
-#else
-# define CATCH_INTERNAL_STRINGIFY(expr) "Disabled by CATCH_CONFIG_DISABLE_STRINGIFICATION"
-#endif
-
-#if defined(CATCH_CONFIG_FAST_COMPILE)
-///////////////////////////////////////////////////////////////////////////////
-// We can speedup compilation significantly by breaking into debugger lower in
-// the callstack, because then we don't have to expand CATCH_BREAK_INTO_DEBUGGER
-// macro in each assertion
-#define INTERNAL_CATCH_REACT( resultBuilder ) \
- resultBuilder.react();
-
-///////////////////////////////////////////////////////////////////////////////
-// Another way to speed-up compilation is to omit local try-catch for REQUIRE*
-// macros.
-// This can potentially cause false negative, if the test code catches
-// the exception before it propagates back up to the runner.
-#define INTERNAL_CATCH_TEST_NO_TRY( macroName, resultDisposition, expr ) \
- do { \
- Catch::ResultBuilder __catchResult( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(expr), resultDisposition ); \
- __catchResult.setExceptionGuard(); \
- CATCH_INTERNAL_SUPPRESS_PARENTHESES_WARNINGS \
- ( __catchResult <= expr ).endExpression(); \
- CATCH_INTERNAL_UNSUPPRESS_PARENTHESES_WARNINGS \
- __catchResult.unsetExceptionGuard(); \
- INTERNAL_CATCH_REACT( __catchResult ) \
- } while( Catch::isTrue( false && static_cast<bool>( !!(expr) ) ) ) // expr here is never evaluated at runtime but it forces the compiler to give it a look
-// The double negation silences MSVC's C4800 warning, the static_cast forces short-circuit evaluation if the type has overloaded &&.
-
-#define INTERNAL_CHECK_THAT_NO_TRY( macroName, matcher, resultDisposition, arg ) \
- do { \
- Catch::ResultBuilder __catchResult( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(arg) ", " CATCH_INTERNAL_STRINGIFY(matcher), resultDisposition ); \
- __catchResult.setExceptionGuard(); \
- __catchResult.captureMatch( arg, matcher, CATCH_INTERNAL_STRINGIFY(matcher) ); \
- __catchResult.unsetExceptionGuard(); \
- INTERNAL_CATCH_REACT( __catchResult ) \
- } while( Catch::alwaysFalse() )
-
-#else
-///////////////////////////////////////////////////////////////////////////////
-// In the event of a failure works out if the debugger needs to be invoked
-// and/or an exception thrown and takes appropriate action.
-// This needs to be done as a macro so the debugger will stop in the user
-// source code rather than in Catch library code
-#define INTERNAL_CATCH_REACT( resultBuilder ) \
- if( resultBuilder.shouldDebugBreak() ) CATCH_BREAK_INTO_DEBUGGER(); \
- resultBuilder.react();
-#endif
-
-///////////////////////////////////////////////////////////////////////////////
-#define INTERNAL_CATCH_TEST( macroName, resultDisposition, expr ) \
- do { \
- Catch::ResultBuilder __catchResult( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(expr), resultDisposition ); \
- try { \
- CATCH_INTERNAL_SUPPRESS_PARENTHESES_WARNINGS \
- ( __catchResult <= expr ).endExpression(); \
- CATCH_INTERNAL_UNSUPPRESS_PARENTHESES_WARNINGS \
- } \
- catch( ... ) { \
- __catchResult.useActiveException( resultDisposition ); \
- } \
- INTERNAL_CATCH_REACT( __catchResult ) \
- } while( Catch::isTrue( false && static_cast<bool>( !!(expr) ) ) ) // expr here is never evaluated at runtime but it forces the compiler to give it a look
- // The double negation silences MSVC's C4800 warning, the static_cast forces short-circuit evaluation if the type has overloaded &&.
-
-///////////////////////////////////////////////////////////////////////////////
-#define INTERNAL_CATCH_IF( macroName, resultDisposition, expr ) \
- INTERNAL_CATCH_TEST( macroName, resultDisposition, expr ); \
- if( Catch::getResultCapture().lastAssertionPassed() )
-
-///////////////////////////////////////////////////////////////////////////////
-#define INTERNAL_CATCH_ELSE( macroName, resultDisposition, expr ) \
- INTERNAL_CATCH_TEST( macroName, resultDisposition, expr ); \
- if( !Catch::getResultCapture().lastAssertionPassed() )
-
-///////////////////////////////////////////////////////////////////////////////
-#define INTERNAL_CATCH_NO_THROW( macroName, resultDisposition, expr ) \
- do { \
- Catch::ResultBuilder __catchResult( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(expr), resultDisposition ); \
- try { \
- static_cast<void>(expr); \
- __catchResult.captureResult( Catch::ResultWas::Ok ); \
- } \
- catch( ... ) { \
- __catchResult.useActiveException( resultDisposition ); \
- } \
- INTERNAL_CATCH_REACT( __catchResult ) \
- } while( Catch::alwaysFalse() )
-
-///////////////////////////////////////////////////////////////////////////////
-#define INTERNAL_CATCH_THROWS( macroName, resultDisposition, matcher, expr ) \
- do { \
- Catch::ResultBuilder __catchResult( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(expr), resultDisposition, CATCH_INTERNAL_STRINGIFY(matcher) ); \
- if( __catchResult.allowThrows() ) \
- try { \
- static_cast<void>(expr); \
- __catchResult.captureResult( Catch::ResultWas::DidntThrowException ); \
- } \
- catch( ... ) { \
- __catchResult.captureExpectedException( matcher ); \
- } \
- else \
- __catchResult.captureResult( Catch::ResultWas::Ok ); \
- INTERNAL_CATCH_REACT( __catchResult ) \
- } while( Catch::alwaysFalse() )
-
-///////////////////////////////////////////////////////////////////////////////
-#define INTERNAL_CATCH_THROWS_AS( macroName, exceptionType, resultDisposition, expr ) \
- do { \
- Catch::ResultBuilder __catchResult( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(expr) ", " CATCH_INTERNAL_STRINGIFY(exceptionType), resultDisposition ); \
- if( __catchResult.allowThrows() ) \
- try { \
- static_cast<void>(expr); \
- __catchResult.captureResult( Catch::ResultWas::DidntThrowException ); \
- } \
- catch( exceptionType ) { \
- __catchResult.captureResult( Catch::ResultWas::Ok ); \
- } \
- catch( ... ) { \
- __catchResult.useActiveException( resultDisposition ); \
- } \
- else \
- __catchResult.captureResult( Catch::ResultWas::Ok ); \
- INTERNAL_CATCH_REACT( __catchResult ) \
- } while( Catch::alwaysFalse() )
-
-///////////////////////////////////////////////////////////////////////////////
-#ifdef CATCH_CONFIG_VARIADIC_MACROS
- #define INTERNAL_CATCH_MSG( macroName, messageType, resultDisposition, ... ) \
- do { \
- Catch::ResultBuilder __catchResult( macroName, CATCH_INTERNAL_LINEINFO, "", resultDisposition ); \
- __catchResult << __VA_ARGS__ + ::Catch::StreamEndStop(); \
- __catchResult.captureResult( messageType ); \
- INTERNAL_CATCH_REACT( __catchResult ) \
- } while( Catch::alwaysFalse() )
-#else
- #define INTERNAL_CATCH_MSG( macroName, messageType, resultDisposition, log ) \
- do { \
- Catch::ResultBuilder __catchResult( macroName, CATCH_INTERNAL_LINEINFO, "", resultDisposition ); \
- __catchResult << log + ::Catch::StreamEndStop(); \
- __catchResult.captureResult( messageType ); \
- INTERNAL_CATCH_REACT( __catchResult ) \
- } while( Catch::alwaysFalse() )
-#endif
-
-///////////////////////////////////////////////////////////////////////////////
-#define INTERNAL_CATCH_INFO( macroName, log ) \
- Catch::ScopedMessage INTERNAL_CATCH_UNIQUE_NAME( scopedMessage ) = Catch::MessageBuilder( macroName, CATCH_INTERNAL_LINEINFO, Catch::ResultWas::Info ) << log;
-
-///////////////////////////////////////////////////////////////////////////////
-#define INTERNAL_CHECK_THAT( macroName, matcher, resultDisposition, arg ) \
- do { \
- Catch::ResultBuilder __catchResult( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(arg) ", " CATCH_INTERNAL_STRINGIFY(matcher), resultDisposition ); \
- try { \
- __catchResult.captureMatch( arg, matcher, CATCH_INTERNAL_STRINGIFY(matcher) ); \
- } catch( ... ) { \
- __catchResult.useActiveException( resultDisposition | Catch::ResultDisposition::ContinueOnFailure ); \
- } \
- INTERNAL_CATCH_REACT( __catchResult ) \
- } while( Catch::alwaysFalse() )
-
-// #included from: internal/catch_section.h
-#define TWOBLUECUBES_CATCH_SECTION_H_INCLUDED
-
-// #included from: catch_section_info.h
-#define TWOBLUECUBES_CATCH_SECTION_INFO_H_INCLUDED
-
-// #included from: catch_totals.hpp
-#define TWOBLUECUBES_CATCH_TOTALS_HPP_INCLUDED
-
-#include <cstddef>
-
-namespace Catch {
-
- struct Counts {
- Counts() : passed( 0 ), failed( 0 ), failedButOk( 0 ) {}
-
- Counts operator - ( Counts const& other ) const {
- Counts diff;
- diff.passed = passed - other.passed;
- diff.failed = failed - other.failed;
- diff.failedButOk = failedButOk - other.failedButOk;
- return diff;
- }
- Counts& operator += ( Counts const& other ) {
- passed += other.passed;
- failed += other.failed;
- failedButOk += other.failedButOk;
- return *this;
- }
-
- std::size_t total() const {
- return passed + failed + failedButOk;
- }
- bool allPassed() const {
- return failed == 0 && failedButOk == 0;
- }
- bool allOk() const {
- return failed == 0;
- }
-
- std::size_t passed;
- std::size_t failed;
- std::size_t failedButOk;
- };
-
- struct Totals {
-
- Totals operator - ( Totals const& other ) const {
- Totals diff;
- diff.assertions = assertions - other.assertions;
- diff.testCases = testCases - other.testCases;
- return diff;
- }
-
- Totals delta( Totals const& prevTotals ) const {
- Totals diff = *this - prevTotals;
- if( diff.assertions.failed > 0 )
- ++diff.testCases.failed;
- else if( diff.assertions.failedButOk > 0 )
- ++diff.testCases.failedButOk;
- else
- ++diff.testCases.passed;
- return diff;
- }
-
- Totals& operator += ( Totals const& other ) {
- assertions += other.assertions;
- testCases += other.testCases;
- return *this;
- }
-
- Counts assertions;
- Counts testCases;
- };
-}
-
-#include <string>
-
-namespace Catch {
-
- struct SectionInfo {
- SectionInfo
- ( SourceLineInfo const& _lineInfo,
- std::string const& _name,
- std::string const& _description = std::string() );
-
- std::string name;
- std::string description;
- SourceLineInfo lineInfo;
- };
-
- struct SectionEndInfo {
- SectionEndInfo( SectionInfo const& _sectionInfo, Counts const& _prevAssertions, double _durationInSeconds )
- : sectionInfo( _sectionInfo ), prevAssertions( _prevAssertions ), durationInSeconds( _durationInSeconds )
- {}
-
- SectionInfo sectionInfo;
- Counts prevAssertions;
- double durationInSeconds;
- };
-
-} // end namespace Catch
-
-// #included from: catch_timer.h
-#define TWOBLUECUBES_CATCH_TIMER_H_INCLUDED
-
-#ifdef _MSC_VER
-
-namespace Catch {
- typedef unsigned long long UInt64;
-}
-#else
-#include <stdint.h>
-namespace Catch {
- typedef uint64_t UInt64;
-}
-#endif
-
-namespace Catch {
- class Timer {
- public:
- Timer() : m_ticks( 0 ) {}
- void start();
- unsigned int getElapsedMicroseconds() const;
- unsigned int getElapsedMilliseconds() const;
- double getElapsedSeconds() const;
-
- private:
- UInt64 m_ticks;
- };
-
-} // namespace Catch
-
-#include <string>
-
-namespace Catch {
-
- class Section : NonCopyable {
- public:
- Section( SectionInfo const& info );
- ~Section();
-
- // This indicates whether the section should be executed or not
- operator bool() const;
-
- private:
- SectionInfo m_info;
-
- std::string m_name;
- Counts m_assertions;
- bool m_sectionIncluded;
- Timer m_timer;
- };
-
-} // end namespace Catch
-
-#ifdef CATCH_CONFIG_VARIADIC_MACROS
- #define INTERNAL_CATCH_SECTION( ... ) \
- if( Catch::Section const& INTERNAL_CATCH_UNIQUE_NAME( catch_internal_Section ) = Catch::SectionInfo( CATCH_INTERNAL_LINEINFO, __VA_ARGS__ ) )
-#else
- #define INTERNAL_CATCH_SECTION( name, desc ) \
- if( Catch::Section const& INTERNAL_CATCH_UNIQUE_NAME( catch_internal_Section ) = Catch::SectionInfo( CATCH_INTERNAL_LINEINFO, name, desc ) )
-#endif
-
-// #included from: internal/catch_generators.hpp
-#define TWOBLUECUBES_CATCH_GENERATORS_HPP_INCLUDED
-
-#include <vector>
-#include <string>
-#include <stdlib.h>
-
-namespace Catch {
-
-template<typename T>
-struct IGenerator {
- virtual ~IGenerator() {}
- virtual T getValue( std::size_t index ) const = 0;
- virtual std::size_t size () const = 0;
-};
-
-template<typename T>
-class BetweenGenerator : public IGenerator<T> {
-public:
- BetweenGenerator( T from, T to ) : m_from( from ), m_to( to ){}
-
- virtual T getValue( std::size_t index ) const {
- return m_from+static_cast<int>( index );
- }
-
- virtual std::size_t size() const {
- return static_cast<std::size_t>( 1+m_to-m_from );
- }
-
-private:
-
- T m_from;
- T m_to;
-};
-
-template<typename T>
-class ValuesGenerator : public IGenerator<T> {
-public:
- ValuesGenerator(){}
-
- void add( T value ) {
- m_values.push_back( value );
- }
-
- virtual T getValue( std::size_t index ) const {
- return m_values[index];
- }
-
- virtual std::size_t size() const {
- return m_values.size();
- }
-
-private:
- std::vector<T> m_values;
-};
-
-template<typename T>
-class CompositeGenerator {
-public:
- CompositeGenerator() : m_totalSize( 0 ) {}
-
- // *** Move semantics, similar to auto_ptr ***
- CompositeGenerator( CompositeGenerator& other )
- : m_fileInfo( other.m_fileInfo ),
- m_totalSize( 0 )
- {
- move( other );
- }
-
- CompositeGenerator& setFileInfo( const char* fileInfo ) {
- m_fileInfo = fileInfo;
- return *this;
- }
-
- ~CompositeGenerator() {
- deleteAll( m_composed );
- }
-
- operator T () const {
- size_t overallIndex = getCurrentContext().getGeneratorIndex( m_fileInfo, m_totalSize );
-
- typename std::vector<const IGenerator<T>*>::const_iterator it = m_composed.begin();
- typename std::vector<const IGenerator<T>*>::const_iterator itEnd = m_composed.end();
- for( size_t index = 0; it != itEnd; ++it )
- {
- const IGenerator<T>* generator = *it;
- if( overallIndex >= index && overallIndex < index + generator->size() )
- {
- return generator->getValue( overallIndex-index );
- }
- index += generator->size();
- }
- CATCH_INTERNAL_ERROR( "Indexed past end of generated range" );
- return T(); // Suppress spurious "not all control paths return a value" warning in Visual Studio - if you know how to fix this please do so
- }
-
- void add( const IGenerator<T>* generator ) {
- m_totalSize += generator->size();
- m_composed.push_back( generator );
- }
-
- CompositeGenerator& then( CompositeGenerator& other ) {
- move( other );
- return *this;
- }
-
- CompositeGenerator& then( T value ) {
- ValuesGenerator<T>* valuesGen = new ValuesGenerator<T>();
- valuesGen->add( value );
- add( valuesGen );
- return *this;
- }
-
-private:
-
- void move( CompositeGenerator& other ) {
- m_composed.insert( m_composed.end(), other.m_composed.begin(), other.m_composed.end() );
- m_totalSize += other.m_totalSize;
- other.m_composed.clear();
- }
-
- std::vector<const IGenerator<T>*> m_composed;
- std::string m_fileInfo;
- size_t m_totalSize;
-};
-
-namespace Generators
-{
- template<typename T>
- CompositeGenerator<T> between( T from, T to ) {
- CompositeGenerator<T> generators;
- generators.add( new BetweenGenerator<T>( from, to ) );
- return generators;
- }
-
- template<typename T>
- CompositeGenerator<T> values( T val1, T val2 ) {
- CompositeGenerator<T> generators;
- ValuesGenerator<T>* valuesGen = new ValuesGenerator<T>();
- valuesGen->add( val1 );
- valuesGen->add( val2 );
- generators.add( valuesGen );
- return generators;
- }
-
- template<typename T>
- CompositeGenerator<T> values( T val1, T val2, T val3 ){
- CompositeGenerator<T> generators;
- ValuesGenerator<T>* valuesGen = new ValuesGenerator<T>();
- valuesGen->add( val1 );
- valuesGen->add( val2 );
- valuesGen->add( val3 );
- generators.add( valuesGen );
- return generators;
- }
-
- template<typename T>
- CompositeGenerator<T> values( T val1, T val2, T val3, T val4 ) {
- CompositeGenerator<T> generators;
- ValuesGenerator<T>* valuesGen = new ValuesGenerator<T>();
- valuesGen->add( val1 );
- valuesGen->add( val2 );
- valuesGen->add( val3 );
- valuesGen->add( val4 );
- generators.add( valuesGen );
- return generators;
- }
-
-} // end namespace Generators
-
-using namespace Generators;
-
-} // end namespace Catch
-
-#define INTERNAL_CATCH_LINESTR2( line ) #line
-#define INTERNAL_CATCH_LINESTR( line ) INTERNAL_CATCH_LINESTR2( line )
-
-#define INTERNAL_CATCH_GENERATE( expr ) expr.setFileInfo( __FILE__ "(" INTERNAL_CATCH_LINESTR( __LINE__ ) ")" )
-
-// #included from: internal/catch_interfaces_exception.h
-#define TWOBLUECUBES_CATCH_INTERFACES_EXCEPTION_H_INCLUDED
-
-#include <string>
-#include <vector>
-
-// #included from: catch_interfaces_registry_hub.h
-#define TWOBLUECUBES_CATCH_INTERFACES_REGISTRY_HUB_H_INCLUDED
-
-#include <string>
-
-namespace Catch {
-
- class TestCase;
- struct ITestCaseRegistry;
- struct IExceptionTranslatorRegistry;
- struct IExceptionTranslator;
- struct IReporterRegistry;
- struct IReporterFactory;
- struct ITagAliasRegistry;
-
- struct IRegistryHub {
- virtual ~IRegistryHub();
-
- virtual IReporterRegistry const& getReporterRegistry() const = 0;
- virtual ITestCaseRegistry const& getTestCaseRegistry() const = 0;
- virtual ITagAliasRegistry const& getTagAliasRegistry() const = 0;
-
- virtual IExceptionTranslatorRegistry& getExceptionTranslatorRegistry() = 0;
- };
-
- struct IMutableRegistryHub {
- virtual ~IMutableRegistryHub();
- virtual void registerReporter( std::string const& name, Ptr<IReporterFactory> const& factory ) = 0;
- virtual void registerListener( Ptr<IReporterFactory> const& factory ) = 0;
- virtual void registerTest( TestCase const& testInfo ) = 0;
- virtual void registerTranslator( const IExceptionTranslator* translator ) = 0;
- virtual void registerTagAlias( std::string const& alias, std::string const& tag, SourceLineInfo const& lineInfo ) = 0;
- };
-
- IRegistryHub& getRegistryHub();
- IMutableRegistryHub& getMutableRegistryHub();
- void cleanUp();
- std::string translateActiveException();
-
-}
-
-namespace Catch {
-
- typedef std::string(*exceptionTranslateFunction)();
-
- struct IExceptionTranslator;
- typedef std::vector<const IExceptionTranslator*> ExceptionTranslators;
-
- struct IExceptionTranslator {
- virtual ~IExceptionTranslator();
- virtual std::string translate( ExceptionTranslators::const_iterator it, ExceptionTranslators::const_iterator itEnd ) const = 0;
- };
-
- struct IExceptionTranslatorRegistry {
- virtual ~IExceptionTranslatorRegistry();
-
- virtual std::string translateActiveException() const = 0;
- };
-
- class ExceptionTranslatorRegistrar {
- template<typename T>
- class ExceptionTranslator : public IExceptionTranslator {
- public:
-
- ExceptionTranslator( std::string(*translateFunction)( T& ) )
- : m_translateFunction( translateFunction )
- {}
-
- virtual std::string translate( ExceptionTranslators::const_iterator it, ExceptionTranslators::const_iterator itEnd ) const CATCH_OVERRIDE {
- try {
- if( it == itEnd )
- throw;
- else
- return (*it)->translate( it+1, itEnd );
- }
- catch( T& ex ) {
- return m_translateFunction( ex );
- }
- }
-
- protected:
- std::string(*m_translateFunction)( T& );
- };
-
- public:
- template<typename T>
- ExceptionTranslatorRegistrar( std::string(*translateFunction)( T& ) ) {
- getMutableRegistryHub().registerTranslator
- ( new ExceptionTranslator<T>( translateFunction ) );
- }
- };
-}
-
-///////////////////////////////////////////////////////////////////////////////
-#define INTERNAL_CATCH_TRANSLATE_EXCEPTION2( translatorName, signature ) \
- static std::string translatorName( signature ); \
- namespace{ Catch::ExceptionTranslatorRegistrar INTERNAL_CATCH_UNIQUE_NAME( catch_internal_ExceptionRegistrar )( &translatorName ); }\
- static std::string translatorName( signature )
-
-#define INTERNAL_CATCH_TRANSLATE_EXCEPTION( signature ) INTERNAL_CATCH_TRANSLATE_EXCEPTION2( INTERNAL_CATCH_UNIQUE_NAME( catch_internal_ExceptionTranslator ), signature )
-
-// #included from: internal/catch_approx.hpp
-#define TWOBLUECUBES_CATCH_APPROX_HPP_INCLUDED
-
-#include <cmath>
-#include <limits>
-
-#if defined(CATCH_CONFIG_CPP11_TYPE_TRAITS)
-#include <type_traits>
-#endif
-
-namespace Catch {
-namespace Detail {
-
- class Approx {
- public:
- explicit Approx ( double value )
- : m_epsilon( std::numeric_limits<float>::epsilon()*100 ),
- m_margin( 0.0 ),
- m_scale( 1.0 ),
- m_value( value )
- {}
-
- static Approx custom() {
- return Approx( 0 );
- }
-
-#if defined(CATCH_CONFIG_CPP11_TYPE_TRAITS)
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- Approx operator()( T value ) {
- Approx approx( static_cast<double>(value) );
- approx.epsilon( m_epsilon );
- approx.margin( m_margin );
- approx.scale( m_scale );
- return approx;
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- explicit Approx( T value ): Approx(static_cast<double>(value))
- {}
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- friend bool operator == ( const T& lhs, Approx const& rhs ) {
- // Thanks to Richard Harris for his help refining this formula
- auto lhs_v = double(lhs);
- bool relativeOK = std::fabs(lhs_v - rhs.m_value) < rhs.m_epsilon * (rhs.m_scale + (std::max)(std::fabs(lhs_v), std::fabs(rhs.m_value)));
- if (relativeOK) {
- return true;
- }
-
- return std::fabs(lhs_v - rhs.m_value) <= rhs.m_margin;
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- friend bool operator == ( Approx const& lhs, const T& rhs ) {
- return operator==( rhs, lhs );
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- friend bool operator != ( T lhs, Approx const& rhs ) {
- return !operator==( lhs, rhs );
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- friend bool operator != ( Approx const& lhs, T rhs ) {
- return !operator==( rhs, lhs );
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- friend bool operator <= ( T lhs, Approx const& rhs ) {
- return double(lhs) < rhs.m_value || lhs == rhs;
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- friend bool operator <= ( Approx const& lhs, T rhs ) {
- return lhs.m_value < double(rhs) || lhs == rhs;
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- friend bool operator >= ( T lhs, Approx const& rhs ) {
- return double(lhs) > rhs.m_value || lhs == rhs;
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- friend bool operator >= ( Approx const& lhs, T rhs ) {
- return lhs.m_value > double(rhs) || lhs == rhs;
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- Approx& epsilon( T newEpsilon ) {
- m_epsilon = double(newEpsilon);
- return *this;
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- Approx& margin( T newMargin ) {
- m_margin = double(newMargin);
- return *this;
- }
-
- template <typename T, typename = typename std::enable_if<std::is_constructible<double, T>::value>::type>
- Approx& scale( T newScale ) {
- m_scale = double(newScale);
- return *this;
- }
-
-#else
-
- Approx operator()( double value ) {
- Approx approx( value );
- approx.epsilon( m_epsilon );
- approx.margin( m_margin );
- approx.scale( m_scale );
- return approx;
- }
-
- friend bool operator == ( double lhs, Approx const& rhs ) {
- // Thanks to Richard Harris for his help refining this formula
- bool relativeOK = std::fabs( lhs - rhs.m_value ) < rhs.m_epsilon * (rhs.m_scale + (std::max)( std::fabs(lhs), std::fabs(rhs.m_value) ) );
- if (relativeOK) {
- return true;
- }
- return std::fabs(lhs - rhs.m_value) <= rhs.m_margin;
- }
-
- friend bool operator == ( Approx const& lhs, double rhs ) {
- return operator==( rhs, lhs );
- }
-
- friend bool operator != ( double lhs, Approx const& rhs ) {
- return !operator==( lhs, rhs );
- }
-
- friend bool operator != ( Approx const& lhs, double rhs ) {
- return !operator==( rhs, lhs );
- }
-
- friend bool operator <= ( double lhs, Approx const& rhs ) {
- return lhs < rhs.m_value || lhs == rhs;
- }
-
- friend bool operator <= ( Approx const& lhs, double rhs ) {
- return lhs.m_value < rhs || lhs == rhs;
- }
-
- friend bool operator >= ( double lhs, Approx const& rhs ) {
- return lhs > rhs.m_value || lhs == rhs;
- }
-
- friend bool operator >= ( Approx const& lhs, double rhs ) {
- return lhs.m_value > rhs || lhs == rhs;
- }
-
- Approx& epsilon( double newEpsilon ) {
- m_epsilon = newEpsilon;
- return *this;
- }
-
- Approx& margin( double newMargin ) {
- m_margin = newMargin;
- return *this;
- }
-
- Approx& scale( double newScale ) {
- m_scale = newScale;
- return *this;
- }
-#endif
-
- std::string toString() const {
- std::ostringstream oss;
- oss << "Approx( " << Catch::toString( m_value ) << " )";
- return oss.str();
- }
-
- private:
- double m_epsilon;
- double m_margin;
- double m_scale;
- double m_value;
- };
-}
-
-template<>
-inline std::string toString<Detail::Approx>( Detail::Approx const& value ) {
- return value.toString();
-}
-
-} // end namespace Catch
-
-// #included from: internal/catch_matchers_string.h
-#define TWOBLUECUBES_CATCH_MATCHERS_STRING_H_INCLUDED
-
-namespace Catch {
-namespace Matchers {
-
- namespace StdString {
-
- struct CasedString
- {
- CasedString( std::string const& str, CaseSensitive::Choice caseSensitivity );
- std::string adjustString( std::string const& str ) const;
- std::string caseSensitivitySuffix() const;
-
- CaseSensitive::Choice m_caseSensitivity;
- std::string m_str;
- };
-
- struct StringMatcherBase : MatcherBase<std::string> {
- StringMatcherBase( std::string const& operation, CasedString const& comparator );
- virtual std::string describe() const CATCH_OVERRIDE;
-
- CasedString m_comparator;
- std::string m_operation;
- };
-
- struct EqualsMatcher : StringMatcherBase {
- EqualsMatcher( CasedString const& comparator );
- virtual bool match( std::string const& source ) const CATCH_OVERRIDE;
- };
- struct ContainsMatcher : StringMatcherBase {
- ContainsMatcher( CasedString const& comparator );
- virtual bool match( std::string const& source ) const CATCH_OVERRIDE;
- };
- struct StartsWithMatcher : StringMatcherBase {
- StartsWithMatcher( CasedString const& comparator );
- virtual bool match( std::string const& source ) const CATCH_OVERRIDE;
- };
- struct EndsWithMatcher : StringMatcherBase {
- EndsWithMatcher( CasedString const& comparator );
- virtual bool match( std::string const& source ) const CATCH_OVERRIDE;
- };
-
- } // namespace StdString
-
- // The following functions create the actual matcher objects.
- // This allows the types to be inferred
-
- StdString::EqualsMatcher Equals( std::string const& str, CaseSensitive::Choice caseSensitivity = CaseSensitive::Yes );
- StdString::ContainsMatcher Contains( std::string const& str, CaseSensitive::Choice caseSensitivity = CaseSensitive::Yes );
- StdString::EndsWithMatcher EndsWith( std::string const& str, CaseSensitive::Choice caseSensitivity = CaseSensitive::Yes );
- StdString::StartsWithMatcher StartsWith( std::string const& str, CaseSensitive::Choice caseSensitivity = CaseSensitive::Yes );
-
-} // namespace Matchers
-} // namespace Catch
-
-// #included from: internal/catch_matchers_vector.h
-#define TWOBLUECUBES_CATCH_MATCHERS_VECTOR_H_INCLUDED
-
-namespace Catch {
-namespace Matchers {
-
- namespace Vector {
-
- template<typename T>
- struct ContainsElementMatcher : MatcherBase<std::vector<T>, T> {
-
- ContainsElementMatcher(T const &comparator) : m_comparator( comparator) {}
-
- bool match(std::vector<T> const &v) const CATCH_OVERRIDE {
- return std::find(v.begin(), v.end(), m_comparator) != v.end();
- }
-
- virtual std::string describe() const CATCH_OVERRIDE {
- return "Contains: " + Catch::toString( m_comparator );
- }
-
- T const& m_comparator;
- };
-
- template<typename T>
- struct ContainsMatcher : MatcherBase<std::vector<T>, std::vector<T> > {
-
- ContainsMatcher(std::vector<T> const &comparator) : m_comparator( comparator ) {}
-
- bool match(std::vector<T> const &v) const CATCH_OVERRIDE {
- // !TBD: see note in EqualsMatcher
- if (m_comparator.size() > v.size())
- return false;
- for (size_t i = 0; i < m_comparator.size(); ++i)
- if (std::find(v.begin(), v.end(), m_comparator[i]) == v.end())
- return false;
- return true;
- }
- virtual std::string describe() const CATCH_OVERRIDE {
- return "Contains: " + Catch::toString( m_comparator );
- }
-
- std::vector<T> const& m_comparator;
- };
-
- template<typename T>
- struct EqualsMatcher : MatcherBase<std::vector<T>, std::vector<T> > {
-
- EqualsMatcher(std::vector<T> const &comparator) : m_comparator( comparator ) {}
-
- bool match(std::vector<T> const &v) const CATCH_OVERRIDE {
- // !TBD: This currently works if all elements can be compared using !=
- // - a more general approach would be via a compare template that defaults
- // to using !=. but could be specialised for, e.g. std::vector<T> etc
- // - then just call that directly
- if (m_comparator.size() != v.size())
- return false;
- for (size_t i = 0; i < v.size(); ++i)
- if (m_comparator[i] != v[i])
- return false;
- return true;
- }
- virtual std::string describe() const CATCH_OVERRIDE {
- return "Equals: " + Catch::toString( m_comparator );
- }
- std::vector<T> const& m_comparator;
- };
-
- } // namespace Vector
-
- // The following functions create the actual matcher objects.
- // This allows the types to be inferred
-
- template<typename T>
- Vector::ContainsMatcher<T> Contains( std::vector<T> const& comparator ) {
- return Vector::ContainsMatcher<T>( comparator );
- }
-
- template<typename T>
- Vector::ContainsElementMatcher<T> VectorContains( T const& comparator ) {
- return Vector::ContainsElementMatcher<T>( comparator );
- }
-
- template<typename T>
- Vector::EqualsMatcher<T> Equals( std::vector<T> const& comparator ) {
- return Vector::EqualsMatcher<T>( comparator );
- }
-
-} // namespace Matchers
-} // namespace Catch
-
-// #included from: internal/catch_interfaces_tag_alias_registry.h
-#define TWOBLUECUBES_CATCH_INTERFACES_TAG_ALIAS_REGISTRY_H_INCLUDED
-
-// #included from: catch_tag_alias.h
-#define TWOBLUECUBES_CATCH_TAG_ALIAS_H_INCLUDED
-
-#include <string>
-
-namespace Catch {
-
- struct TagAlias {
- TagAlias( std::string const& _tag, SourceLineInfo _lineInfo ) : tag( _tag ), lineInfo( _lineInfo ) {}
-
- std::string tag;
- SourceLineInfo lineInfo;
- };
-
- struct RegistrarForTagAliases {
- RegistrarForTagAliases( char const* alias, char const* tag, SourceLineInfo const& lineInfo );
- };
-
-} // end namespace Catch
-
-#define CATCH_REGISTER_TAG_ALIAS( alias, spec ) namespace{ Catch::RegistrarForTagAliases INTERNAL_CATCH_UNIQUE_NAME( AutoRegisterTagAlias )( alias, spec, CATCH_INTERNAL_LINEINFO ); }
-// #included from: catch_option.hpp
-#define TWOBLUECUBES_CATCH_OPTION_HPP_INCLUDED
-
-namespace Catch {
-
- // An optional type
- template<typename T>
- class Option {
- public:
- Option() : nullableValue( CATCH_NULL ) {}
- Option( T const& _value )
- : nullableValue( new( storage ) T( _value ) )
- {}
- Option( Option const& _other )
- : nullableValue( _other ? new( storage ) T( *_other ) : CATCH_NULL )
- {}
-
- ~Option() {
- reset();
- }
-
- Option& operator= ( Option const& _other ) {
- if( &_other != this ) {
- reset();
- if( _other )
- nullableValue = new( storage ) T( *_other );
- }
- return *this;
- }
- Option& operator = ( T const& _value ) {
- reset();
- nullableValue = new( storage ) T( _value );
- return *this;
- }
-
- void reset() {
- if( nullableValue )
- nullableValue->~T();
- nullableValue = CATCH_NULL;
- }
-
- T& operator*() { return *nullableValue; }
- T const& operator*() const { return *nullableValue; }
- T* operator->() { return nullableValue; }
- const T* operator->() const { return nullableValue; }
-
- T valueOr( T const& defaultValue ) const {
- return nullableValue ? *nullableValue : defaultValue;
- }
-
- bool some() const { return nullableValue != CATCH_NULL; }
- bool none() const { return nullableValue == CATCH_NULL; }
-
- bool operator !() const { return nullableValue == CATCH_NULL; }
- operator SafeBool::type() const {
- return SafeBool::makeSafe( some() );
- }
-
- private:
- T *nullableValue;
- union {
- char storage[sizeof(T)];
-
- // These are here to force alignment for the storage
- long double dummy1;
- void (*dummy2)();
- long double dummy3;
-#ifdef CATCH_CONFIG_CPP11_LONG_LONG
- long long dummy4;
-#endif
- };
- };
-
-} // end namespace Catch
-
-namespace Catch {
-
- struct ITagAliasRegistry {
- virtual ~ITagAliasRegistry();
- virtual Option<TagAlias> find( std::string const& alias ) const = 0;
- virtual std::string expandAliases( std::string const& unexpandedTestSpec ) const = 0;
-
- static ITagAliasRegistry const& get();
- };
-
-} // end namespace Catch
-
-// These files are included here so the single_include script doesn't put them
-// in the conditionally compiled sections
-// #included from: internal/catch_test_case_info.h
-#define TWOBLUECUBES_CATCH_TEST_CASE_INFO_H_INCLUDED
-
-#include <string>
-#include <set>
-
-#ifdef __clang__
-#pragma clang diagnostic push
-#pragma clang diagnostic ignored "-Wpadded"
-#endif
-
-namespace Catch {
-
- struct ITestCase;
-
- struct TestCaseInfo {
- enum SpecialProperties{
- None = 0,
- IsHidden = 1 << 1,
- ShouldFail = 1 << 2,
- MayFail = 1 << 3,
- Throws = 1 << 4,
- NonPortable = 1 << 5
- };
-
- TestCaseInfo( std::string const& _name,
- std::string const& _className,
- std::string const& _description,
- std::set<std::string> const& _tags,
- SourceLineInfo const& _lineInfo );
-
- TestCaseInfo( TestCaseInfo const& other );
-
- friend void setTags( TestCaseInfo& testCaseInfo, std::set<std::string> const& tags );
-
- bool isHidden() const;
- bool throws() const;
- bool okToFail() const;
- bool expectedToFail() const;
-
- std::string name;
- std::string className;
- std::string description;
- std::set<std::string> tags;
- std::set<std::string> lcaseTags;
- std::string tagsAsString;
- SourceLineInfo lineInfo;
- SpecialProperties properties;
- };
-
- class TestCase : public TestCaseInfo {
- public:
-
- TestCase( ITestCase* testCase, TestCaseInfo const& info );
- TestCase( TestCase const& other );
-
- TestCase withName( std::string const& _newName ) const;
-
- void invoke() const;
-
- TestCaseInfo const& getTestCaseInfo() const;
-
- void swap( TestCase& other );
- bool operator == ( TestCase const& other ) const;
- bool operator < ( TestCase const& other ) const;
- TestCase& operator = ( TestCase const& other );
-
- private:
- Ptr<ITestCase> test;
- };
-
- TestCase makeTestCase( ITestCase* testCase,
- std::string const& className,
- std::string const& name,
- std::string const& description,
- SourceLineInfo const& lineInfo );
-}
-
-#ifdef __clang__
-#pragma clang diagnostic pop
-#endif
-
-
-#ifdef __OBJC__
-// #included from: internal/catch_objc.hpp
-#define TWOBLUECUBES_CATCH_OBJC_HPP_INCLUDED
-
-#import <objc/runtime.h>
-
-#include <string>
-
-// NB. Any general catch headers included here must be included
-// in catch.hpp first to make sure they are included by the single
-// header for non obj-usage
-
-///////////////////////////////////////////////////////////////////////////////
-// This protocol is really only here for (self) documenting purposes, since
-// all its methods are optional.
-@protocol OcFixture
-
-@optional
-
--(void) setUp;
--(void) tearDown;
-
-@end
-
-namespace Catch {
-
- class OcMethod : public SharedImpl<ITestCase> {
-
- public:
- OcMethod( Class cls, SEL sel ) : m_cls( cls ), m_sel( sel ) {}
-
- virtual void invoke() const {
- id obj = [[m_cls alloc] init];
-
- performOptionalSelector( obj, @selector(setUp) );
- performOptionalSelector( obj, m_sel );
- performOptionalSelector( obj, @selector(tearDown) );
-
- arcSafeRelease( obj );
- }
- private:
- virtual ~OcMethod() {}
-
- Class m_cls;
- SEL m_sel;
- };
-
- namespace Detail{
-
- inline std::string getAnnotation( Class cls,
- std::string const& annotationName,
- std::string const& testCaseName ) {
- NSString* selStr = [[NSString alloc] initWithFormat:@"Catch_%s_%s", annotationName.c_str(), testCaseName.c_str()];
- SEL sel = NSSelectorFromString( selStr );
- arcSafeRelease( selStr );
- id value = performOptionalSelector( cls, sel );
- if( value )
- return [(NSString*)value UTF8String];
- return "";
- }
- }
-
- inline size_t registerTestMethods() {
- size_t noTestMethods = 0;
- int noClasses = objc_getClassList( CATCH_NULL, 0 );
-
- Class* classes = (CATCH_UNSAFE_UNRETAINED Class *)malloc( sizeof(Class) * noClasses);
- objc_getClassList( classes, noClasses );
-
- for( int c = 0; c < noClasses; c++ ) {
- Class cls = classes[c];
- {
- u_int count;
- Method* methods = class_copyMethodList( cls, &count );
- for( u_int m = 0; m < count ; m++ ) {
- SEL selector = method_getName(methods[m]);
- std::string methodName = sel_getName(selector);
- if( startsWith( methodName, "Catch_TestCase_" ) ) {
- std::string testCaseName = methodName.substr( 15 );
- std::string name = Detail::getAnnotation( cls, "Name", testCaseName );
- std::string desc = Detail::getAnnotation( cls, "Description", testCaseName );
- const char* className = class_getName( cls );
-
- getMutableRegistryHub().registerTest( makeTestCase( new OcMethod( cls, selector ), className, name.c_str(), desc.c_str(), SourceLineInfo() ) );
- noTestMethods++;
- }
- }
- free(methods);
- }
- }
- return noTestMethods;
- }
-
- namespace Matchers {
- namespace Impl {
- namespace NSStringMatchers {
-
- struct StringHolder : MatcherBase<NSString*>{
- StringHolder( NSString* substr ) : m_substr( [substr copy] ){}
- StringHolder( StringHolder const& other ) : m_substr( [other.m_substr copy] ){}
- StringHolder() {
- arcSafeRelease( m_substr );
- }
-
- virtual bool match( NSString* arg ) const CATCH_OVERRIDE {
- return false;
- }
-
- NSString* m_substr;
- };
-
- struct Equals : StringHolder {
- Equals( NSString* substr ) : StringHolder( substr ){}
-
- virtual bool match( NSString* str ) const CATCH_OVERRIDE {
- return (str != nil || m_substr == nil ) &&
- [str isEqualToString:m_substr];
- }
-
- virtual std::string describe() const CATCH_OVERRIDE {
- return "equals string: " + Catch::toString( m_substr );
- }
- };
-
- struct Contains : StringHolder {
- Contains( NSString* substr ) : StringHolder( substr ){}
-
- virtual bool match( NSString* str ) const {
- return (str != nil || m_substr == nil ) &&
- [str rangeOfString:m_substr].location != NSNotFound;
- }
-
- virtual std::string describe() const CATCH_OVERRIDE {
- return "contains string: " + Catch::toString( m_substr );
- }
- };
-
- struct StartsWith : StringHolder {
- StartsWith( NSString* substr ) : StringHolder( substr ){}
-
- virtual bool match( NSString* str ) const {
- return (str != nil || m_substr == nil ) &&
- [str rangeOfString:m_substr].location == 0;
- }
-
- virtual std::string describe() const CATCH_OVERRIDE {
- return "starts with: " + Catch::toString( m_substr );
- }
- };
- struct EndsWith : StringHolder {
- EndsWith( NSString* substr ) : StringHolder( substr ){}
-
- virtual bool match( NSString* str ) const {
- return (str != nil || m_substr == nil ) &&
- [str rangeOfString:m_substr].location == [str length] - [m_substr length];
- }
-
- virtual std::string describe() const CATCH_OVERRIDE {
- return "ends with: " + Catch::toString( m_substr );
- }
- };
-
- } // namespace NSStringMatchers
- } // namespace Impl
-
- inline Impl::NSStringMatchers::Equals
- Equals( NSString* substr ){ return Impl::NSStringMatchers::Equals( substr ); }
-
- inline Impl::NSStringMatchers::Contains
- Contains( NSString* substr ){ return Impl::NSStringMatchers::Contains( substr ); }
-
- inline Impl::NSStringMatchers::StartsWith
- StartsWith( NSString* substr ){ return Impl::NSStringMatchers::StartsWith( substr ); }
-
- inline Impl::NSStringMatchers::EndsWith
- EndsWith( NSString* substr ){ return Impl::NSStringMatchers::EndsWith( substr ); }
-
- } // namespace Matchers
-
- using namespace Matchers;
-
-} // namespace Catch
-
-///////////////////////////////////////////////////////////////////////////////
-#define OC_TEST_CASE( name, desc )\
-+(NSString*) INTERNAL_CATCH_UNIQUE_NAME( Catch_Name_test ) \
-{\
-return @ name; \
-}\
-+(NSString*) INTERNAL_CATCH_UNIQUE_NAME( Catch_Description_test ) \
-{ \
-return @ desc; \
-} \
--(void) INTERNAL_CATCH_UNIQUE_NAME( Catch_TestCase_test )
-
-#endif
-
-#ifdef CATCH_IMPL
-
-// !TBD: Move the leak detector code into a separate header
-#ifdef CATCH_CONFIG_WINDOWS_CRTDBG
-#include <crtdbg.h>
-class LeakDetector {
-public:
- LeakDetector() {
- int flag = _CrtSetDbgFlag(_CRTDBG_REPORT_FLAG);
- flag |= _CRTDBG_LEAK_CHECK_DF;
- flag |= _CRTDBG_ALLOC_MEM_DF;
- _CrtSetDbgFlag(flag);
- _CrtSetReportMode(_CRT_WARN, _CRTDBG_MODE_FILE | _CRTDBG_MODE_DEBUG);
- _CrtSetReportFile(_CRT_WARN, _CRTDBG_FILE_STDERR);
- // Change this to leaking allocation's number to break there
- _CrtSetBreakAlloc(-1);
- }
-};
-#else
-class LeakDetector {};
-#endif
-
-LeakDetector leakDetector;
-
-// #included from: internal/catch_impl.hpp
-#define TWOBLUECUBES_CATCH_IMPL_HPP_INCLUDED
-
-// Collect all the implementation files together here
-// These are the equivalent of what would usually be cpp files
-
-#ifdef __clang__
-#pragma clang diagnostic push
-#pragma clang diagnostic ignored "-Wweak-vtables"
-#endif
-
-// #included from: ../catch_session.hpp
-#define TWOBLUECUBES_CATCH_RUNNER_HPP_INCLUDED
-
-// #included from: internal/catch_commandline.hpp
-#define TWOBLUECUBES_CATCH_COMMANDLINE_HPP_INCLUDED
-
-// #included from: catch_config.hpp
-#define TWOBLUECUBES_CATCH_CONFIG_HPP_INCLUDED
-
-// #included from: catch_test_spec_parser.hpp
-#define TWOBLUECUBES_CATCH_TEST_SPEC_PARSER_HPP_INCLUDED
-
-#ifdef __clang__
-#pragma clang diagnostic push
-#pragma clang diagnostic ignored "-Wpadded"
-#endif
-
-// #included from: catch_test_spec.hpp
-#define TWOBLUECUBES_CATCH_TEST_SPEC_HPP_INCLUDED
-
-#ifdef __clang__
-#pragma clang diagnostic push
-#pragma clang diagnostic ignored "-Wpadded"
-#endif
-
-// #included from: catch_wildcard_pattern.hpp
-#define TWOBLUECUBES_CATCH_WILDCARD_PATTERN_HPP_INCLUDED
-
-#include <stdexcept>
-
-namespace Catch
-{
- class WildcardPattern {
- enum WildcardPosition {
- NoWildcard = 0,
- WildcardAtStart = 1,
- WildcardAtEnd = 2,
- WildcardAtBothEnds = WildcardAtStart | WildcardAtEnd
- };
-
- public:
-
- WildcardPattern( std::string const& pattern, CaseSensitive::Choice caseSensitivity )
- : m_caseSensitivity( caseSensitivity ),
- m_wildcard( NoWildcard ),
- m_pattern( adjustCase( pattern ) )
- {
- if( startsWith( m_pattern, '*' ) ) {
- m_pattern = m_pattern.substr( 1 );
- m_wildcard = WildcardAtStart;
- }
- if( endsWith( m_pattern, '*' ) ) {
- m_pattern = m_pattern.substr( 0, m_pattern.size()-1 );
- m_wildcard = static_cast<WildcardPosition>( m_wildcard | WildcardAtEnd );
- }
- }
- virtual ~WildcardPattern();
- virtual bool matches( std::string const& str ) const {
- switch( m_wildcard ) {
- case NoWildcard:
- return m_pattern == adjustCase( str );
- case WildcardAtStart:
- return endsWith( adjustCase( str ), m_pattern );
- case WildcardAtEnd:
- return startsWith( adjustCase( str ), m_pattern );
- case WildcardAtBothEnds:
- return contains( adjustCase( str ), m_pattern );
- }
-
-#ifdef __clang__
-#pragma clang diagnostic push
-#pragma clang diagnostic ignored "-Wunreachable-code"
-#endif
- throw std::logic_error( "Unknown enum" );
-#ifdef __clang__
-#pragma clang diagnostic pop
-#endif
- }
- private:
- std::string adjustCase( std::string const& str ) const {
- return m_caseSensitivity == CaseSensitive::No ? toLower( str ) : str;
- }
- CaseSensitive::Choice m_caseSensitivity;
- WildcardPosition m_wildcard;
- std::string m_pattern;
- };
-}
-
-#include <string>
-#include <vector>
-
-namespace Catch {
-
- class TestSpec {
- struct Pattern : SharedImpl<> {
- virtual ~Pattern();
- virtual bool matches( TestCaseInfo const& testCase ) const = 0;
- };
- class NamePattern : public Pattern {
- public:
- NamePattern( std::string const& name )
- : m_wildcardPattern( toLower( name ), CaseSensitive::No )
- {}
- virtual ~NamePattern();
- virtual bool matches( TestCaseInfo const& testCase ) const {
- return m_wildcardPattern.matches( toLower( testCase.name ) );
- }
- private:
- WildcardPattern m_wildcardPattern;
- };
-
- class TagPattern : public Pattern {
- public:
- TagPattern( std::string const& tag ) : m_tag( toLower( tag ) ) {}
- virtual ~TagPattern();
- virtual bool matches( TestCaseInfo const& testCase ) const {
- return testCase.lcaseTags.find( m_tag ) != testCase.lcaseTags.end();
- }
- private:
- std::string m_tag;
- };
-
- class ExcludedPattern : public Pattern {
- public:
- ExcludedPattern( Ptr<Pattern> const& underlyingPattern ) : m_underlyingPattern( underlyingPattern ) {}
- virtual ~ExcludedPattern();
- virtual bool matches( TestCaseInfo const& testCase ) const { return !m_underlyingPattern->matches( testCase ); }
- private:
- Ptr<Pattern> m_underlyingPattern;
- };
-
- struct Filter {
- std::vector<Ptr<Pattern> > m_patterns;
-
- bool matches( TestCaseInfo const& testCase ) const {
- // All patterns in a filter must match for the filter to be a match
- for( std::vector<Ptr<Pattern> >::const_iterator it = m_patterns.begin(), itEnd = m_patterns.end(); it != itEnd; ++it ) {
- if( !(*it)->matches( testCase ) )
- return false;
- }
- return true;
- }
- };
-
- public:
- bool hasFilters() const {
- return !m_filters.empty();
- }
- bool matches( TestCaseInfo const& testCase ) const {
- // A TestSpec matches if any filter matches
- for( std::vector<Filter>::const_iterator it = m_filters.begin(), itEnd = m_filters.end(); it != itEnd; ++it )
- if( it->matches( testCase ) )
- return true;
- return false;
- }
-
- private:
- std::vector<Filter> m_filters;
-
- friend class TestSpecParser;
- };
-}
-
-#ifdef __clang__
-#pragma clang diagnostic pop
-#endif
-
-namespace Catch {
-
- class TestSpecParser {
- enum Mode{ None, Name, QuotedName, Tag, EscapedName };
- Mode m_mode;
- bool m_exclusion;
- std::size_t m_start, m_pos;
- std::string m_arg;
- std::vector<std::size_t> m_escapeChars;
- TestSpec::Filter m_currentFilter;
- TestSpec m_testSpec;
- ITagAliasRegistry const* m_tagAliases;
-
- public:
- TestSpecParser( ITagAliasRegistry const& tagAliases ) :m_mode(None), m_exclusion(false), m_start(0), m_pos(0), m_tagAliases( &tagAliases ) {}
-
- TestSpecParser& parse( std::string const& arg ) {
- m_mode = None;
- m_exclusion = false;
- m_start = std::string::npos;
- m_arg = m_tagAliases->expandAliases( arg );
- m_escapeChars.clear();
- for( m_pos = 0; m_pos < m_arg.size(); ++m_pos )
- visitChar( m_arg[m_pos] );
- if( m_mode == Name )
- addPattern<TestSpec::NamePattern>();
- return *this;
- }
- TestSpec testSpec() {
- addFilter();
- return m_testSpec;
- }
- private:
- void visitChar( char c ) {
- if( m_mode == None ) {
- switch( c ) {
- case ' ': return;
- case '~': m_exclusion = true; return;
- case '[': return startNewMode( Tag, ++m_pos );
- case '"': return startNewMode( QuotedName, ++m_pos );
- case '\\': return escape();
- default: startNewMode( Name, m_pos ); break;
- }
- }
- if( m_mode == Name ) {
- if( c == ',' ) {
- addPattern<TestSpec::NamePattern>();
- addFilter();
- }
- else if( c == '[' ) {
- if( subString() == "exclude:" )
- m_exclusion = true;
- else
- addPattern<TestSpec::NamePattern>();
- startNewMode( Tag, ++m_pos );
- }
- else if( c == '\\' )
- escape();
- }
- else if( m_mode == EscapedName )
- m_mode = Name;
- else if( m_mode == QuotedName && c == '"' )
- addPattern<TestSpec::NamePattern>();
- else if( m_mode == Tag && c == ']' )
- addPattern<TestSpec::TagPattern>();
- }
- void startNewMode( Mode mode, std::size_t start ) {
- m_mode = mode;
- m_start = start;
- }
- void escape() {
- if( m_mode == None )
- m_start = m_pos;
- m_mode = EscapedName;
- m_escapeChars.push_back( m_pos );
- }
- std::string subString() const { return m_arg.substr( m_start, m_pos - m_start ); }
- template<typename T>
- void addPattern() {
- std::string token = subString();
- for( size_t i = 0; i < m_escapeChars.size(); ++i )
- token = token.substr( 0, m_escapeChars[i]-m_start-i ) + token.substr( m_escapeChars[i]-m_start-i+1 );
- m_escapeChars.clear();
- if( startsWith( token, "exclude:" ) ) {
- m_exclusion = true;
- token = token.substr( 8 );
- }
- if( !token.empty() ) {
- Ptr<TestSpec::Pattern> pattern = new T( token );
- if( m_exclusion )
- pattern = new TestSpec::ExcludedPattern( pattern );
- m_currentFilter.m_patterns.push_back( pattern );
- }
- m_exclusion = false;
- m_mode = None;
- }
- void addFilter() {
- if( !m_currentFilter.m_patterns.empty() ) {
- m_testSpec.m_filters.push_back( m_currentFilter );
- m_currentFilter = TestSpec::Filter();
- }
- }
- };
- inline TestSpec parseTestSpec( std::string const& arg ) {
- return TestSpecParser( ITagAliasRegistry::get() ).parse( arg ).testSpec();
- }
-
-} // namespace Catch
-
-#ifdef __clang__
-#pragma clang diagnostic pop
-#endif
-
-// #included from: catch_interfaces_config.h
-#define TWOBLUECUBES_CATCH_INTERFACES_CONFIG_H_INCLUDED
-
-#include <iosfwd>
-#include <string>
-#include <vector>
-
-namespace Catch {
-
- struct Verbosity { enum Level {
- NoOutput = 0,
- Quiet,
- Normal
- }; };
-
- struct WarnAbout { enum What {
- Nothing = 0x00,
- NoAssertions = 0x01
- }; };
-
- struct ShowDurations { enum OrNot {
- DefaultForReporter,
- Always,
- Never
- }; };
- struct RunTests { enum InWhatOrder {
- InDeclarationOrder,
- InLexicographicalOrder,
- InRandomOrder
- }; };
- struct UseColour { enum YesOrNo {
- Auto,
- Yes,
- No
- }; };
- struct WaitForKeypress { enum When {
- Never,
- BeforeStart = 1,
- BeforeExit = 2,
- BeforeStartAndExit = BeforeStart | BeforeExit
- }; };
-
- class TestSpec;
-
- struct IConfig : IShared {
-
- virtual ~IConfig();
-
- virtual bool allowThrows() const = 0;
- virtual std::ostream& stream() const = 0;
- virtual std::string name() const = 0;
- virtual bool includeSuccessfulResults() const = 0;
- virtual bool shouldDebugBreak() const = 0;
- virtual bool warnAboutMissingAssertions() const = 0;
- virtual int abortAfter() const = 0;
- virtual bool showInvisibles() const = 0;
- virtual ShowDurations::OrNot showDurations() const = 0;
- virtual TestSpec const& testSpec() const = 0;
- virtual RunTests::InWhatOrder runOrder() const = 0;
- virtual unsigned int rngSeed() const = 0;
- virtual UseColour::YesOrNo useColour() const = 0;
- virtual std::vector<std::string> const& getSectionsToRun() const = 0;
-
- };
-}
-
-// #included from: catch_stream.h
-#define TWOBLUECUBES_CATCH_STREAM_H_INCLUDED
-
-// #included from: catch_streambuf.h
-#define TWOBLUECUBES_CATCH_STREAMBUF_H_INCLUDED
-
-#include <streambuf>
-
-namespace Catch {
-
- class StreamBufBase : public std::streambuf {
- public:
- virtual ~StreamBufBase() CATCH_NOEXCEPT;
- };
-}
-
-#include <streambuf>
-#include <ostream>
-#include <fstream>
-#include <memory>
-
-namespace Catch {
-
- std::ostream& cout();
- std::ostream& cerr();
- std::ostream& clog();
-
- struct IStream {
- virtual ~IStream() CATCH_NOEXCEPT;
- virtual std::ostream& stream() const = 0;
- };
-
- class FileStream : public IStream {
- mutable std::ofstream m_ofs;
- public:
- FileStream( std::string const& filename );
- virtual ~FileStream() CATCH_NOEXCEPT;
- public: // IStream
- virtual std::ostream& stream() const CATCH_OVERRIDE;
- };
-
- class CoutStream : public IStream {
- mutable std::ostream m_os;
- public:
- CoutStream();
- virtual ~CoutStream() CATCH_NOEXCEPT;
-
- public: // IStream
- virtual std::ostream& stream() const CATCH_OVERRIDE;
- };
-
- class DebugOutStream : public IStream {
- CATCH_AUTO_PTR( StreamBufBase ) m_streamBuf;
- mutable std::ostream m_os;
- public:
- DebugOutStream();
- virtual ~DebugOutStream() CATCH_NOEXCEPT;
-
- public: // IStream
- virtual std::ostream& stream() const CATCH_OVERRIDE;
- };
-}
-
-#include <memory>
-#include <vector>
-#include <string>
-#include <stdexcept>
-
-#ifndef CATCH_CONFIG_CONSOLE_WIDTH
-#define CATCH_CONFIG_CONSOLE_WIDTH 80
-#endif
-
-namespace Catch {
-
- struct ConfigData {
-
- ConfigData()
- : listTests( false ),
- listTags( false ),
- listReporters( false ),
- listTestNamesOnly( false ),
- listExtraInfo( false ),
- showSuccessfulTests( false ),
- shouldDebugBreak( false ),
- noThrow( false ),
- showHelp( false ),
- showInvisibles( false ),
- filenamesAsTags( false ),
- libIdentify( false ),
- abortAfter( -1 ),
- rngSeed( 0 ),
- verbosity( Verbosity::Normal ),
- warnings( WarnAbout::Nothing ),
- showDurations( ShowDurations::DefaultForReporter ),
- runOrder( RunTests::InDeclarationOrder ),
- useColour( UseColour::Auto ),
- waitForKeypress( WaitForKeypress::Never )
- {}
-
- bool listTests;
- bool listTags;
- bool listReporters;
- bool listTestNamesOnly;
- bool listExtraInfo;
-
- bool showSuccessfulTests;
- bool shouldDebugBreak;
- bool noThrow;
- bool showHelp;
- bool showInvisibles;
- bool filenamesAsTags;
- bool libIdentify;
-
- int abortAfter;
- unsigned int rngSeed;
-
- Verbosity::Level verbosity;
- WarnAbout::What warnings;
- ShowDurations::OrNot showDurations;
- RunTests::InWhatOrder runOrder;
- UseColour::YesOrNo useColour;
- WaitForKeypress::When waitForKeypress;
-
- std::string outputFilename;
- std::string name;
- std::string processName;
-
- std::vector<std::string> reporterNames;
- std::vector<std::string> testsOrTags;
- std::vector<std::string> sectionsToRun;
- };
-
- class Config : public SharedImpl<IConfig> {
- private:
- Config( Config const& other );
- Config& operator = ( Config const& other );
- virtual void dummy();
- public:
-
- Config()
- {}
-
- Config( ConfigData const& data )
- : m_data( data ),
- m_stream( openStream() )
- {
- if( !data.testsOrTags.empty() ) {
- TestSpecParser parser( ITagAliasRegistry::get() );
- for( std::size_t i = 0; i < data.testsOrTags.size(); ++i )
- parser.parse( data.testsOrTags[i] );
- m_testSpec = parser.testSpec();
- }
- }
-
- virtual ~Config() {}
-
- std::string const& getFilename() const {
- return m_data.outputFilename ;
- }
-
- bool listTests() const { return m_data.listTests; }
- bool listTestNamesOnly() const { return m_data.listTestNamesOnly; }
- bool listTags() const { return m_data.listTags; }
- bool listReporters() const { return m_data.listReporters; }
- bool listExtraInfo() const { return m_data.listExtraInfo; }
-
- std::string getProcessName() const { return m_data.processName; }
-
- std::vector<std::string> const& getReporterNames() const { return m_data.reporterNames; }
- std::vector<std::string> const& getSectionsToRun() const CATCH_OVERRIDE { return m_data.sectionsToRun; }
-
- virtual TestSpec const& testSpec() const CATCH_OVERRIDE { return m_testSpec; }
-
- bool showHelp() const { return m_data.showHelp; }
-
- // IConfig interface
- virtual bool allowThrows() const CATCH_OVERRIDE { return !m_data.noThrow; }
- virtual std::ostream& stream() const CATCH_OVERRIDE { return m_stream->stream(); }
- virtual std::string name() const CATCH_OVERRIDE { return m_data.name.empty() ? m_data.processName : m_data.name; }
- virtual bool includeSuccessfulResults() const CATCH_OVERRIDE { return m_data.showSuccessfulTests; }
- virtual bool warnAboutMissingAssertions() const CATCH_OVERRIDE { return m_data.warnings & WarnAbout::NoAssertions; }
- virtual ShowDurations::OrNot showDurations() const CATCH_OVERRIDE { return m_data.showDurations; }
- virtual RunTests::InWhatOrder runOrder() const CATCH_OVERRIDE { return m_data.runOrder; }
- virtual unsigned int rngSeed() const CATCH_OVERRIDE { return m_data.rngSeed; }
- virtual UseColour::YesOrNo useColour() const CATCH_OVERRIDE { return m_data.useColour; }
- virtual bool shouldDebugBreak() const CATCH_OVERRIDE { return m_data.shouldDebugBreak; }
- virtual int abortAfter() const CATCH_OVERRIDE { return m_data.abortAfter; }
- virtual bool showInvisibles() const CATCH_OVERRIDE { return m_data.showInvisibles; }
-
- private:
-
- IStream const* openStream() {
- if( m_data.outputFilename.empty() )
- return new CoutStream();
- else if( m_data.outputFilename[0] == '%' ) {
- if( m_data.outputFilename == "%debug" )
- return new DebugOutStream();
- else
- throw std::domain_error( "Unrecognised stream: " + m_data.outputFilename );
- }
- else
- return new FileStream( m_data.outputFilename );
- }
- ConfigData m_data;
-
- CATCH_AUTO_PTR( IStream const ) m_stream;
- TestSpec m_testSpec;
- };
-
-} // end namespace Catch
-
-// #included from: catch_clara.h
-#define TWOBLUECUBES_CATCH_CLARA_H_INCLUDED
-
-// Use Catch's value for console width (store Clara's off to the side, if present)
-#ifdef CLARA_CONFIG_CONSOLE_WIDTH
-#define CATCH_TEMP_CLARA_CONFIG_CONSOLE_WIDTH CLARA_CONFIG_CONSOLE_WIDTH
-#undef CLARA_CONFIG_CONSOLE_WIDTH
-#endif
-#define CLARA_CONFIG_CONSOLE_WIDTH CATCH_CONFIG_CONSOLE_WIDTH
-
-// Declare Clara inside the Catch namespace
-#define STITCH_CLARA_OPEN_NAMESPACE namespace Catch {
-// #included from: ../external/clara.h
-
-// Version 0.0.2.4
-
-// Only use header guard if we are not using an outer namespace
-#if !defined(TWOBLUECUBES_CLARA_H_INCLUDED) || defined(STITCH_CLARA_OPEN_NAMESPACE)
-
-#ifndef STITCH_CLARA_OPEN_NAMESPACE
-#define TWOBLUECUBES_CLARA_H_INCLUDED
-#define STITCH_CLARA_OPEN_NAMESPACE
-#define STITCH_CLARA_CLOSE_NAMESPACE
-#else
-#define STITCH_CLARA_CLOSE_NAMESPACE }
-#endif
-
-#define STITCH_TBC_TEXT_FORMAT_OPEN_NAMESPACE STITCH_CLARA_OPEN_NAMESPACE
-
-// ----------- #included from tbc_text_format.h -----------
-
-// Only use header guard if we are not using an outer namespace
-#if !defined(TBC_TEXT_FORMAT_H_INCLUDED) || defined(STITCH_TBC_TEXT_FORMAT_OUTER_NAMESPACE)
-#ifndef STITCH_TBC_TEXT_FORMAT_OUTER_NAMESPACE
-#define TBC_TEXT_FORMAT_H_INCLUDED
-#endif
-
-#include <string>
-#include <vector>
-#include <sstream>
-#include <algorithm>
-#include <cctype>
-
-// Use optional outer namespace
-#ifdef STITCH_TBC_TEXT_FORMAT_OUTER_NAMESPACE
-namespace STITCH_TBC_TEXT_FORMAT_OUTER_NAMESPACE {
-#endif
-
-namespace Tbc {
-
-#ifdef TBC_TEXT_FORMAT_CONSOLE_WIDTH
- const unsigned int consoleWidth = TBC_TEXT_FORMAT_CONSOLE_WIDTH;
-#else
- const unsigned int consoleWidth = 80;
-#endif
-
- struct TextAttributes {
- TextAttributes()
- : initialIndent( std::string::npos ),
- indent( 0 ),
- width( consoleWidth-1 ),
- tabChar( '\t' )
- {}
-
- TextAttributes& setInitialIndent( std::size_t _value ) { initialIndent = _value; return *this; }
- TextAttributes& setIndent( std::size_t _value ) { indent = _value; return *this; }
- TextAttributes& setWidth( std::size_t _value ) { width = _value; return *this; }
- TextAttributes& setTabChar( char _value ) { tabChar = _value; return *this; }
-
- std::size_t initialIndent; // indent of first line, or npos
- std::size_t indent; // indent of subsequent lines, or all if initialIndent is npos
- std::size_t width; // maximum width of text, including indent. Longer text will wrap
- char tabChar; // If this char is seen the indent is changed to current pos
- };
-
- class Text {
- public:
- Text( std::string const& _str, TextAttributes const& _attr = TextAttributes() )
- : attr( _attr )
- {
- std::string wrappableChars = " [({.,/|\\-";
- std::size_t indent = _attr.initialIndent != std::string::npos
- ? _attr.initialIndent
- : _attr.indent;
- std::string remainder = _str;
-
- while( !remainder.empty() ) {
- if( lines.size() >= 1000 ) {
- lines.push_back( "... message truncated due to excessive size" );
- return;
- }
- std::size_t tabPos = std::string::npos;
- std::size_t width = (std::min)( remainder.size(), _attr.width - indent );
- std::size_t pos = remainder.find_first_of( '\n' );
- if( pos <= width ) {
- width = pos;
- }
- pos = remainder.find_last_of( _attr.tabChar, width );
- if( pos != std::string::npos ) {
- tabPos = pos;
- if( remainder[width] == '\n' )
- width--;
- remainder = remainder.substr( 0, tabPos ) + remainder.substr( tabPos+1 );
- }
-
- if( width == remainder.size() ) {
- spliceLine( indent, remainder, width );
- }
- else if( remainder[width] == '\n' ) {
- spliceLine( indent, remainder, width );
- if( width <= 1 || remainder.size() != 1 )
- remainder = remainder.substr( 1 );
- indent = _attr.indent;
- }
- else {
- pos = remainder.find_last_of( wrappableChars, width );
- if( pos != std::string::npos && pos > 0 ) {
- spliceLine( indent, remainder, pos );
- if( remainder[0] == ' ' )
- remainder = remainder.substr( 1 );
- }
- else {
- spliceLine( indent, remainder, width-1 );
- lines.back() += "-";
- }
- if( lines.size() == 1 )
- indent = _attr.indent;
- if( tabPos != std::string::npos )
- indent += tabPos;
- }
- }
- }
-
- void spliceLine( std::size_t _indent, std::string& _remainder, std::size_t _pos ) {
- lines.push_back( std::string( _indent, ' ' ) + _remainder.substr( 0, _pos ) );
- _remainder = _remainder.substr( _pos );
- }
-
- typedef std::vector<std::string>::const_iterator const_iterator;
-
- const_iterator begin() const { return lines.begin(); }
- const_iterator end() const { return lines.end(); }
- std::string const& last() const { return lines.back(); }
- std::size_t size() const { return lines.size(); }
- std::string const& operator[]( std::size_t _index ) const { return lines[_index]; }
- std::string toString() const {
- std::ostringstream oss;
- oss << *this;
- return oss.str();
- }
-
- friend std::ostream& operator << ( std::ostream& _stream, Text const& _text ) {
- for( Text::const_iterator it = _text.begin(), itEnd = _text.end();
- it != itEnd; ++it ) {
- if( it != _text.begin() )
- _stream << "\n";
- _stream << *it;
- }
- return _stream;
- }
-
- private:
- std::string str;
- TextAttributes attr;
- std::vector<std::string> lines;
- };
-
-} // end namespace Tbc
-
-#ifdef STITCH_TBC_TEXT_FORMAT_OUTER_NAMESPACE
-} // end outer namespace
-#endif
-
-#endif // TBC_TEXT_FORMAT_H_INCLUDED
-
-// ----------- end of #include from tbc_text_format.h -----------
-// ........... back in clara.h
-
-#undef STITCH_TBC_TEXT_FORMAT_OPEN_NAMESPACE
-
-// ----------- #included from clara_compilers.h -----------
-
-#ifndef TWOBLUECUBES_CLARA_COMPILERS_H_INCLUDED
-#define TWOBLUECUBES_CLARA_COMPILERS_H_INCLUDED
-
-// Detect a number of compiler features - mostly C++11/14 conformance - by compiler
-// The following features are defined:
-//
-// CLARA_CONFIG_CPP11_NULLPTR : is nullptr supported?
-// CLARA_CONFIG_CPP11_NOEXCEPT : is noexcept supported?
-// CLARA_CONFIG_CPP11_GENERATED_METHODS : The delete and default keywords for compiler generated methods
-// CLARA_CONFIG_CPP11_OVERRIDE : is override supported?
-// CLARA_CONFIG_CPP11_UNIQUE_PTR : is unique_ptr supported (otherwise use auto_ptr)
-
-// CLARA_CONFIG_CPP11_OR_GREATER : Is C++11 supported?
-
-// CLARA_CONFIG_VARIADIC_MACROS : are variadic macros supported?
-
-// In general each macro has a _NO_<feature name> form
-// (e.g. CLARA_CONFIG_CPP11_NO_NULLPTR) which disables the feature.
-// Many features, at point of detection, define an _INTERNAL_ macro, so they
-// can be combined, en-mass, with the _NO_ forms later.
-
-// All the C++11 features can be disabled with CLARA_CONFIG_NO_CPP11
-
-#ifdef __clang__
-
-#if __has_feature(cxx_nullptr)
-#define CLARA_INTERNAL_CONFIG_CPP11_NULLPTR
-#endif
-
-#if __has_feature(cxx_noexcept)
-#define CLARA_INTERNAL_CONFIG_CPP11_NOEXCEPT
-#endif
-
-#endif // __clang__
-
-////////////////////////////////////////////////////////////////////////////////
-// GCC
-#ifdef __GNUC__
-
-#if __GNUC__ == 4 && __GNUC_MINOR__ >= 6 && defined(__GXX_EXPERIMENTAL_CXX0X__)
-#define CLARA_INTERNAL_CONFIG_CPP11_NULLPTR
-#endif
-
-// - otherwise more recent versions define __cplusplus >= 201103L
-// and will get picked up below
-
-#endif // __GNUC__
-
-////////////////////////////////////////////////////////////////////////////////
-// Visual C++
-#ifdef _MSC_VER
-
-#if (_MSC_VER >= 1600)
-#define CLARA_INTERNAL_CONFIG_CPP11_NULLPTR
-#define CLARA_INTERNAL_CONFIG_CPP11_UNIQUE_PTR
-#endif
-
-#if (_MSC_VER >= 1900 ) // (VC++ 13 (VS2015))
-#define CLARA_INTERNAL_CONFIG_CPP11_NOEXCEPT
-#define CLARA_INTERNAL_CONFIG_CPP11_GENERATED_METHODS
-#endif
-
-#endif // _MSC_VER
-
-////////////////////////////////////////////////////////////////////////////////
-// C++ language feature support
-
-// catch all support for C++11
-#if defined(__cplusplus) && __cplusplus >= 201103L
-
-#define CLARA_CPP11_OR_GREATER
-
-#if !defined(CLARA_INTERNAL_CONFIG_CPP11_NULLPTR)
-#define CLARA_INTERNAL_CONFIG_CPP11_NULLPTR
-#endif
-
-#ifndef CLARA_INTERNAL_CONFIG_CPP11_NOEXCEPT
-#define CLARA_INTERNAL_CONFIG_CPP11_NOEXCEPT
-#endif
-
-#ifndef CLARA_INTERNAL_CONFIG_CPP11_GENERATED_METHODS
-#define CLARA_INTERNAL_CONFIG_CPP11_GENERATED_METHODS
-#endif
-
-#if !defined(CLARA_INTERNAL_CONFIG_CPP11_OVERRIDE)
-#define CLARA_INTERNAL_CONFIG_CPP11_OVERRIDE
-#endif
-#if !defined(CLARA_INTERNAL_CONFIG_CPP11_UNIQUE_PTR)
-#define CLARA_INTERNAL_CONFIG_CPP11_UNIQUE_PTR
-#endif
-
-#endif // __cplusplus >= 201103L
-
-// Now set the actual defines based on the above + anything the user has configured
-#if defined(CLARA_INTERNAL_CONFIG_CPP11_NULLPTR) && !defined(CLARA_CONFIG_CPP11_NO_NULLPTR) && !defined(CLARA_CONFIG_CPP11_NULLPTR) && !defined(CLARA_CONFIG_NO_CPP11)
-#define CLARA_CONFIG_CPP11_NULLPTR
-#endif
-#if defined(CLARA_INTERNAL_CONFIG_CPP11_NOEXCEPT) && !defined(CLARA_CONFIG_CPP11_NO_NOEXCEPT) && !defined(CLARA_CONFIG_CPP11_NOEXCEPT) && !defined(CLARA_CONFIG_NO_CPP11)
-#define CLARA_CONFIG_CPP11_NOEXCEPT
-#endif
-#if defined(CLARA_INTERNAL_CONFIG_CPP11_GENERATED_METHODS) && !defined(CLARA_CONFIG_CPP11_NO_GENERATED_METHODS) && !defined(CLARA_CONFIG_CPP11_GENERATED_METHODS) && !defined(CLARA_CONFIG_NO_CPP11)
-#define CLARA_CONFIG_CPP11_GENERATED_METHODS
-#endif
-#if defined(CLARA_INTERNAL_CONFIG_CPP11_OVERRIDE) && !defined(CLARA_CONFIG_NO_OVERRIDE) && !defined(CLARA_CONFIG_CPP11_OVERRIDE) && !defined(CLARA_CONFIG_NO_CPP11)
-#define CLARA_CONFIG_CPP11_OVERRIDE
-#endif
-#if defined(CLARA_INTERNAL_CONFIG_CPP11_UNIQUE_PTR) && !defined(CLARA_CONFIG_NO_UNIQUE_PTR) && !defined(CLARA_CONFIG_CPP11_UNIQUE_PTR) && !defined(CLARA_CONFIG_NO_CPP11)
-#define CLARA_CONFIG_CPP11_UNIQUE_PTR
-#endif
-
-// noexcept support:
-#if defined(CLARA_CONFIG_CPP11_NOEXCEPT) && !defined(CLARA_NOEXCEPT)
-#define CLARA_NOEXCEPT noexcept
-# define CLARA_NOEXCEPT_IS(x) noexcept(x)
-#else
-#define CLARA_NOEXCEPT throw()
-# define CLARA_NOEXCEPT_IS(x)
-#endif
-
-// nullptr support
-#ifdef CLARA_CONFIG_CPP11_NULLPTR
-#define CLARA_NULL nullptr
-#else
-#define CLARA_NULL NULL
-#endif
-
-// override support
-#ifdef CLARA_CONFIG_CPP11_OVERRIDE
-#define CLARA_OVERRIDE override
-#else
-#define CLARA_OVERRIDE
-#endif
-
-// unique_ptr support
-#ifdef CLARA_CONFIG_CPP11_UNIQUE_PTR
-# define CLARA_AUTO_PTR( T ) std::unique_ptr<T>
-#else
-# define CLARA_AUTO_PTR( T ) std::auto_ptr<T>
-#endif
-
-#endif // TWOBLUECUBES_CLARA_COMPILERS_H_INCLUDED
-
-// ----------- end of #include from clara_compilers.h -----------
-// ........... back in clara.h
-
-#include <map>
-#include <stdexcept>
-#include <memory>
-
-#if defined(WIN32) || defined(__WIN32__) || defined(_WIN32) || defined(_MSC_VER)
-#define CLARA_PLATFORM_WINDOWS
-#endif
-
-// Use optional outer namespace
-#ifdef STITCH_CLARA_OPEN_NAMESPACE
-STITCH_CLARA_OPEN_NAMESPACE
-#endif
-
-namespace Clara {
-
- struct UnpositionalTag {};
-
- extern UnpositionalTag _;
-
-#ifdef CLARA_CONFIG_MAIN
- UnpositionalTag _;
-#endif
-
- namespace Detail {
-
-#ifdef CLARA_CONSOLE_WIDTH
- const unsigned int consoleWidth = CLARA_CONFIG_CONSOLE_WIDTH;
-#else
- const unsigned int consoleWidth = 80;
-#endif
-
- using namespace Tbc;
-
- inline bool startsWith( std::string const& str, std::string const& prefix ) {
- return str.size() >= prefix.size() && str.substr( 0, prefix.size() ) == prefix;
- }
-
- template<typename T> struct RemoveConstRef{ typedef T type; };
- template<typename T> struct RemoveConstRef<T&>{ typedef T type; };
- template<typename T> struct RemoveConstRef<T const&>{ typedef T type; };
- template<typename T> struct RemoveConstRef<T const>{ typedef T type; };
-
- template<typename T> struct IsBool { static const bool value = false; };
- template<> struct IsBool<bool> { static const bool value = true; };
-
- template<typename T>
- void convertInto( std::string const& _source, T& _dest ) {
- std::stringstream ss;
- ss << _source;
- ss >> _dest;
- if( ss.fail() )
- throw std::runtime_error( "Unable to convert " + _source + " to destination type" );
- }
- inline void convertInto( std::string const& _source, std::string& _dest ) {
- _dest = _source;
- }
- char toLowerCh(char c) {
- return static_cast<char>( std::tolower( c ) );
- }
- inline void convertInto( std::string const& _source, bool& _dest ) {
- std::string sourceLC = _source;
- std::transform( sourceLC.begin(), sourceLC.end(), sourceLC.begin(), toLowerCh );
- if( sourceLC == "y" || sourceLC == "1" || sourceLC == "true" || sourceLC == "yes" || sourceLC == "on" )
- _dest = true;
- else if( sourceLC == "n" || sourceLC == "0" || sourceLC == "false" || sourceLC == "no" || sourceLC == "off" )
- _dest = false;
- else
- throw std::runtime_error( "Expected a boolean value but did not recognise:\n '" + _source + "'" );
- }
-
- template<typename ConfigT>
- struct IArgFunction {
- virtual ~IArgFunction() {}
-#ifdef CLARA_CONFIG_CPP11_GENERATED_METHODS
- IArgFunction() = default;
- IArgFunction( IArgFunction const& ) = default;
-#endif
- virtual void set( ConfigT& config, std::string const& value ) const = 0;
- virtual bool takesArg() const = 0;
- virtual IArgFunction* clone() const = 0;
- };
-
- template<typename ConfigT>
- class BoundArgFunction {
- public:
- BoundArgFunction() : functionObj( CLARA_NULL ) {}
- BoundArgFunction( IArgFunction<ConfigT>* _functionObj ) : functionObj( _functionObj ) {}
- BoundArgFunction( BoundArgFunction const& other ) : functionObj( other.functionObj ? other.functionObj->clone() : CLARA_NULL ) {}
- BoundArgFunction& operator = ( BoundArgFunction const& other ) {
- IArgFunction<ConfigT>* newFunctionObj = other.functionObj ? other.functionObj->clone() : CLARA_NULL;
- delete functionObj;
- functionObj = newFunctionObj;
- return *this;
- }
- ~BoundArgFunction() { delete functionObj; }
-
- void set( ConfigT& config, std::string const& value ) const {
- functionObj->set( config, value );
- }
- bool takesArg() const { return functionObj->takesArg(); }
-
- bool isSet() const {
- return functionObj != CLARA_NULL;
- }
- private:
- IArgFunction<ConfigT>* functionObj;
- };
-
- template<typename C>
- struct NullBinder : IArgFunction<C>{
- virtual void set( C&, std::string const& ) const {}
- virtual bool takesArg() const { return true; }
- virtual IArgFunction<C>* clone() const { return new NullBinder( *this ); }
- };
-
- template<typename C, typename M>
- struct BoundDataMember : IArgFunction<C>{
- BoundDataMember( M C::* _member ) : member( _member ) {}
- virtual void set( C& p, std::string const& stringValue ) const {
- convertInto( stringValue, p.*member );
- }
- virtual bool takesArg() const { return !IsBool<M>::value; }
- virtual IArgFunction<C>* clone() const { return new BoundDataMember( *this ); }
- M C::* member;
- };
- template<typename C, typename M>
- struct BoundUnaryMethod : IArgFunction<C>{
- BoundUnaryMethod( void (C::*_member)( M ) ) : member( _member ) {}
- virtual void set( C& p, std::string const& stringValue ) const {
- typename RemoveConstRef<M>::type value;
- convertInto( stringValue, value );
- (p.*member)( value );
- }
- virtual bool takesArg() const { return !IsBool<M>::value; }
- virtual IArgFunction<C>* clone() const { return new BoundUnaryMethod( *this ); }
- void (C::*member)( M );
- };
- template<typename C>
- struct BoundNullaryMethod : IArgFunction<C>{
- BoundNullaryMethod( void (C::*_member)() ) : member( _member ) {}
- virtual void set( C& p, std::string const& stringValue ) const {
- bool value;
- convertInto( stringValue, value );
- if( value )
- (p.*member)();
- }
- virtual bool takesArg() const { return false; }
- virtual IArgFunction<C>* clone() const { return new BoundNullaryMethod( *this ); }
- void (C::*member)();
- };
-
- template<typename C>
- struct BoundUnaryFunction : IArgFunction<C>{
- BoundUnaryFunction( void (*_function)( C& ) ) : function( _function ) {}
- virtual void set( C& obj, std::string const& stringValue ) const {
- bool value;
- convertInto( stringValue, value );
- if( value )
- function( obj );
- }
- virtual bool takesArg() const { return false; }
- virtual IArgFunction<C>* clone() const { return new BoundUnaryFunction( *this ); }
- void (*function)( C& );
- };
-
- template<typename C, typename T>
- struct BoundBinaryFunction : IArgFunction<C>{
- BoundBinaryFunction( void (*_function)( C&, T ) ) : function( _function ) {}
- virtual void set( C& obj, std::string const& stringValue ) const {
- typename RemoveConstRef<T>::type value;
- convertInto( stringValue, value );
- function( obj, value );
- }
- virtual bool takesArg() const { return !IsBool<T>::value; }
- virtual IArgFunction<C>* clone() const { return new BoundBinaryFunction( *this ); }
- void (*function)( C&, T );
- };
-
- } // namespace Detail
-
- inline std::vector<std::string> argsToVector( int argc, char const* const* const argv ) {
- std::vector<std::string> args( static_cast<std::size_t>( argc ) );
- for( std::size_t i = 0; i < static_cast<std::size_t>( argc ); ++i )
- args[i] = argv[i];
-
- return args;
- }
-
- class Parser {
- enum Mode { None, MaybeShortOpt, SlashOpt, ShortOpt, LongOpt, Positional };
- Mode mode;
- std::size_t from;
- bool inQuotes;
- public:
-
- struct Token {
- enum Type { Positional, ShortOpt, LongOpt };
- Token( Type _type, std::string const& _data ) : type( _type ), data( _data ) {}
- Type type;
- std::string data;
- };
-
- Parser() : mode( None ), from( 0 ), inQuotes( false ){}
-
- void parseIntoTokens( std::vector<std::string> const& args, std::vector<Token>& tokens ) {
- const std::string doubleDash = "--";
- for( std::size_t i = 1; i < args.size() && args[i] != doubleDash; ++i )
- parseIntoTokens( args[i], tokens);
- }
-
- void parseIntoTokens( std::string const& arg, std::vector<Token>& tokens ) {
- for( std::size_t i = 0; i < arg.size(); ++i ) {
- char c = arg[i];
- if( c == '"' )
- inQuotes = !inQuotes;
- mode = handleMode( i, c, arg, tokens );
- }
- mode = handleMode( arg.size(), '\0', arg, tokens );
- }
- Mode handleMode( std::size_t i, char c, std::string const& arg, std::vector<Token>& tokens ) {
- switch( mode ) {
- case None: return handleNone( i, c );
- case MaybeShortOpt: return handleMaybeShortOpt( i, c );
- case ShortOpt:
- case LongOpt:
- case SlashOpt: return handleOpt( i, c, arg, tokens );
- case Positional: return handlePositional( i, c, arg, tokens );
- default: throw std::logic_error( "Unknown mode" );
- }
- }
-
- Mode handleNone( std::size_t i, char c ) {
- if( inQuotes ) {
- from = i;
- return Positional;
- }
- switch( c ) {
- case '-': return MaybeShortOpt;
-#ifdef CLARA_PLATFORM_WINDOWS
- case '/': from = i+1; return SlashOpt;
-#endif
- default: from = i; return Positional;
- }
- }
- Mode handleMaybeShortOpt( std::size_t i, char c ) {
- switch( c ) {
- case '-': from = i+1; return LongOpt;
- default: from = i; return ShortOpt;
- }
- }
-
- Mode handleOpt( std::size_t i, char c, std::string const& arg, std::vector<Token>& tokens ) {
- if( std::string( ":=\0", 3 ).find( c ) == std::string::npos )
- return mode;
-
- std::string optName = arg.substr( from, i-from );
- if( mode == ShortOpt )
- for( std::size_t j = 0; j < optName.size(); ++j )
- tokens.push_back( Token( Token::ShortOpt, optName.substr( j, 1 ) ) );
- else if( mode == SlashOpt && optName.size() == 1 )
- tokens.push_back( Token( Token::ShortOpt, optName ) );
- else
- tokens.push_back( Token( Token::LongOpt, optName ) );
- return None;
- }
- Mode handlePositional( std::size_t i, char c, std::string const& arg, std::vector<Token>& tokens ) {
- if( inQuotes || std::string( "\0", 1 ).find( c ) == std::string::npos )
- return mode;
-
- std::string data = arg.substr( from, i-from );
- tokens.push_back( Token( Token::Positional, data ) );
- return None;
- }
- };
-
- template<typename ConfigT>
- struct CommonArgProperties {
- CommonArgProperties() {}
- CommonArgProperties( Detail::BoundArgFunction<ConfigT> const& _boundField ) : boundField( _boundField ) {}
-
- Detail::BoundArgFunction<ConfigT> boundField;
- std::string description;
- std::string detail;
- std::string placeholder; // Only value if boundField takes an arg
-
- bool takesArg() const {
- return !placeholder.empty();
- }
- void validate() const {
- if( !boundField.isSet() )
- throw std::logic_error( "option not bound" );
- }
- };
- struct OptionArgProperties {
- std::vector<std::string> shortNames;
- std::string longName;
-
- bool hasShortName( std::string const& shortName ) const {
- return std::find( shortNames.begin(), shortNames.end(), shortName ) != shortNames.end();
- }
- bool hasLongName( std::string const& _longName ) const {
- return _longName == longName;
- }
- };
- struct PositionalArgProperties {
- PositionalArgProperties() : position( -1 ) {}
- int position; // -1 means non-positional (floating)
-
- bool isFixedPositional() const {
- return position != -1;
- }
- };
-
- template<typename ConfigT>
- class CommandLine {
-
- struct Arg : CommonArgProperties<ConfigT>, OptionArgProperties, PositionalArgProperties {
- Arg() {}
- Arg( Detail::BoundArgFunction<ConfigT> const& _boundField ) : CommonArgProperties<ConfigT>( _boundField ) {}
-
- using CommonArgProperties<ConfigT>::placeholder; // !TBD
-
- std::string dbgName() const {
- if( !longName.empty() )
- return "--" + longName;
- if( !shortNames.empty() )
- return "-" + shortNames[0];
- return "positional args";
- }
- std::string commands() const {
- std::ostringstream oss;
- bool first = true;
- std::vector<std::string>::const_iterator it = shortNames.begin(), itEnd = shortNames.end();
- for(; it != itEnd; ++it ) {
- if( first )
- first = false;
- else
- oss << ", ";
- oss << "-" << *it;
- }
- if( !longName.empty() ) {
- if( !first )
- oss << ", ";
- oss << "--" << longName;
- }
- if( !placeholder.empty() )
- oss << " <" << placeholder << ">";
- return oss.str();
- }
- };
-
- typedef CLARA_AUTO_PTR( Arg ) ArgAutoPtr;
-
- friend void addOptName( Arg& arg, std::string const& optName )
- {
- if( optName.empty() )
- return;
- if( Detail::startsWith( optName, "--" ) ) {
- if( !arg.longName.empty() )
- throw std::logic_error( "Only one long opt may be specified. '"
- + arg.longName
- + "' already specified, now attempting to add '"
- + optName + "'" );
- arg.longName = optName.substr( 2 );
- }
- else if( Detail::startsWith( optName, "-" ) )
- arg.shortNames.push_back( optName.substr( 1 ) );
- else
- throw std::logic_error( "option must begin with - or --. Option was: '" + optName + "'" );
- }
- friend void setPositionalArg( Arg& arg, int position )
- {
- arg.position = position;
- }
-
- class ArgBuilder {
- public:
- ArgBuilder( Arg* arg ) : m_arg( arg ) {}
-
- // Bind a non-boolean data member (requires placeholder string)
- template<typename C, typename M>
- void bind( M C::* field, std::string const& placeholder ) {
- m_arg->boundField = new Detail::BoundDataMember<C,M>( field );
- m_arg->placeholder = placeholder;
- }
- // Bind a boolean data member (no placeholder required)
- template<typename C>
- void bind( bool C::* field ) {
- m_arg->boundField = new Detail::BoundDataMember<C,bool>( field );
- }
-
- // Bind a method taking a single, non-boolean argument (requires a placeholder string)
- template<typename C, typename M>
- void bind( void (C::* unaryMethod)( M ), std::string const& placeholder ) {
- m_arg->boundField = new Detail::BoundUnaryMethod<C,M>( unaryMethod );
- m_arg->placeholder = placeholder;
- }
-
- // Bind a method taking a single, boolean argument (no placeholder string required)
- template<typename C>
- void bind( void (C::* unaryMethod)( bool ) ) {
- m_arg->boundField = new Detail::BoundUnaryMethod<C,bool>( unaryMethod );
- }
-
- // Bind a method that takes no arguments (will be called if opt is present)
- template<typename C>
- void bind( void (C::* nullaryMethod)() ) {
- m_arg->boundField = new Detail::BoundNullaryMethod<C>( nullaryMethod );
- }
-
- // Bind a free function taking a single argument - the object to operate on (no placeholder string required)
- template<typename C>
- void bind( void (* unaryFunction)( C& ) ) {
- m_arg->boundField = new Detail::BoundUnaryFunction<C>( unaryFunction );
- }
-
- // Bind a free function taking a single argument - the object to operate on (requires a placeholder string)
- template<typename C, typename T>
- void bind( void (* binaryFunction)( C&, T ), std::string const& placeholder ) {
- m_arg->boundField = new Detail::BoundBinaryFunction<C, T>( binaryFunction );
- m_arg->placeholder = placeholder;
- }
-
- ArgBuilder& describe( std::string const& description ) {
- m_arg->description = description;
- return *this;
- }
- ArgBuilder& detail( std::string const& detail ) {
- m_arg->detail = detail;
- return *this;
- }
-
- protected:
- Arg* m_arg;
- };
-
- class OptBuilder : public ArgBuilder {
- public:
- OptBuilder( Arg* arg ) : ArgBuilder( arg ) {}
- OptBuilder( OptBuilder& other ) : ArgBuilder( other ) {}
-
- OptBuilder& operator[]( std::string const& optName ) {
- addOptName( *ArgBuilder::m_arg, optName );
- return *this;
- }
- };
-
- public:
-
- CommandLine()
- : m_boundProcessName( new Detail::NullBinder<ConfigT>() ),
- m_highestSpecifiedArgPosition( 0 ),
- m_throwOnUnrecognisedTokens( false )
- {}
- CommandLine( CommandLine const& other )
- : m_boundProcessName( other.m_boundProcessName ),
- m_options ( other.m_options ),
- m_positionalArgs( other.m_positionalArgs ),
- m_highestSpecifiedArgPosition( other.m_highestSpecifiedArgPosition ),
- m_throwOnUnrecognisedTokens( other.m_throwOnUnrecognisedTokens )
- {
- if( other.m_floatingArg.get() )
- m_floatingArg.reset( new Arg( *other.m_floatingArg ) );
- }
-
- CommandLine& setThrowOnUnrecognisedTokens( bool shouldThrow = true ) {
- m_throwOnUnrecognisedTokens = shouldThrow;
- return *this;
- }
-
- OptBuilder operator[]( std::string const& optName ) {
- m_options.push_back( Arg() );
- addOptName( m_options.back(), optName );
- OptBuilder builder( &m_options.back() );
- return builder;
- }
-
- ArgBuilder operator[]( int position ) {
- m_positionalArgs.insert( std::make_pair( position, Arg() ) );
- if( position > m_highestSpecifiedArgPosition )
- m_highestSpecifiedArgPosition = position;
- setPositionalArg( m_positionalArgs[position], position );
- ArgBuilder builder( &m_positionalArgs[position] );
- return builder;
- }
-
- // Invoke this with the _ instance
- ArgBuilder operator[]( UnpositionalTag ) {
- if( m_floatingArg.get() )
- throw std::logic_error( "Only one unpositional argument can be added" );
- m_floatingArg.reset( new Arg() );
- ArgBuilder builder( m_floatingArg.get() );
- return builder;
- }
-
- template<typename C, typename M>
- void bindProcessName( M C::* field ) {
- m_boundProcessName = new Detail::BoundDataMember<C,M>( field );
- }
- template<typename C, typename M>
- void bindProcessName( void (C::*_unaryMethod)( M ) ) {
- m_boundProcessName = new Detail::BoundUnaryMethod<C,M>( _unaryMethod );
- }
-
- void optUsage( std::ostream& os, std::size_t indent = 0, std::size_t width = Detail::consoleWidth ) const {
- typename std::vector<Arg>::const_iterator itBegin = m_options.begin(), itEnd = m_options.end(), it;
- std::size_t maxWidth = 0;
- for( it = itBegin; it != itEnd; ++it )
- maxWidth = (std::max)( maxWidth, it->commands().size() );
-
- for( it = itBegin; it != itEnd; ++it ) {
- Detail::Text usage( it->commands(), Detail::TextAttributes()
- .setWidth( maxWidth+indent )
- .setIndent( indent ) );
- Detail::Text desc( it->description, Detail::TextAttributes()
- .setWidth( width - maxWidth - 3 ) );
-
- for( std::size_t i = 0; i < (std::max)( usage.size(), desc.size() ); ++i ) {
- std::string usageCol = i < usage.size() ? usage[i] : "";
- os << usageCol;
-
- if( i < desc.size() && !desc[i].empty() )
- os << std::string( indent + 2 + maxWidth - usageCol.size(), ' ' )
- << desc[i];
- os << "\n";
- }
- }
- }
- std::string optUsage() const {
- std::ostringstream oss;
- optUsage( oss );
- return oss.str();
- }
-
- void argSynopsis( std::ostream& os ) const {
- for( int i = 1; i <= m_highestSpecifiedArgPosition; ++i ) {
- if( i > 1 )
- os << " ";
- typename std::map<int, Arg>::const_iterator it = m_positionalArgs.find( i );
- if( it != m_positionalArgs.end() )
- os << "<" << it->second.placeholder << ">";
- else if( m_floatingArg.get() )
- os << "<" << m_floatingArg->placeholder << ">";
- else
- throw std::logic_error( "non consecutive positional arguments with no floating args" );
- }
- // !TBD No indication of mandatory args
- if( m_floatingArg.get() ) {
- if( m_highestSpecifiedArgPosition > 1 )
- os << " ";
- os << "[<" << m_floatingArg->placeholder << "> ...]";
- }
- }
- std::string argSynopsis() const {
- std::ostringstream oss;
- argSynopsis( oss );
- return oss.str();
- }
-
- void usage( std::ostream& os, std::string const& procName ) const {
- validate();
- os << "usage:\n " << procName << " ";
- argSynopsis( os );
- if( !m_options.empty() ) {
- os << " [options]\n\nwhere options are: \n";
- optUsage( os, 2 );
- }
- os << "\n";
- }
- std::string usage( std::string const& procName ) const {
- std::ostringstream oss;
- usage( oss, procName );
- return oss.str();
- }
-
- ConfigT parse( std::vector<std::string> const& args ) const {
- ConfigT config;
- parseInto( args, config );
- return config;
- }
-
- std::vector<Parser::Token> parseInto( std::vector<std::string> const& args, ConfigT& config ) const {
- std::string processName = args.empty() ? std::string() : args[0];
- std::size_t lastSlash = processName.find_last_of( "/\\" );
- if( lastSlash != std::string::npos )
- processName = processName.substr( lastSlash+1 );
- m_boundProcessName.set( config, processName );
- std::vector<Parser::Token> tokens;
- Parser parser;
- parser.parseIntoTokens( args, tokens );
- return populate( tokens, config );
- }
-
- std::vector<Parser::Token> populate( std::vector<Parser::Token> const& tokens, ConfigT& config ) const {
- validate();
- std::vector<Parser::Token> unusedTokens = populateOptions( tokens, config );
- unusedTokens = populateFixedArgs( unusedTokens, config );
- unusedTokens = populateFloatingArgs( unusedTokens, config );
- return unusedTokens;
- }
-
- std::vector<Parser::Token> populateOptions( std::vector<Parser::Token> const& tokens, ConfigT& config ) const {
- std::vector<Parser::Token> unusedTokens;
- std::vector<std::string> errors;
- for( std::size_t i = 0; i < tokens.size(); ++i ) {
- Parser::Token const& token = tokens[i];
- typename std::vector<Arg>::const_iterator it = m_options.begin(), itEnd = m_options.end();
- for(; it != itEnd; ++it ) {
- Arg const& arg = *it;
-
- try {
- if( ( token.type == Parser::Token::ShortOpt && arg.hasShortName( token.data ) ) ||
- ( token.type == Parser::Token::LongOpt && arg.hasLongName( token.data ) ) ) {
- if( arg.takesArg() ) {
- if( i == tokens.size()-1 || tokens[i+1].type != Parser::Token::Positional )
- errors.push_back( "Expected argument to option: " + token.data );
- else
- arg.boundField.set( config, tokens[++i].data );
- }
- else {
- arg.boundField.set( config, "true" );
- }
- break;
- }
- }
- catch( std::exception& ex ) {
- errors.push_back( std::string( ex.what() ) + "\n- while parsing: (" + arg.commands() + ")" );
- }
- }
- if( it == itEnd ) {
- if( token.type == Parser::Token::Positional || !m_throwOnUnrecognisedTokens )
- unusedTokens.push_back( token );
- else if( errors.empty() && m_throwOnUnrecognisedTokens )
- errors.push_back( "unrecognised option: " + token.data );
- }
- }
- if( !errors.empty() ) {
- std::ostringstream oss;
- for( std::vector<std::string>::const_iterator it = errors.begin(), itEnd = errors.end();
- it != itEnd;
- ++it ) {
- if( it != errors.begin() )
- oss << "\n";
- oss << *it;
- }
- throw std::runtime_error( oss.str() );
- }
- return unusedTokens;
- }
- std::vector<Parser::Token> populateFixedArgs( std::vector<Parser::Token> const& tokens, ConfigT& config ) const {
- std::vector<Parser::Token> unusedTokens;
- int position = 1;
- for( std::size_t i = 0; i < tokens.size(); ++i ) {
- Parser::Token const& token = tokens[i];
- typename std::map<int, Arg>::const_iterator it = m_positionalArgs.find( position );
- if( it != m_positionalArgs.end() )
- it->second.boundField.set( config, token.data );
- else
- unusedTokens.push_back( token );
- if( token.type == Parser::Token::Positional )
- position++;
- }
- return unusedTokens;
- }
- std::vector<Parser::Token> populateFloatingArgs( std::vector<Parser::Token> const& tokens, ConfigT& config ) const {
- if( !m_floatingArg.get() )
- return tokens;
- std::vector<Parser::Token> unusedTokens;
- for( std::size_t i = 0; i < tokens.size(); ++i ) {
- Parser::Token const& token = tokens[i];
- if( token.type == Parser::Token::Positional )
- m_floatingArg->boundField.set( config, token.data );
- else
- unusedTokens.push_back( token );
- }
- return unusedTokens;
- }
-
- void validate() const
- {
- if( m_options.empty() && m_positionalArgs.empty() && !m_floatingArg.get() )
- throw std::logic_error( "No options or arguments specified" );
-
- for( typename std::vector<Arg>::const_iterator it = m_options.begin(),
- itEnd = m_options.end();
- it != itEnd; ++it )
- it->validate();
- }
-
- private:
- Detail::BoundArgFunction<ConfigT> m_boundProcessName;
- std::vector<Arg> m_options;
- std::map<int, Arg> m_positionalArgs;
- ArgAutoPtr m_floatingArg;
- int m_highestSpecifiedArgPosition;
- bool m_throwOnUnrecognisedTokens;
- };
-
-} // end namespace Clara
-
-STITCH_CLARA_CLOSE_NAMESPACE
-#undef STITCH_CLARA_OPEN_NAMESPACE
-#undef STITCH_CLARA_CLOSE_NAMESPACE
-
-#endif // TWOBLUECUBES_CLARA_H_INCLUDED
-#undef STITCH_CLARA_OPEN_NAMESPACE
-
-// Restore Clara's value for console width, if present
-#ifdef CATCH_TEMP_CLARA_CONFIG_CONSOLE_WIDTH
-#define CLARA_CONFIG_CONSOLE_WIDTH CATCH_TEMP_CLARA_CONFIG_CONSOLE_WIDTH
-#undef CATCH_TEMP_CLARA_CONFIG_CONSOLE_WIDTH
-#endif
-
-#include <fstream>
-#include <ctime>
-
-namespace Catch {
-
- inline void abortAfterFirst( ConfigData& config ) { config.abortAfter = 1; }
- inline void abortAfterX( ConfigData& config, int x ) {
- if( x < 1 )
- throw std::runtime_error( "Value after -x or --abortAfter must be greater than zero" );
- config.abortAfter = x;
- }
- inline void addTestOrTags( ConfigData& config, std::string const& _testSpec ) { config.testsOrTags.push_back( _testSpec ); }
- inline void addSectionToRun( ConfigData& config, std::string const& sectionName ) { config.sectionsToRun.push_back( sectionName ); }
- inline void addReporterName( ConfigData& config, std::string const& _reporterName ) { config.reporterNames.push_back( _reporterName ); }
-
- inline void addWarning( ConfigData& config, std::string const& _warning ) {
- if( _warning == "NoAssertions" )
- config.warnings = static_cast<WarnAbout::What>( config.warnings | WarnAbout::NoAssertions );
- else
- throw std::runtime_error( "Unrecognised warning: '" + _warning + '\'' );
- }
- inline void setOrder( ConfigData& config, std::string const& order ) {
- if( startsWith( "declared", order ) )
- config.runOrder = RunTests::InDeclarationOrder;
- else if( startsWith( "lexical", order ) )
- config.runOrder = RunTests::InLexicographicalOrder;
- else if( startsWith( "random", order ) )
- config.runOrder = RunTests::InRandomOrder;
- else
- throw std::runtime_error( "Unrecognised ordering: '" + order + '\'' );
- }
- inline void setRngSeed( ConfigData& config, std::string const& seed ) {
- if( seed == "time" ) {
- config.rngSeed = static_cast<unsigned int>( std::time(0) );
- }
- else {
- std::stringstream ss;
- ss << seed;
- ss >> config.rngSeed;
- if( ss.fail() )
- throw std::runtime_error( "Argument to --rng-seed should be the word 'time' or a number" );
- }
- }
- inline void setVerbosity( ConfigData& config, int level ) {
- // !TBD: accept strings?
- config.verbosity = static_cast<Verbosity::Level>( level );
- }
- inline void setShowDurations( ConfigData& config, bool _showDurations ) {
- config.showDurations = _showDurations
- ? ShowDurations::Always
- : ShowDurations::Never;
- }
- inline void setUseColour( ConfigData& config, std::string const& value ) {
- std::string mode = toLower( value );
-
- if( mode == "yes" )
- config.useColour = UseColour::Yes;
- else if( mode == "no" )
- config.useColour = UseColour::No;
- else if( mode == "auto" )
- config.useColour = UseColour::Auto;
- else
- throw std::runtime_error( "colour mode must be one of: auto, yes or no" );
- }
- inline void setWaitForKeypress( ConfigData& config, std::string const& keypress ) {
- std::string keypressLc = toLower( keypress );
- if( keypressLc == "start" )
- config.waitForKeypress = WaitForKeypress::BeforeStart;
- else if( keypressLc == "exit" )
- config.waitForKeypress = WaitForKeypress::BeforeExit;
- else if( keypressLc == "both" )
- config.waitForKeypress = WaitForKeypress::BeforeStartAndExit;
- else
- throw std::runtime_error( "keypress argument must be one of: start, exit or both. '" + keypress + "' not recognised" );
- };
-
- inline void forceColour( ConfigData& config ) {
- config.useColour = UseColour::Yes;
- }
- inline void loadTestNamesFromFile( ConfigData& config, std::string const& _filename ) {
- std::ifstream f( _filename.c_str() );
- if( !f.is_open() )
- throw std::domain_error( "Unable to load input file: " + _filename );
-
- std::string line;
- while( std::getline( f, line ) ) {
- line = trim(line);
- if( !line.empty() && !startsWith( line, '#' ) ) {
- if( !startsWith( line, '"' ) )
- line = '"' + line + '"';
- addTestOrTags( config, line + ',' );
- }
- }
- }
-
- inline Clara::CommandLine<ConfigData> makeCommandLineParser() {
-
- using namespace Clara;
- CommandLine<ConfigData> cli;
-
- cli.bindProcessName( &ConfigData::processName );
-
- cli["-?"]["-h"]["--help"]
- .describe( "display usage information" )
- .bind( &ConfigData::showHelp );
-
- cli["-l"]["--list-tests"]
- .describe( "list all/matching test cases" )
- .bind( &ConfigData::listTests );
-
- cli["-t"]["--list-tags"]
- .describe( "list all/matching tags" )
- .bind( &ConfigData::listTags );
-
- cli["-s"]["--success"]
- .describe( "include successful tests in output" )
- .bind( &ConfigData::showSuccessfulTests );
-
- cli["-b"]["--break"]
- .describe( "break into debugger on failure" )
- .bind( &ConfigData::shouldDebugBreak );
-
- cli["-e"]["--nothrow"]
- .describe( "skip exception tests" )
- .bind( &ConfigData::noThrow );
-
- cli["-i"]["--invisibles"]
- .describe( "show invisibles (tabs, newlines)" )
- .bind( &ConfigData::showInvisibles );
-
- cli["-o"]["--out"]
- .describe( "output filename" )
- .bind( &ConfigData::outputFilename, "filename" );
-
- cli["-r"]["--reporter"]
-// .placeholder( "name[:filename]" )
- .describe( "reporter to use (defaults to console)" )
- .bind( &addReporterName, "name" );
-
- cli["-n"]["--name"]
- .describe( "suite name" )
- .bind( &ConfigData::name, "name" );
-
- cli["-a"]["--abort"]
- .describe( "abort at first failure" )
- .bind( &abortAfterFirst );
-
- cli["-x"]["--abortx"]
- .describe( "abort after x failures" )
- .bind( &abortAfterX, "no. failures" );
-
- cli["-w"]["--warn"]
- .describe( "enable warnings" )
- .bind( &addWarning, "warning name" );
-
-// - needs updating if reinstated
-// cli.into( &setVerbosity )
-// .describe( "level of verbosity (0=no output)" )
-// .shortOpt( "v")
-// .longOpt( "verbosity" )
-// .placeholder( "level" );
-
- cli[_]
- .describe( "which test or tests to use" )
- .bind( &addTestOrTags, "test name, pattern or tags" );
-
- cli["-d"]["--durations"]
- .describe( "show test durations" )
- .bind( &setShowDurations, "yes|no" );
-
- cli["-f"]["--input-file"]
- .describe( "load test names to run from a file" )
- .bind( &loadTestNamesFromFile, "filename" );
-
- cli["-#"]["--filenames-as-tags"]
- .describe( "adds a tag for the filename" )
- .bind( &ConfigData::filenamesAsTags );
-
- cli["-c"]["--section"]
- .describe( "specify section to run" )
- .bind( &addSectionToRun, "section name" );
-
- // Less common commands which don't have a short form
- cli["--list-test-names-only"]
- .describe( "list all/matching test cases names only" )
- .bind( &ConfigData::listTestNamesOnly );
-
- cli["--list-extra-info"]
- .describe( "list all/matching test cases with more info" )
- .bind( &ConfigData::listExtraInfo );
-
- cli["--list-reporters"]
- .describe( "list all reporters" )
- .bind( &ConfigData::listReporters );
-
- cli["--order"]
- .describe( "test case order (defaults to decl)" )
- .bind( &setOrder, "decl|lex|rand" );
-
- cli["--rng-seed"]
- .describe( "set a specific seed for random numbers" )
- .bind( &setRngSeed, "'time'|number" );
-
- cli["--force-colour"]
- .describe( "force colourised output (deprecated)" )
- .bind( &forceColour );
-
- cli["--use-colour"]
- .describe( "should output be colourised" )
- .bind( &setUseColour, "yes|no" );
-
- cli["--libidentify"]
- .describe( "report name and version according to libidentify standard" )
- .bind( &ConfigData::libIdentify );
-
- cli["--wait-for-keypress"]
- .describe( "waits for a keypress before exiting" )
- .bind( &setWaitForKeypress, "start|exit|both" );
-
- return cli;
- }
-
-} // end namespace Catch
-
-// #included from: internal/catch_list.hpp
-#define TWOBLUECUBES_CATCH_LIST_HPP_INCLUDED
-
-// #included from: catch_text.h
-#define TWOBLUECUBES_CATCH_TEXT_H_INCLUDED
-
-#define TBC_TEXT_FORMAT_CONSOLE_WIDTH CATCH_CONFIG_CONSOLE_WIDTH
-
-#define CLICHE_TBC_TEXT_FORMAT_OUTER_NAMESPACE Catch
-// #included from: ../external/tbc_text_format.h
-// Only use header guard if we are not using an outer namespace
-#ifndef CLICHE_TBC_TEXT_FORMAT_OUTER_NAMESPACE
-# ifdef TWOBLUECUBES_TEXT_FORMAT_H_INCLUDED
-# ifndef TWOBLUECUBES_TEXT_FORMAT_H_ALREADY_INCLUDED
-# define TWOBLUECUBES_TEXT_FORMAT_H_ALREADY_INCLUDED
-# endif
-# else
-# define TWOBLUECUBES_TEXT_FORMAT_H_INCLUDED
-# endif
-#endif
-#ifndef TWOBLUECUBES_TEXT_FORMAT_H_ALREADY_INCLUDED
-#include <string>
-#include <vector>
-#include <sstream>
-
-// Use optional outer namespace
-#ifdef CLICHE_TBC_TEXT_FORMAT_OUTER_NAMESPACE
-namespace CLICHE_TBC_TEXT_FORMAT_OUTER_NAMESPACE {
-#endif
-
-namespace Tbc {
-
-#ifdef TBC_TEXT_FORMAT_CONSOLE_WIDTH
- const unsigned int consoleWidth = TBC_TEXT_FORMAT_CONSOLE_WIDTH;
-#else
- const unsigned int consoleWidth = 80;
-#endif
-
- struct TextAttributes {
- TextAttributes()
- : initialIndent( std::string::npos ),
- indent( 0 ),
- width( consoleWidth-1 )
- {}
-
- TextAttributes& setInitialIndent( std::size_t _value ) { initialIndent = _value; return *this; }
- TextAttributes& setIndent( std::size_t _value ) { indent = _value; return *this; }
- TextAttributes& setWidth( std::size_t _value ) { width = _value; return *this; }
-
- std::size_t initialIndent; // indent of first line, or npos
- std::size_t indent; // indent of subsequent lines, or all if initialIndent is npos
- std::size_t width; // maximum width of text, including indent. Longer text will wrap
- };
-
- class Text {
- public:
- Text( std::string const& _str, TextAttributes const& _attr = TextAttributes() )
- : attr( _attr )
- {
- const std::string wrappableBeforeChars = "[({<\t";
- const std::string wrappableAfterChars = "])}>-,./|\\";
- const std::string wrappableInsteadOfChars = " \n\r";
- std::string indent = _attr.initialIndent != std::string::npos
- ? std::string( _attr.initialIndent, ' ' )
- : std::string( _attr.indent, ' ' );
-
- typedef std::string::const_iterator iterator;
- iterator it = _str.begin();
- const iterator strEnd = _str.end();
-
- while( it != strEnd ) {
-
- if( lines.size() >= 1000 ) {
- lines.push_back( "... message truncated due to excessive size" );
- return;
- }
-
- std::string suffix;
- std::size_t width = (std::min)( static_cast<size_t>( strEnd-it ), _attr.width-static_cast<size_t>( indent.size() ) );
- iterator itEnd = it+width;
- iterator itNext = _str.end();
-
- iterator itNewLine = std::find( it, itEnd, '\n' );
- if( itNewLine != itEnd )
- itEnd = itNewLine;
-
- if( itEnd != strEnd ) {
- bool foundWrapPoint = false;
- iterator findIt = itEnd;
- do {
- if( wrappableAfterChars.find( *findIt ) != std::string::npos && findIt != itEnd ) {
- itEnd = findIt+1;
- itNext = findIt+1;
- foundWrapPoint = true;
- }
- else if( findIt > it && wrappableBeforeChars.find( *findIt ) != std::string::npos ) {
- itEnd = findIt;
- itNext = findIt;
- foundWrapPoint = true;
- }
- else if( wrappableInsteadOfChars.find( *findIt ) != std::string::npos ) {
- itNext = findIt+1;
- itEnd = findIt;
- foundWrapPoint = true;
- }
- if( findIt == it )
- break;
- else
- --findIt;
- }
- while( !foundWrapPoint );
-
- if( !foundWrapPoint ) {
- // No good wrap char, so we'll break mid word and add a hyphen
- --itEnd;
- itNext = itEnd;
- suffix = "-";
- }
- else {
- while( itEnd > it && wrappableInsteadOfChars.find( *(itEnd-1) ) != std::string::npos )
- --itEnd;
- }
- }
- lines.push_back( indent + std::string( it, itEnd ) + suffix );
-
- if( indent.size() != _attr.indent )
- indent = std::string( _attr.indent, ' ' );
- it = itNext;
- }
- }
-
- typedef std::vector<std::string>::const_iterator const_iterator;
-
- const_iterator begin() const { return lines.begin(); }
- const_iterator end() const { return lines.end(); }
- std::string const& last() const { return lines.back(); }
- std::size_t size() const { return lines.size(); }
- std::string const& operator[]( std::size_t _index ) const { return lines[_index]; }
- std::string toString() const {
- std::ostringstream oss;
- oss << *this;
- return oss.str();
- }
-
- inline friend std::ostream& operator << ( std::ostream& _stream, Text const& _text ) {
- for( Text::const_iterator it = _text.begin(), itEnd = _text.end();
- it != itEnd; ++it ) {
- if( it != _text.begin() )
- _stream << "\n";
- _stream << *it;
- }
- return _stream;
- }
-
- private:
- std::string str;
- TextAttributes attr;
- std::vector<std::string> lines;
- };
-
-} // end namespace Tbc
-
-#ifdef CLICHE_TBC_TEXT_FORMAT_OUTER_NAMESPACE
-} // end outer namespace
-#endif
-
-#endif // TWOBLUECUBES_TEXT_FORMAT_H_ALREADY_INCLUDED
-#undef CLICHE_TBC_TEXT_FORMAT_OUTER_NAMESPACE
-
-namespace Catch {
- using Tbc::Text;
- using Tbc::TextAttributes;
-}
-
-// #included from: catch_console_colour.hpp
-#define TWOBLUECUBES_CATCH_CONSOLE_COLOUR_HPP_INCLUDED
-
-namespace Catch {
-
- struct Colour {
- enum Code {
- None = 0,
-
- White,
- Red,
- Green,
- Blue,
- Cyan,
- Yellow,
- Grey,
-
- Bright = 0x10,
-
- BrightRed = Bright | Red,
- BrightGreen = Bright | Green,
- LightGrey = Bright | Grey,
- BrightWhite = Bright | White,
-
- // By intention
- FileName = LightGrey,
- Warning = Yellow,
- ResultError = BrightRed,
- ResultSuccess = BrightGreen,
- ResultExpectedFailure = Warning,
-
- Error = BrightRed,
- Success = Green,
-
- OriginalExpression = Cyan,
- ReconstructedExpression = Yellow,
-
- SecondaryText = LightGrey,
- Headers = White
- };
-
- // Use constructed object for RAII guard
- Colour( Code _colourCode );
- Colour( Colour const& other );
- ~Colour();
-
- // Use static method for one-shot changes
- static void use( Code _colourCode );
-
- private:
- bool m_moved;
- };
-
- inline std::ostream& operator << ( std::ostream& os, Colour const& ) { return os; }
-
-} // end namespace Catch
-
-// #included from: catch_interfaces_reporter.h
-#define TWOBLUECUBES_CATCH_INTERFACES_REPORTER_H_INCLUDED
-
-#include <string>
-#include <ostream>
-#include <map>
-
-namespace Catch
-{
- struct ReporterConfig {
- explicit ReporterConfig( Ptr<IConfig const> const& _fullConfig )
- : m_stream( &_fullConfig->stream() ), m_fullConfig( _fullConfig ) {}
-
- ReporterConfig( Ptr<IConfig const> const& _fullConfig, std::ostream& _stream )
- : m_stream( &_stream ), m_fullConfig( _fullConfig ) {}
-
- std::ostream& stream() const { return *m_stream; }
- Ptr<IConfig const> fullConfig() const { return m_fullConfig; }
-
- private:
- std::ostream* m_stream;
- Ptr<IConfig const> m_fullConfig;
- };
-
- struct ReporterPreferences {
- ReporterPreferences()
- : shouldRedirectStdOut( false )
- {}
-
- bool shouldRedirectStdOut;
- };
-
- template<typename T>
- struct LazyStat : Option<T> {
- LazyStat() : used( false ) {}
- LazyStat& operator=( T const& _value ) {
- Option<T>::operator=( _value );
- used = false;
- return *this;
- }
- void reset() {
- Option<T>::reset();
- used = false;
- }
- bool used;
- };
-
- struct TestRunInfo {
- TestRunInfo( std::string const& _name ) : name( _name ) {}
- std::string name;
- };
- struct GroupInfo {
- GroupInfo( std::string const& _name,
- std::size_t _groupIndex,
- std::size_t _groupsCount )
- : name( _name ),
- groupIndex( _groupIndex ),
- groupsCounts( _groupsCount )
- {}
-
- std::string name;
- std::size_t groupIndex;
- std::size_t groupsCounts;
- };
-
- struct AssertionStats {
- AssertionStats( AssertionResult const& _assertionResult,
- std::vector<MessageInfo> const& _infoMessages,
- Totals const& _totals )
- : assertionResult( _assertionResult ),
- infoMessages( _infoMessages ),
- totals( _totals )
- {
- if( assertionResult.hasMessage() ) {
- // Copy message into messages list.
- // !TBD This should have been done earlier, somewhere
- MessageBuilder builder( assertionResult.getTestMacroName(), assertionResult.getSourceInfo(), assertionResult.getResultType() );
- builder << assertionResult.getMessage();
- builder.m_info.message = builder.m_stream.str();
-
- infoMessages.push_back( builder.m_info );
- }
- }
- virtual ~AssertionStats();
-
-# ifdef CATCH_CONFIG_CPP11_GENERATED_METHODS
- AssertionStats( AssertionStats const& ) = default;
- AssertionStats( AssertionStats && ) = default;
- AssertionStats& operator = ( AssertionStats const& ) = default;
- AssertionStats& operator = ( AssertionStats && ) = default;
-# endif
-
- AssertionResult assertionResult;
- std::vector<MessageInfo> infoMessages;
- Totals totals;
- };
-
- struct SectionStats {
- SectionStats( SectionInfo const& _sectionInfo,
- Counts const& _assertions,
- double _durationInSeconds,
- bool _missingAssertions )
- : sectionInfo( _sectionInfo ),
- assertions( _assertions ),
- durationInSeconds( _durationInSeconds ),
- missingAssertions( _missingAssertions )
- {}
- virtual ~SectionStats();
-# ifdef CATCH_CONFIG_CPP11_GENERATED_METHODS
- SectionStats( SectionStats const& ) = default;
- SectionStats( SectionStats && ) = default;
- SectionStats& operator = ( SectionStats const& ) = default;
- SectionStats& operator = ( SectionStats && ) = default;
-# endif
-
- SectionInfo sectionInfo;
- Counts assertions;
- double durationInSeconds;
- bool missingAssertions;
- };
-
- struct TestCaseStats {
- TestCaseStats( TestCaseInfo const& _testInfo,
- Totals const& _totals,
- std::string const& _stdOut,
- std::string const& _stdErr,
- bool _aborting )
- : testInfo( _testInfo ),
- totals( _totals ),
- stdOut( _stdOut ),
- stdErr( _stdErr ),
- aborting( _aborting )
- {}
- virtual ~TestCaseStats();
-
-# ifdef CATCH_CONFIG_CPP11_GENERATED_METHODS
- TestCaseStats( TestCaseStats const& ) = default;
- TestCaseStats( TestCaseStats && ) = default;
- TestCaseStats& operator = ( TestCaseStats const& ) = default;
- TestCaseStats& operator = ( TestCaseStats && ) = default;
-# endif
-
- TestCaseInfo testInfo;
- Totals totals;
- std::string stdOut;
- std::string stdErr;
- bool aborting;
- };
-
- struct TestGroupStats {
- TestGroupStats( GroupInfo const& _groupInfo,
- Totals const& _totals,
- bool _aborting )
- : groupInfo( _groupInfo ),
- totals( _totals ),
- aborting( _aborting )
- {}
- TestGroupStats( GroupInfo const& _groupInfo )
- : groupInfo( _groupInfo ),
- aborting( false )
- {}
- virtual ~TestGroupStats();
-
-# ifdef CATCH_CONFIG_CPP11_GENERATED_METHODS
- TestGroupStats( TestGroupStats const& ) = default;
- TestGroupStats( TestGroupStats && ) = default;
- TestGroupStats& operator = ( TestGroupStats const& ) = default;
- TestGroupStats& operator = ( TestGroupStats && ) = default;
-# endif
-
- GroupInfo groupInfo;
- Totals totals;
- bool aborting;
- };
-
- struct TestRunStats {
- TestRunStats( TestRunInfo const& _runInfo,
- Totals const& _totals,
- bool _aborting )
- : runInfo( _runInfo ),
- totals( _totals ),
- aborting( _aborting )
- {}
- virtual ~TestRunStats();
-
-# ifndef CATCH_CONFIG_CPP11_GENERATED_METHODS
- TestRunStats( TestRunStats const& _other )
- : runInfo( _other.runInfo ),
- totals( _other.totals ),
- aborting( _other.aborting )
- {}
-# else
- TestRunStats( TestRunStats const& ) = default;
- TestRunStats( TestRunStats && ) = default;
- TestRunStats& operator = ( TestRunStats const& ) = default;
- TestRunStats& operator = ( TestRunStats && ) = default;
-# endif
-
- TestRunInfo runInfo;
- Totals totals;
- bool aborting;
- };
-
- class MultipleReporters;
-
- struct IStreamingReporter : IShared {
- virtual ~IStreamingReporter();
-
- // Implementing class must also provide the following static method:
- // static std::string getDescription();
-
- virtual ReporterPreferences getPreferences() const = 0;
-
- virtual void noMatchingTestCases( std::string const& spec ) = 0;
-
- virtual void testRunStarting( TestRunInfo const& testRunInfo ) = 0;
- virtual void testGroupStarting( GroupInfo const& groupInfo ) = 0;
-
- virtual void testCaseStarting( TestCaseInfo const& testInfo ) = 0;
- virtual void sectionStarting( SectionInfo const& sectionInfo ) = 0;
-
- virtual void assertionStarting( AssertionInfo const& assertionInfo ) = 0;
-
- // The return value indicates if the messages buffer should be cleared:
- virtual bool assertionEnded( AssertionStats const& assertionStats ) = 0;
-
- virtual void sectionEnded( SectionStats const& sectionStats ) = 0;
- virtual void testCaseEnded( TestCaseStats const& testCaseStats ) = 0;
- virtual void testGroupEnded( TestGroupStats const& testGroupStats ) = 0;
- virtual void testRunEnded( TestRunStats const& testRunStats ) = 0;
-
- virtual void skipTest( TestCaseInfo const& testInfo ) = 0;
-
- virtual MultipleReporters* tryAsMulti() { return CATCH_NULL; }
- };
-
- struct IReporterFactory : IShared {
- virtual ~IReporterFactory();
- virtual IStreamingReporter* create( ReporterConfig const& config ) const = 0;
- virtual std::string getDescription() const = 0;
- };
-
- struct IReporterRegistry {
- typedef std::map<std::string, Ptr<IReporterFactory> > FactoryMap;
- typedef std::vector<Ptr<IReporterFactory> > Listeners;
-
- virtual ~IReporterRegistry();
- virtual IStreamingReporter* create( std::string const& name, Ptr<IConfig const> const& config ) const = 0;
- virtual FactoryMap const& getFactories() const = 0;
- virtual Listeners const& getListeners() const = 0;
- };
-
- Ptr<IStreamingReporter> addReporter( Ptr<IStreamingReporter> const& existingReporter, Ptr<IStreamingReporter> const& additionalReporter );
-
-}
-
-#include <limits>
-#include <algorithm>
-
-namespace Catch {
-
- inline std::size_t listTests( Config const& config ) {
-
- TestSpec testSpec = config.testSpec();
- if( config.testSpec().hasFilters() )
- Catch::cout() << "Matching test cases:\n";
- else {
- Catch::cout() << "All available test cases:\n";
- testSpec = TestSpecParser( ITagAliasRegistry::get() ).parse( "*" ).testSpec();
- }
-
- std::size_t matchedTests = 0;
- TextAttributes nameAttr, descAttr, tagsAttr;
- nameAttr.setInitialIndent( 2 ).setIndent( 4 );
- descAttr.setIndent( 4 );
- tagsAttr.setIndent( 6 );
-
- std::vector<TestCase> matchedTestCases = filterTests( getAllTestCasesSorted( config ), testSpec, config );
- for( std::vector<TestCase>::const_iterator it = matchedTestCases.begin(), itEnd = matchedTestCases.end();
- it != itEnd;
- ++it ) {
- matchedTests++;
- TestCaseInfo const& testCaseInfo = it->getTestCaseInfo();
- Colour::Code colour = testCaseInfo.isHidden()
- ? Colour::SecondaryText
- : Colour::None;
- Colour colourGuard( colour );
-
- Catch::cout() << Text( testCaseInfo.name, nameAttr ) << std::endl;
- if( config.listExtraInfo() ) {
- Catch::cout() << " " << testCaseInfo.lineInfo << std::endl;
- std::string description = testCaseInfo.description;
- if( description.empty() )
- description = "(NO DESCRIPTION)";
- Catch::cout() << Text( description, descAttr ) << std::endl;
- }
- if( !testCaseInfo.tags.empty() )
- Catch::cout() << Text( testCaseInfo.tagsAsString, tagsAttr ) << std::endl;
- }
-
- if( !config.testSpec().hasFilters() )
- Catch::cout() << pluralise( matchedTests, "test case" ) << '\n' << std::endl;
- else
- Catch::cout() << pluralise( matchedTests, "matching test case" ) << '\n' << std::endl;
- return matchedTests;
- }
-
- inline std::size_t listTestsNamesOnly( Config const& config ) {
- TestSpec testSpec = config.testSpec();
- if( !config.testSpec().hasFilters() )
- testSpec = TestSpecParser( ITagAliasRegistry::get() ).parse( "*" ).testSpec();
- std::size_t matchedTests = 0;
- std::vector<TestCase> matchedTestCases = filterTests( getAllTestCasesSorted( config ), testSpec, config );
- for( std::vector<TestCase>::const_iterator it = matchedTestCases.begin(), itEnd = matchedTestCases.end();
- it != itEnd;
- ++it ) {
- matchedTests++;
- TestCaseInfo const& testCaseInfo = it->getTestCaseInfo();
- if( startsWith( testCaseInfo.name, '#' ) )
- Catch::cout() << '"' << testCaseInfo.name << '"';
- else
- Catch::cout() << testCaseInfo.name;
- if ( config.listExtraInfo() )
- Catch::cout() << "\t@" << testCaseInfo.lineInfo;
- Catch::cout() << std::endl;
- }
- return matchedTests;
- }
-
- struct TagInfo {
- TagInfo() : count ( 0 ) {}
- void add( std::string const& spelling ) {
- ++count;
- spellings.insert( spelling );
- }
- std::string all() const {
- std::string out;
- for( std::set<std::string>::const_iterator it = spellings.begin(), itEnd = spellings.end();
- it != itEnd;
- ++it )
- out += "[" + *it + "]";
- return out;
- }
- std::set<std::string> spellings;
- std::size_t count;
- };
-
- inline std::size_t listTags( Config const& config ) {
- TestSpec testSpec = config.testSpec();
- if( config.testSpec().hasFilters() )
- Catch::cout() << "Tags for matching test cases:\n";
- else {
- Catch::cout() << "All available tags:\n";
- testSpec = TestSpecParser( ITagAliasRegistry::get() ).parse( "*" ).testSpec();
- }
-
- std::map<std::string, TagInfo> tagCounts;
-
- std::vector<TestCase> matchedTestCases = filterTests( getAllTestCasesSorted( config ), testSpec, config );
- for( std::vector<TestCase>::const_iterator it = matchedTestCases.begin(), itEnd = matchedTestCases.end();
- it != itEnd;
- ++it ) {
- for( std::set<std::string>::const_iterator tagIt = it->getTestCaseInfo().tags.begin(),
- tagItEnd = it->getTestCaseInfo().tags.end();
- tagIt != tagItEnd;
- ++tagIt ) {
- std::string tagName = *tagIt;
- std::string lcaseTagName = toLower( tagName );
- std::map<std::string, TagInfo>::iterator countIt = tagCounts.find( lcaseTagName );
- if( countIt == tagCounts.end() )
- countIt = tagCounts.insert( std::make_pair( lcaseTagName, TagInfo() ) ).first;
- countIt->second.add( tagName );
- }
- }
-
- for( std::map<std::string, TagInfo>::const_iterator countIt = tagCounts.begin(),
- countItEnd = tagCounts.end();
- countIt != countItEnd;
- ++countIt ) {
- std::ostringstream oss;
- oss << " " << std::setw(2) << countIt->second.count << " ";
- Text wrapper( countIt->second.all(), TextAttributes()
- .setInitialIndent( 0 )
- .setIndent( oss.str().size() )
- .setWidth( CATCH_CONFIG_CONSOLE_WIDTH-10 ) );
- Catch::cout() << oss.str() << wrapper << '\n';
- }
- Catch::cout() << pluralise( tagCounts.size(), "tag" ) << '\n' << std::endl;
- return tagCounts.size();
- }
-
- inline std::size_t listReporters( Config const& /*config*/ ) {
- Catch::cout() << "Available reporters:\n";
- IReporterRegistry::FactoryMap const& factories = getRegistryHub().getReporterRegistry().getFactories();
- IReporterRegistry::FactoryMap::const_iterator itBegin = factories.begin(), itEnd = factories.end(), it;
- std::size_t maxNameLen = 0;
- for(it = itBegin; it != itEnd; ++it )
- maxNameLen = (std::max)( maxNameLen, it->first.size() );
-
- for(it = itBegin; it != itEnd; ++it ) {
- Text wrapper( it->second->getDescription(), TextAttributes()
- .setInitialIndent( 0 )
- .setIndent( 7+maxNameLen )
- .setWidth( CATCH_CONFIG_CONSOLE_WIDTH - maxNameLen-8 ) );
- Catch::cout() << " "
- << it->first
- << ':'
- << std::string( maxNameLen - it->first.size() + 2, ' ' )
- << wrapper << '\n';
- }
- Catch::cout() << std::endl;
- return factories.size();
- }
-
- inline Option<std::size_t> list( Config const& config ) {
- Option<std::size_t> listedCount;
- if( config.listTests() || ( config.listExtraInfo() && !config.listTestNamesOnly() ) )
- listedCount = listedCount.valueOr(0) + listTests( config );
- if( config.listTestNamesOnly() )
- listedCount = listedCount.valueOr(0) + listTestsNamesOnly( config );
- if( config.listTags() )
- listedCount = listedCount.valueOr(0) + listTags( config );
- if( config.listReporters() )
- listedCount = listedCount.valueOr(0) + listReporters( config );
- return listedCount;
- }
-
-} // end namespace Catch
-
-// #included from: internal/catch_run_context.hpp
-#define TWOBLUECUBES_CATCH_RUNNER_IMPL_HPP_INCLUDED
-
-// #included from: catch_test_case_tracker.hpp
-#define TWOBLUECUBES_CATCH_TEST_CASE_TRACKER_HPP_INCLUDED
-
-#include <algorithm>
-#include <string>
-#include <assert.h>
-#include <vector>
-#include <stdexcept>
-
-CATCH_INTERNAL_SUPPRESS_ETD_WARNINGS
-
-namespace Catch {
-namespace TestCaseTracking {
-
- struct NameAndLocation {
- std::string name;
- SourceLineInfo location;
-
- NameAndLocation( std::string const& _name, SourceLineInfo const& _location )
- : name( _name ),
- location( _location )
- {}
- };
-
- struct ITracker : SharedImpl<> {
- virtual ~ITracker();
-
- // static queries
- virtual NameAndLocation const& nameAndLocation() const = 0;
-
- // dynamic queries
- virtual bool isComplete() const = 0; // Successfully completed or failed
- virtual bool isSuccessfullyCompleted() const = 0;
- virtual bool isOpen() const = 0; // Started but not complete
- virtual bool hasChildren() const = 0;
-
- virtual ITracker& parent() = 0;
-
- // actions
- virtual void close() = 0; // Successfully complete
- virtual void fail() = 0;
- virtual void markAsNeedingAnotherRun() = 0;
-
- virtual void addChild( Ptr<ITracker> const& child ) = 0;
- virtual ITracker* findChild( NameAndLocation const& nameAndLocation ) = 0;
- virtual void openChild() = 0;
-
- // Debug/ checking
- virtual bool isSectionTracker() const = 0;
- virtual bool isIndexTracker() const = 0;
- };
-
- class TrackerContext {
-
- enum RunState {
- NotStarted,
- Executing,
- CompletedCycle
- };
-
- Ptr<ITracker> m_rootTracker;
- ITracker* m_currentTracker;
- RunState m_runState;
-
- public:
-
- static TrackerContext& instance() {
- static TrackerContext s_instance;
- return s_instance;
- }
-
- TrackerContext()
- : m_currentTracker( CATCH_NULL ),
- m_runState( NotStarted )
- {}
-
- ITracker& startRun();
-
- void endRun() {
- m_rootTracker.reset();
- m_currentTracker = CATCH_NULL;
- m_runState = NotStarted;
- }
-
- void startCycle() {
- m_currentTracker = m_rootTracker.get();
- m_runState = Executing;
- }
- void completeCycle() {
- m_runState = CompletedCycle;
- }
-
- bool completedCycle() const {
- return m_runState == CompletedCycle;
- }
- ITracker& currentTracker() {
- return *m_currentTracker;
- }
- void setCurrentTracker( ITracker* tracker ) {
- m_currentTracker = tracker;
- }
- };
-
- class TrackerBase : public ITracker {
- protected:
- enum CycleState {
- NotStarted,
- Executing,
- ExecutingChildren,
- NeedsAnotherRun,
- CompletedSuccessfully,
- Failed
- };
- class TrackerHasName {
- NameAndLocation m_nameAndLocation;
- public:
- TrackerHasName( NameAndLocation const& nameAndLocation ) : m_nameAndLocation( nameAndLocation ) {}
- bool operator ()( Ptr<ITracker> const& tracker ) {
- return
- tracker->nameAndLocation().name == m_nameAndLocation.name &&
- tracker->nameAndLocation().location == m_nameAndLocation.location;
- }
- };
- typedef std::vector<Ptr<ITracker> > Children;
- NameAndLocation m_nameAndLocation;
- TrackerContext& m_ctx;
- ITracker* m_parent;
- Children m_children;
- CycleState m_runState;
- public:
- TrackerBase( NameAndLocation const& nameAndLocation, TrackerContext& ctx, ITracker* parent )
- : m_nameAndLocation( nameAndLocation ),
- m_ctx( ctx ),
- m_parent( parent ),
- m_runState( NotStarted )
- {}
- virtual ~TrackerBase();
-
- virtual NameAndLocation const& nameAndLocation() const CATCH_OVERRIDE {
- return m_nameAndLocation;
- }
- virtual bool isComplete() const CATCH_OVERRIDE {
- return m_runState == CompletedSuccessfully || m_runState == Failed;
- }
- virtual bool isSuccessfullyCompleted() const CATCH_OVERRIDE {
- return m_runState == CompletedSuccessfully;
- }
- virtual bool isOpen() const CATCH_OVERRIDE {
- return m_runState != NotStarted && !isComplete();
- }
- virtual bool hasChildren() const CATCH_OVERRIDE {
- return !m_children.empty();
- }
-
- virtual void addChild( Ptr<ITracker> const& child ) CATCH_OVERRIDE {
- m_children.push_back( child );
- }
-
- virtual ITracker* findChild( NameAndLocation const& nameAndLocation ) CATCH_OVERRIDE {
- Children::const_iterator it = std::find_if( m_children.begin(), m_children.end(), TrackerHasName( nameAndLocation ) );
- return( it != m_children.end() )
- ? it->get()
- : CATCH_NULL;
- }
- virtual ITracker& parent() CATCH_OVERRIDE {
- assert( m_parent ); // Should always be non-null except for root
- return *m_parent;
- }
-
- virtual void openChild() CATCH_OVERRIDE {
- if( m_runState != ExecutingChildren ) {
- m_runState = ExecutingChildren;
- if( m_parent )
- m_parent->openChild();
- }
- }
-
- virtual bool isSectionTracker() const CATCH_OVERRIDE { return false; }
- virtual bool isIndexTracker() const CATCH_OVERRIDE { return false; }
-
- void open() {
- m_runState = Executing;
- moveToThis();
- if( m_parent )
- m_parent->openChild();
- }
-
- virtual void close() CATCH_OVERRIDE {
-
- // Close any still open children (e.g. generators)
- while( &m_ctx.currentTracker() != this )
- m_ctx.currentTracker().close();
-
- switch( m_runState ) {
- case NotStarted:
- case CompletedSuccessfully:
- case Failed:
- throw std::logic_error( "Illogical state" );
-
- case NeedsAnotherRun:
- break;;
-
- case Executing:
- m_runState = CompletedSuccessfully;
- break;
- case ExecutingChildren:
- if( m_children.empty() || m_children.back()->isComplete() )
- m_runState = CompletedSuccessfully;
- break;
-
- default:
- throw std::logic_error( "Unexpected state" );
- }
- moveToParent();
- m_ctx.completeCycle();
- }
- virtual void fail() CATCH_OVERRIDE {
- m_runState = Failed;
- if( m_parent )
- m_parent->markAsNeedingAnotherRun();
- moveToParent();
- m_ctx.completeCycle();
- }
- virtual void markAsNeedingAnotherRun() CATCH_OVERRIDE {
- m_runState = NeedsAnotherRun;
- }
- private:
- void moveToParent() {
- assert( m_parent );
- m_ctx.setCurrentTracker( m_parent );
- }
- void moveToThis() {
- m_ctx.setCurrentTracker( this );
- }
- };
-
- class SectionTracker : public TrackerBase {
- std::vector<std::string> m_filters;
- public:
- SectionTracker( NameAndLocation const& nameAndLocation, TrackerContext& ctx, ITracker* parent )
- : TrackerBase( nameAndLocation, ctx, parent )
- {
- if( parent ) {
- while( !parent->isSectionTracker() )
- parent = &parent->parent();
-
- SectionTracker& parentSection = static_cast<SectionTracker&>( *parent );
- addNextFilters( parentSection.m_filters );
- }
- }
- virtual ~SectionTracker();
-
- virtual bool isSectionTracker() const CATCH_OVERRIDE { return true; }
-
- static SectionTracker& acquire( TrackerContext& ctx, NameAndLocation const& nameAndLocation ) {
- SectionTracker* section = CATCH_NULL;
-
- ITracker& currentTracker = ctx.currentTracker();
- if( ITracker* childTracker = currentTracker.findChild( nameAndLocation ) ) {
- assert( childTracker );
- assert( childTracker->isSectionTracker() );
- section = static_cast<SectionTracker*>( childTracker );
- }
- else {
- section = new SectionTracker( nameAndLocation, ctx, ¤tTracker );
- currentTracker.addChild( section );
- }
- if( !ctx.completedCycle() )
- section->tryOpen();
- return *section;
- }
-
- void tryOpen() {
- if( !isComplete() && (m_filters.empty() || m_filters[0].empty() || m_filters[0] == m_nameAndLocation.name ) )
- open();
- }
-
- void addInitialFilters( std::vector<std::string> const& filters ) {
- if( !filters.empty() ) {
- m_filters.push_back(""); // Root - should never be consulted
- m_filters.push_back(""); // Test Case - not a section filter
- m_filters.insert( m_filters.end(), filters.begin(), filters.end() );
- }
- }
- void addNextFilters( std::vector<std::string> const& filters ) {
- if( filters.size() > 1 )
- m_filters.insert( m_filters.end(), ++filters.begin(), filters.end() );
- }
- };
-
- class IndexTracker : public TrackerBase {
- int m_size;
- int m_index;
- public:
- IndexTracker( NameAndLocation const& nameAndLocation, TrackerContext& ctx, ITracker* parent, int size )
- : TrackerBase( nameAndLocation, ctx, parent ),
- m_size( size ),
- m_index( -1 )
- {}
- virtual ~IndexTracker();
-
- virtual bool isIndexTracker() const CATCH_OVERRIDE { return true; }
-
- static IndexTracker& acquire( TrackerContext& ctx, NameAndLocation const& nameAndLocation, int size ) {
- IndexTracker* tracker = CATCH_NULL;
-
- ITracker& currentTracker = ctx.currentTracker();
- if( ITracker* childTracker = currentTracker.findChild( nameAndLocation ) ) {
- assert( childTracker );
- assert( childTracker->isIndexTracker() );
- tracker = static_cast<IndexTracker*>( childTracker );
- }
- else {
- tracker = new IndexTracker( nameAndLocation, ctx, ¤tTracker, size );
- currentTracker.addChild( tracker );
- }
-
- if( !ctx.completedCycle() && !tracker->isComplete() ) {
- if( tracker->m_runState != ExecutingChildren && tracker->m_runState != NeedsAnotherRun )
- tracker->moveNext();
- tracker->open();
- }
-
- return *tracker;
- }
-
- int index() const { return m_index; }
-
- void moveNext() {
- m_index++;
- m_children.clear();
- }
-
- virtual void close() CATCH_OVERRIDE {
- TrackerBase::close();
- if( m_runState == CompletedSuccessfully && m_index < m_size-1 )
- m_runState = Executing;
- }
- };
-
- inline ITracker& TrackerContext::startRun() {
- m_rootTracker = new SectionTracker( NameAndLocation( "{root}", CATCH_INTERNAL_LINEINFO ), *this, CATCH_NULL );
- m_currentTracker = CATCH_NULL;
- m_runState = Executing;
- return *m_rootTracker;
- }
-
-} // namespace TestCaseTracking
-
-using TestCaseTracking::ITracker;
-using TestCaseTracking::TrackerContext;
-using TestCaseTracking::SectionTracker;
-using TestCaseTracking::IndexTracker;
-
-} // namespace Catch
-
-CATCH_INTERNAL_UNSUPPRESS_ETD_WARNINGS
-
-// #included from: catch_fatal_condition.hpp
-#define TWOBLUECUBES_CATCH_FATAL_CONDITION_H_INCLUDED
-
-namespace Catch {
-
- // Report the error condition
- inline void reportFatal( std::string const& message ) {
- IContext& context = Catch::getCurrentContext();
- IResultCapture* resultCapture = context.getResultCapture();
- resultCapture->handleFatalErrorCondition( message );
- }
-
-} // namespace Catch
-
-#if defined ( CATCH_PLATFORM_WINDOWS ) /////////////////////////////////////////
-// #included from: catch_windows_h_proxy.h
-
-#define TWOBLUECUBES_CATCH_WINDOWS_H_PROXY_H_INCLUDED
-
-#ifdef CATCH_DEFINES_NOMINMAX
-# define NOMINMAX
-#endif
-#ifdef CATCH_DEFINES_WIN32_LEAN_AND_MEAN
-# define WIN32_LEAN_AND_MEAN
-#endif
-
-#ifdef __AFXDLL
-#include <AfxWin.h>
-#else
-#include <windows.h>
-#endif
-
-#ifdef CATCH_DEFINES_NOMINMAX
-# undef NOMINMAX
-#endif
-#ifdef CATCH_DEFINES_WIN32_LEAN_AND_MEAN
-# undef WIN32_LEAN_AND_MEAN
-#endif
-
-
-# if !defined ( CATCH_CONFIG_WINDOWS_SEH )
-
-namespace Catch {
- struct FatalConditionHandler {
- void reset() {}
- };
-}
-
-# else // CATCH_CONFIG_WINDOWS_SEH is defined
-
-namespace Catch {
-
- struct SignalDefs { DWORD id; const char* name; };
- extern SignalDefs signalDefs[];
- // There is no 1-1 mapping between signals and windows exceptions.
- // Windows can easily distinguish between SO and SigSegV,
- // but SigInt, SigTerm, etc are handled differently.
- SignalDefs signalDefs[] = {
- { EXCEPTION_ILLEGAL_INSTRUCTION, "SIGILL - Illegal instruction signal" },
- { EXCEPTION_STACK_OVERFLOW, "SIGSEGV - Stack overflow" },
- { EXCEPTION_ACCESS_VIOLATION, "SIGSEGV - Segmentation violation signal" },
- { EXCEPTION_INT_DIVIDE_BY_ZERO, "Divide by zero error" },
- };
-
- struct FatalConditionHandler {
-
- static LONG CALLBACK handleVectoredException(PEXCEPTION_POINTERS ExceptionInfo) {
- for (int i = 0; i < sizeof(signalDefs) / sizeof(SignalDefs); ++i) {
- if (ExceptionInfo->ExceptionRecord->ExceptionCode == signalDefs[i].id) {
- reportFatal(signalDefs[i].name);
- }
- }
- // If its not an exception we care about, pass it along.
- // This stops us from eating debugger breaks etc.
- return EXCEPTION_CONTINUE_SEARCH;
- }
-
- FatalConditionHandler() {
- isSet = true;
- // 32k seems enough for Catch to handle stack overflow,
- // but the value was found experimentally, so there is no strong guarantee
- guaranteeSize = 32 * 1024;
- exceptionHandlerHandle = CATCH_NULL;
- // Register as first handler in current chain
- exceptionHandlerHandle = AddVectoredExceptionHandler(1, handleVectoredException);
- // Pass in guarantee size to be filled
- SetThreadStackGuarantee(&guaranteeSize);
- }
-
- static void reset() {
- if (isSet) {
- // Unregister handler and restore the old guarantee
- RemoveVectoredExceptionHandler(exceptionHandlerHandle);
- SetThreadStackGuarantee(&guaranteeSize);
- exceptionHandlerHandle = CATCH_NULL;
- isSet = false;
- }
- }
-
- ~FatalConditionHandler() {
- reset();
- }
- private:
- static bool isSet;
- static ULONG guaranteeSize;
- static PVOID exceptionHandlerHandle;
- };
-
- bool FatalConditionHandler::isSet = false;
- ULONG FatalConditionHandler::guaranteeSize = 0;
- PVOID FatalConditionHandler::exceptionHandlerHandle = CATCH_NULL;
-
-} // namespace Catch
-
-# endif // CATCH_CONFIG_WINDOWS_SEH
-
-#else // Not Windows - assumed to be POSIX compatible //////////////////////////
-
-# if !defined(CATCH_CONFIG_POSIX_SIGNALS)
-
-namespace Catch {
- struct FatalConditionHandler {
- void reset() {}
- };
-}
-
-# else // CATCH_CONFIG_POSIX_SIGNALS is defined
-
-#include <signal.h>
-
-namespace Catch {
-
- struct SignalDefs {
- int id;
- const char* name;
- };
- extern SignalDefs signalDefs[];
- SignalDefs signalDefs[] = {
- { SIGINT, "SIGINT - Terminal interrupt signal" },
- { SIGILL, "SIGILL - Illegal instruction signal" },
- { SIGFPE, "SIGFPE - Floating point error signal" },
- { SIGSEGV, "SIGSEGV - Segmentation violation signal" },
- { SIGTERM, "SIGTERM - Termination request signal" },
- { SIGABRT, "SIGABRT - Abort (abnormal termination) signal" }
- };
-
- struct FatalConditionHandler {
-
- static bool isSet;
- static struct sigaction oldSigActions [sizeof(signalDefs)/sizeof(SignalDefs)];
- static stack_t oldSigStack;
- static char altStackMem[SIGSTKSZ];
-
- static void handleSignal( int sig ) {
- std::string name = "<unknown signal>";
- for (std::size_t i = 0; i < sizeof(signalDefs) / sizeof(SignalDefs); ++i) {
- SignalDefs &def = signalDefs[i];
- if (sig == def.id) {
- name = def.name;
- break;
- }
- }
- reset();
- reportFatal(name);
- raise( sig );
- }
-
- FatalConditionHandler() {
- isSet = true;
- stack_t sigStack;
- sigStack.ss_sp = altStackMem;
- sigStack.ss_size = SIGSTKSZ;
- sigStack.ss_flags = 0;
- sigaltstack(&sigStack, &oldSigStack);
- struct sigaction sa = { 0 };
-
- sa.sa_handler = handleSignal;
- sa.sa_flags = SA_ONSTACK;
- for (std::size_t i = 0; i < sizeof(signalDefs)/sizeof(SignalDefs); ++i) {
- sigaction(signalDefs[i].id, &sa, &oldSigActions[i]);
- }
- }
-
- ~FatalConditionHandler() {
- reset();
- }
- static void reset() {
- if( isSet ) {
- // Set signals back to previous values -- hopefully nobody overwrote them in the meantime
- for( std::size_t i = 0; i < sizeof(signalDefs)/sizeof(SignalDefs); ++i ) {
- sigaction(signalDefs[i].id, &oldSigActions[i], CATCH_NULL);
- }
- // Return the old stack
- sigaltstack(&oldSigStack, CATCH_NULL);
- isSet = false;
- }
- }
- };
-
- bool FatalConditionHandler::isSet = false;
- struct sigaction FatalConditionHandler::oldSigActions[sizeof(signalDefs)/sizeof(SignalDefs)] = {};
- stack_t FatalConditionHandler::oldSigStack = {};
- char FatalConditionHandler::altStackMem[SIGSTKSZ] = {};
-
-} // namespace Catch
-
-# endif // CATCH_CONFIG_POSIX_SIGNALS
-
-#endif // not Windows
-
-#include <cassert>
-#include <set>
-#include <string>
-
-namespace Catch {
-
- class StreamRedirect {
-
- public:
- StreamRedirect( std::ostream& stream, std::string& targetString )
- : m_stream( stream ),
- m_prevBuf( stream.rdbuf() ),
- m_targetString( targetString )
- {
- stream.rdbuf( m_oss.rdbuf() );
- }
-
- ~StreamRedirect() {
- m_targetString += m_oss.str();
- m_stream.rdbuf( m_prevBuf );
- }
-
- private:
- std::ostream& m_stream;
- std::streambuf* m_prevBuf;
- std::ostringstream m_oss;
- std::string& m_targetString;
- };
-
- // StdErr has two constituent streams in C++, std::cerr and std::clog
- // This means that we need to redirect 2 streams into 1 to keep proper
- // order of writes and cannot use StreamRedirect on its own
- class StdErrRedirect {
- public:
- StdErrRedirect(std::string& targetString)
- :m_cerrBuf( cerr().rdbuf() ), m_clogBuf(clog().rdbuf()),
- m_targetString(targetString){
- cerr().rdbuf(m_oss.rdbuf());
- clog().rdbuf(m_oss.rdbuf());
- }
- ~StdErrRedirect() {
- m_targetString += m_oss.str();
- cerr().rdbuf(m_cerrBuf);
- clog().rdbuf(m_clogBuf);
- }
- private:
- std::streambuf* m_cerrBuf;
- std::streambuf* m_clogBuf;
- std::ostringstream m_oss;
- std::string& m_targetString;
- };
-
- ///////////////////////////////////////////////////////////////////////////
-
- class RunContext : public IResultCapture, public IRunner {
-
- RunContext( RunContext const& );
- void operator =( RunContext const& );
-
- public:
-
- explicit RunContext( Ptr<IConfig const> const& _config, Ptr<IStreamingReporter> const& reporter )
- : m_runInfo( _config->name() ),
- m_context( getCurrentMutableContext() ),
- m_activeTestCase( CATCH_NULL ),
- m_config( _config ),
- m_reporter( reporter ),
- m_shouldReportUnexpected ( true )
- {
- m_context.setRunner( this );
- m_context.setConfig( m_config );
- m_context.setResultCapture( this );
- m_reporter->testRunStarting( m_runInfo );
- }
-
- virtual ~RunContext() {
- m_reporter->testRunEnded( TestRunStats( m_runInfo, m_totals, aborting() ) );
- }
-
- void testGroupStarting( std::string const& testSpec, std::size_t groupIndex, std::size_t groupsCount ) {
- m_reporter->testGroupStarting( GroupInfo( testSpec, groupIndex, groupsCount ) );
- }
- void testGroupEnded( std::string const& testSpec, Totals const& totals, std::size_t groupIndex, std::size_t groupsCount ) {
- m_reporter->testGroupEnded( TestGroupStats( GroupInfo( testSpec, groupIndex, groupsCount ), totals, aborting() ) );
- }
-
- Totals runTest( TestCase const& testCase ) {
- Totals prevTotals = m_totals;
-
- std::string redirectedCout;
- std::string redirectedCerr;
-
- TestCaseInfo testInfo = testCase.getTestCaseInfo();
-
- m_reporter->testCaseStarting( testInfo );
-
- m_activeTestCase = &testCase;
-
- do {
- ITracker& rootTracker = m_trackerContext.startRun();
- assert( rootTracker.isSectionTracker() );
- static_cast<SectionTracker&>( rootTracker ).addInitialFilters( m_config->getSectionsToRun() );
- do {
- m_trackerContext.startCycle();
- m_testCaseTracker = &SectionTracker::acquire( m_trackerContext, TestCaseTracking::NameAndLocation( testInfo.name, testInfo.lineInfo ) );
- runCurrentTest( redirectedCout, redirectedCerr );
- }
- while( !m_testCaseTracker->isSuccessfullyCompleted() && !aborting() );
- }
- // !TBD: deprecated - this will be replaced by indexed trackers
- while( getCurrentContext().advanceGeneratorsForCurrentTest() && !aborting() );
-
- Totals deltaTotals = m_totals.delta( prevTotals );
- if( testInfo.expectedToFail() && deltaTotals.testCases.passed > 0 ) {
- deltaTotals.assertions.failed++;
- deltaTotals.testCases.passed--;
- deltaTotals.testCases.failed++;
- }
- m_totals.testCases += deltaTotals.testCases;
- m_reporter->testCaseEnded( TestCaseStats( testInfo,
- deltaTotals,
- redirectedCout,
- redirectedCerr,
- aborting() ) );
-
- m_activeTestCase = CATCH_NULL;
- m_testCaseTracker = CATCH_NULL;
-
- return deltaTotals;
- }
-
- Ptr<IConfig const> config() const {
- return m_config;
- }
-
- private: // IResultCapture
-
- virtual void assertionEnded( AssertionResult const& result ) {
- if( result.getResultType() == ResultWas::Ok ) {
- m_totals.assertions.passed++;
- }
- else if( !result.isOk() ) {
- if( m_activeTestCase->getTestCaseInfo().okToFail() )
- m_totals.assertions.failedButOk++;
- else
- m_totals.assertions.failed++;
- }
-
- // We have no use for the return value (whether messages should be cleared), because messages were made scoped
- // and should be let to clear themselves out.
- static_cast<void>(m_reporter->assertionEnded(AssertionStats(result, m_messages, m_totals)));
-
- // Reset working state
- m_lastAssertionInfo = AssertionInfo( "", m_lastAssertionInfo.lineInfo, "{Unknown expression after the reported line}" , m_lastAssertionInfo.resultDisposition );
- m_lastResult = result;
- }
-
- virtual bool lastAssertionPassed()
- {
- return m_totals.assertions.passed == (m_prevPassed + 1);
- }
-
- virtual void assertionPassed()
- {
- m_totals.assertions.passed++;
- m_lastAssertionInfo.capturedExpression = "{Unknown expression after the reported line}";
- m_lastAssertionInfo.macroName = "";
- }
-
- virtual void assertionRun()
- {
- m_prevPassed = m_totals.assertions.passed;
- }
-
- virtual bool sectionStarted (
- SectionInfo const& sectionInfo,
- Counts& assertions
- )
- {
- ITracker& sectionTracker = SectionTracker::acquire( m_trackerContext, TestCaseTracking::NameAndLocation( sectionInfo.name, sectionInfo.lineInfo ) );
- if( !sectionTracker.isOpen() )
- return false;
- m_activeSections.push_back( §ionTracker );
-
- m_lastAssertionInfo.lineInfo = sectionInfo.lineInfo;
-
- m_reporter->sectionStarting( sectionInfo );
-
- assertions = m_totals.assertions;
-
- return true;
- }
- bool testForMissingAssertions( Counts& assertions ) {
- if( assertions.total() != 0 )
- return false;
- if( !m_config->warnAboutMissingAssertions() )
- return false;
- if( m_trackerContext.currentTracker().hasChildren() )
- return false;
- m_totals.assertions.failed++;
- assertions.failed++;
- return true;
- }
-
- virtual void sectionEnded( SectionEndInfo const& endInfo ) {
- Counts assertions = m_totals.assertions - endInfo.prevAssertions;
- bool missingAssertions = testForMissingAssertions( assertions );
-
- if( !m_activeSections.empty() ) {
- m_activeSections.back()->close();
- m_activeSections.pop_back();
- }
-
- m_reporter->sectionEnded( SectionStats( endInfo.sectionInfo, assertions, endInfo.durationInSeconds, missingAssertions ) );
- m_messages.clear();
- }
-
- virtual void sectionEndedEarly( SectionEndInfo const& endInfo ) {
- if( m_unfinishedSections.empty() )
- m_activeSections.back()->fail();
- else
- m_activeSections.back()->close();
- m_activeSections.pop_back();
-
- m_unfinishedSections.push_back( endInfo );
- }
-
- virtual void pushScopedMessage( MessageInfo const& message ) {
- m_messages.push_back( message );
- }
-
- virtual void popScopedMessage( MessageInfo const& message ) {
- m_messages.erase( std::remove( m_messages.begin(), m_messages.end(), message ), m_messages.end() );
- }
-
- virtual std::string getCurrentTestName() const {
- return m_activeTestCase
- ? m_activeTestCase->getTestCaseInfo().name
- : std::string();
- }
-
- virtual const AssertionResult* getLastResult() const {
- return &m_lastResult;
- }
-
- virtual void exceptionEarlyReported() {
- m_shouldReportUnexpected = false;
- }
-
- virtual void handleFatalErrorCondition( std::string const& message ) {
- // Don't rebuild the result -- the stringification itself can cause more fatal errors
- // Instead, fake a result data.
- AssertionResultData tempResult;
- tempResult.resultType = ResultWas::FatalErrorCondition;
- tempResult.message = message;
- AssertionResult result(m_lastAssertionInfo, tempResult);
-
- getResultCapture().assertionEnded(result);
-
- handleUnfinishedSections();
-
- // Recreate section for test case (as we will lose the one that was in scope)
- TestCaseInfo const& testCaseInfo = m_activeTestCase->getTestCaseInfo();
- SectionInfo testCaseSection( testCaseInfo.lineInfo, testCaseInfo.name, testCaseInfo.description );
-
- Counts assertions;
- assertions.failed = 1;
- SectionStats testCaseSectionStats( testCaseSection, assertions, 0, false );
- m_reporter->sectionEnded( testCaseSectionStats );
-
- TestCaseInfo testInfo = m_activeTestCase->getTestCaseInfo();
-
- Totals deltaTotals;
- deltaTotals.testCases.failed = 1;
- deltaTotals.assertions.failed = 1;
- m_reporter->testCaseEnded( TestCaseStats( testInfo,
- deltaTotals,
- std::string(),
- std::string(),
- false ) );
- m_totals.testCases.failed++;
- testGroupEnded( std::string(), m_totals, 1, 1 );
- m_reporter->testRunEnded( TestRunStats( m_runInfo, m_totals, false ) );
- }
-
- public:
- // !TBD We need to do this another way!
- bool aborting() const {
- return m_totals.assertions.failed == static_cast<std::size_t>( m_config->abortAfter() );
- }
-
- private:
-
- void runCurrentTest( std::string& redirectedCout, std::string& redirectedCerr ) {
- TestCaseInfo const& testCaseInfo = m_activeTestCase->getTestCaseInfo();
- SectionInfo testCaseSection( testCaseInfo.lineInfo, testCaseInfo.name, testCaseInfo.description );
- m_reporter->sectionStarting( testCaseSection );
- Counts prevAssertions = m_totals.assertions;
- double duration = 0;
- m_shouldReportUnexpected = true;
- try {
- m_lastAssertionInfo = AssertionInfo( "TEST_CASE", testCaseInfo.lineInfo, "", ResultDisposition::Normal );
-
- seedRng( *m_config );
-
- Timer timer;
- timer.start();
- if( m_reporter->getPreferences().shouldRedirectStdOut ) {
- StreamRedirect coutRedir( Catch::cout(), redirectedCout );
- StdErrRedirect errRedir( redirectedCerr );
- invokeActiveTestCase();
- }
- else {
- invokeActiveTestCase();
- }
- duration = timer.getElapsedSeconds();
- }
- catch( TestFailureException& ) {
- // This just means the test was aborted due to failure
- }
- catch(...) {
- // Under CATCH_CONFIG_FAST_COMPILE, unexpected exceptions under REQUIRE assertions
- // are reported without translation at the point of origin.
- if (m_shouldReportUnexpected) {
- makeUnexpectedResultBuilder().useActiveException();
- }
- }
- m_testCaseTracker->close();
- handleUnfinishedSections();
- m_messages.clear();
-
- Counts assertions = m_totals.assertions - prevAssertions;
- bool missingAssertions = testForMissingAssertions( assertions );
-
- SectionStats testCaseSectionStats( testCaseSection, assertions, duration, missingAssertions );
- m_reporter->sectionEnded( testCaseSectionStats );
- }
-
- void invokeActiveTestCase() {
- FatalConditionHandler fatalConditionHandler; // Handle signals
- m_activeTestCase->invoke();
- fatalConditionHandler.reset();
- }
-
- private:
-
- ResultBuilder makeUnexpectedResultBuilder() const {
- return ResultBuilder( m_lastAssertionInfo.macroName,
- m_lastAssertionInfo.lineInfo,
- m_lastAssertionInfo.capturedExpression,
- m_lastAssertionInfo.resultDisposition );
- }
-
- void handleUnfinishedSections() {
- // If sections ended prematurely due to an exception we stored their
- // infos here so we can tear them down outside the unwind process.
- for( std::vector<SectionEndInfo>::const_reverse_iterator it = m_unfinishedSections.rbegin(),
- itEnd = m_unfinishedSections.rend();
- it != itEnd;
- ++it )
- sectionEnded( *it );
- m_unfinishedSections.clear();
- }
-
- TestRunInfo m_runInfo;
- IMutableContext& m_context;
- TestCase const* m_activeTestCase;
- ITracker* m_testCaseTracker;
- ITracker* m_currentSectionTracker;
- AssertionResult m_lastResult;
-
- Ptr<IConfig const> m_config;
- Totals m_totals;
- Ptr<IStreamingReporter> m_reporter;
- std::vector<MessageInfo> m_messages;
- AssertionInfo m_lastAssertionInfo;
- std::vector<SectionEndInfo> m_unfinishedSections;
- std::vector<ITracker*> m_activeSections;
- TrackerContext m_trackerContext;
- size_t m_prevPassed;
- bool m_shouldReportUnexpected;
- };
-
- IResultCapture& getResultCapture() {
- if( IResultCapture* capture = getCurrentContext().getResultCapture() )
- return *capture;
- else
- throw std::logic_error( "No result capture instance" );
- }
-
-} // end namespace Catch
-
-// #included from: internal/catch_version.h
-#define TWOBLUECUBES_CATCH_VERSION_H_INCLUDED
-
-namespace Catch {
-
- // Versioning information
- struct Version {
- Version( unsigned int _majorVersion,
- unsigned int _minorVersion,
- unsigned int _patchNumber,
- char const * const _branchName,
- unsigned int _buildNumber );
-
- unsigned int const majorVersion;
- unsigned int const minorVersion;
- unsigned int const patchNumber;
-
- // buildNumber is only used if branchName is not null
- char const * const branchName;
- unsigned int const buildNumber;
-
- friend std::ostream& operator << ( std::ostream& os, Version const& version );
-
- private:
- void operator=( Version const& );
- };
-
- inline Version libraryVersion();
-}
-
-#include <fstream>
-#include <stdlib.h>
-#include <limits>
-
-namespace Catch {
-
- Ptr<IStreamingReporter> createReporter( std::string const& reporterName, Ptr<Config> const& config ) {
- Ptr<IStreamingReporter> reporter = getRegistryHub().getReporterRegistry().create( reporterName, config.get() );
- if( !reporter ) {
- std::ostringstream oss;
- oss << "No reporter registered with name: '" << reporterName << "'";
- throw std::domain_error( oss.str() );
- }
- return reporter;
- }
-
-#if !defined(CATCH_CONFIG_DEFAULT_REPORTER)
-#define CATCH_CONFIG_DEFAULT_REPORTER "console"
-#endif
-
- Ptr<IStreamingReporter> makeReporter( Ptr<Config> const& config ) {
- std::vector<std::string> reporters = config->getReporterNames();
- if( reporters.empty() )
- reporters.push_back( CATCH_CONFIG_DEFAULT_REPORTER );
-
- Ptr<IStreamingReporter> reporter;
- for( std::vector<std::string>::const_iterator it = reporters.begin(), itEnd = reporters.end();
- it != itEnd;
- ++it )
- reporter = addReporter( reporter, createReporter( *it, config ) );
- return reporter;
- }
- Ptr<IStreamingReporter> addListeners( Ptr<IConfig const> const& config, Ptr<IStreamingReporter> reporters ) {
- IReporterRegistry::Listeners listeners = getRegistryHub().getReporterRegistry().getListeners();
- for( IReporterRegistry::Listeners::const_iterator it = listeners.begin(), itEnd = listeners.end();
- it != itEnd;
- ++it )
- reporters = addReporter(reporters, (*it)->create( ReporterConfig( config ) ) );
- return reporters;
- }
-
- Totals runTests( Ptr<Config> const& config ) {
-
- Ptr<IConfig const> iconfig = config.get();
-
- Ptr<IStreamingReporter> reporter = makeReporter( config );
- reporter = addListeners( iconfig, reporter );
-
- RunContext context( iconfig, reporter );
-
- Totals totals;
-
- context.testGroupStarting( config->name(), 1, 1 );
-
- TestSpec testSpec = config->testSpec();
- if( !testSpec.hasFilters() )
- testSpec = TestSpecParser( ITagAliasRegistry::get() ).parse( "~[.]" ).testSpec(); // All not hidden tests
-
- std::vector<TestCase> const& allTestCases = getAllTestCasesSorted( *iconfig );
- for( std::vector<TestCase>::const_iterator it = allTestCases.begin(), itEnd = allTestCases.end();
- it != itEnd;
- ++it ) {
- if( !context.aborting() && matchTest( *it, testSpec, *iconfig ) )
- totals += context.runTest( *it );
- else
- reporter->skipTest( *it );
- }
-
- context.testGroupEnded( iconfig->name(), totals, 1, 1 );
- return totals;
- }
-
- void applyFilenamesAsTags( IConfig const& config ) {
- std::vector<TestCase> const& tests = getAllTestCasesSorted( config );
- for(std::size_t i = 0; i < tests.size(); ++i ) {
- TestCase& test = const_cast<TestCase&>( tests[i] );
- std::set<std::string> tags = test.tags;
-
- std::string filename = test.lineInfo.file;
- std::string::size_type lastSlash = filename.find_last_of( "\\/" );
- if( lastSlash != std::string::npos )
- filename = filename.substr( lastSlash+1 );
-
- std::string::size_type lastDot = filename.find_last_of( '.' );
- if( lastDot != std::string::npos )
- filename = filename.substr( 0, lastDot );
-
- tags.insert( '#' + filename );
- setTags( test, tags );
- }
- }
-
- class Session : NonCopyable {
- static bool alreadyInstantiated;
-
- public:
-
- struct OnUnusedOptions { enum DoWhat { Ignore, Fail }; };
-
- Session()
- : m_cli( makeCommandLineParser() ) {
- if( alreadyInstantiated ) {
- std::string msg = "Only one instance of Catch::Session can ever be used";
- Catch::cerr() << msg << std::endl;
- throw std::logic_error( msg );
- }
- alreadyInstantiated = true;
- }
- ~Session() {
- Catch::cleanUp();
- }
-
- void showHelp( std::string const& processName ) {
- Catch::cout() << "\nCatch v" << libraryVersion() << "\n";
-
- m_cli.usage( Catch::cout(), processName );
- Catch::cout() << "For more detail usage please see the project docs\n" << std::endl;
- }
- void libIdentify() {
- Catch::cout()
- << std::left << std::setw(16) << "description: " << "A Catch test executable\n"
- << std::left << std::setw(16) << "category: " << "testframework\n"
- << std::left << std::setw(16) << "framework: " << "Catch Test\n"
- << std::left << std::setw(16) << "version: " << libraryVersion() << std::endl;
- }
-
- int applyCommandLine( int argc, char const* const* const argv, OnUnusedOptions::DoWhat unusedOptionBehaviour = OnUnusedOptions::Fail ) {
- try {
- m_cli.setThrowOnUnrecognisedTokens( unusedOptionBehaviour == OnUnusedOptions::Fail );
- m_unusedTokens = m_cli.parseInto( Clara::argsToVector( argc, argv ), m_configData );
- if( m_configData.showHelp )
- showHelp( m_configData.processName );
- if( m_configData.libIdentify )
- libIdentify();
- m_config.reset();
- }
- catch( std::exception& ex ) {
- {
- Colour colourGuard( Colour::Red );
- Catch::cerr()
- << "\nError(s) in input:\n"
- << Text( ex.what(), TextAttributes().setIndent(2) )
- << "\n\n";
- }
- m_cli.usage( Catch::cout(), m_configData.processName );
- return (std::numeric_limits<int>::max)();
- }
- return 0;
- }
-
- void useConfigData( ConfigData const& _configData ) {
- m_configData = _configData;
- m_config.reset();
- }
-
- int run( int argc, char const* const* const argv ) {
-
- int returnCode = applyCommandLine( argc, argv );
- if( returnCode == 0 )
- returnCode = run();
- return returnCode;
- }
-
- #if defined(WIN32) && defined(UNICODE)
- int run( int argc, wchar_t const* const* const argv ) {
-
- char **utf8Argv = new char *[ argc ];
-
- for ( int i = 0; i < argc; ++i ) {
- int bufSize = WideCharToMultiByte( CP_UTF8, 0, argv[i], -1, NULL, 0, NULL, NULL );
-
- utf8Argv[ i ] = new char[ bufSize ];
-
- WideCharToMultiByte( CP_UTF8, 0, argv[i], -1, utf8Argv[i], bufSize, NULL, NULL );
- }
-
- int returnCode = applyCommandLine( argc, utf8Argv );
- if( returnCode == 0 )
- returnCode = run();
-
- for ( int i = 0; i < argc; ++i )
- delete [] utf8Argv[ i ];
-
- delete [] utf8Argv;
-
- return returnCode;
- }
- #endif
-
- int run() {
- if( ( m_configData.waitForKeypress & WaitForKeypress::BeforeStart ) != 0 ) {
- Catch::cout() << "...waiting for enter/ return before starting" << std::endl;
- static_cast<void>(std::getchar());
- }
- int exitCode = runInternal();
- if( ( m_configData.waitForKeypress & WaitForKeypress::BeforeExit ) != 0 ) {
- Catch::cout() << "...waiting for enter/ return before exiting, with code: " << exitCode << std::endl;
- static_cast<void>(std::getchar());
- }
- return exitCode;
- }
-
- Clara::CommandLine<ConfigData> const& cli() const {
- return m_cli;
- }
- std::vector<Clara::Parser::Token> const& unusedTokens() const {
- return m_unusedTokens;
- }
- ConfigData& configData() {
- return m_configData;
- }
- Config& config() {
- if( !m_config )
- m_config = new Config( m_configData );
- return *m_config;
- }
- private:
-
- int runInternal() {
- if( m_configData.showHelp || m_configData.libIdentify )
- return 0;
-
- try
- {
- config(); // Force config to be constructed
-
- seedRng( *m_config );
-
- if( m_configData.filenamesAsTags )
- applyFilenamesAsTags( *m_config );
-
- // Handle list request
- if( Option<std::size_t> listed = list( config() ) )
- return static_cast<int>( *listed );
-
- return static_cast<int>( runTests( m_config ).assertions.failed );
- }
- catch( std::exception& ex ) {
- Catch::cerr() << ex.what() << std::endl;
- return (std::numeric_limits<int>::max)();
- }
- }
-
- Clara::CommandLine<ConfigData> m_cli;
- std::vector<Clara::Parser::Token> m_unusedTokens;
- ConfigData m_configData;
- Ptr<Config> m_config;
- };
-
- bool Session::alreadyInstantiated = false;
-
-} // end namespace Catch
-
-// #included from: catch_registry_hub.hpp
-#define TWOBLUECUBES_CATCH_REGISTRY_HUB_HPP_INCLUDED
-
-// #included from: catch_test_case_registry_impl.hpp
-#define TWOBLUECUBES_CATCH_TEST_CASE_REGISTRY_IMPL_HPP_INCLUDED
-
-#include <vector>
-#include <set>
-#include <sstream>
-#include <algorithm>
-
-namespace Catch {
-
- struct RandomNumberGenerator {
- typedef unsigned int result_type;
-
- result_type operator()( result_type n ) const { return std::rand() % n; }
-
-#ifdef CATCH_CONFIG_CPP11_SHUFFLE
- static constexpr result_type (min)() { return 0; }
- static constexpr result_type (max)() { return 1000000; }
- result_type operator()() const { return std::rand() % (max)(); }
-#endif
- template<typename V>
- static void shuffle( V& vector ) {
- RandomNumberGenerator rng;
-#ifdef CATCH_CONFIG_CPP11_SHUFFLE
- std::shuffle( vector.begin(), vector.end(), rng );
-#else
- std::random_shuffle( vector.begin(), vector.end(), rng );
-#endif
- }
- };
-
- inline std::vector<TestCase> sortTests( IConfig const& config, std::vector<TestCase> const& unsortedTestCases ) {
-
- std::vector<TestCase> sorted = unsortedTestCases;
-
- switch( config.runOrder() ) {
- case RunTests::InLexicographicalOrder:
- std::sort( sorted.begin(), sorted.end() );
- break;
- case RunTests::InRandomOrder:
- {
- seedRng( config );
- RandomNumberGenerator::shuffle( sorted );
- }
- break;
- case RunTests::InDeclarationOrder:
- // already in declaration order
- break;
- }
- return sorted;
- }
- bool matchTest( TestCase const& testCase, TestSpec const& testSpec, IConfig const& config ) {
- return testSpec.matches( testCase ) && ( config.allowThrows() || !testCase.throws() );
- }
-
- void enforceNoDuplicateTestCases( std::vector<TestCase> const& functions ) {
- std::set<TestCase> seenFunctions;
- for( std::vector<TestCase>::const_iterator it = functions.begin(), itEnd = functions.end();
- it != itEnd;
- ++it ) {
- std::pair<std::set<TestCase>::const_iterator, bool> prev = seenFunctions.insert( *it );
- if( !prev.second ) {
- std::ostringstream ss;
-
- ss << Colour( Colour::Red )
- << "error: TEST_CASE( \"" << it->name << "\" ) already defined.\n"
- << "\tFirst seen at " << prev.first->getTestCaseInfo().lineInfo << '\n'
- << "\tRedefined at " << it->getTestCaseInfo().lineInfo << std::endl;
-
- throw std::runtime_error(ss.str());
- }
- }
- }
-
- std::vector<TestCase> filterTests( std::vector<TestCase> const& testCases, TestSpec const& testSpec, IConfig const& config ) {
- std::vector<TestCase> filtered;
- filtered.reserve( testCases.size() );
- for( std::vector<TestCase>::const_iterator it = testCases.begin(), itEnd = testCases.end();
- it != itEnd;
- ++it )
- if( matchTest( *it, testSpec, config ) )
- filtered.push_back( *it );
- return filtered;
- }
- std::vector<TestCase> const& getAllTestCasesSorted( IConfig const& config ) {
- return getRegistryHub().getTestCaseRegistry().getAllTestsSorted( config );
- }
-
- class TestRegistry : public ITestCaseRegistry {
- public:
- TestRegistry()
- : m_currentSortOrder( RunTests::InDeclarationOrder ),
- m_unnamedCount( 0 )
- {}
- virtual ~TestRegistry();
-
- virtual void registerTest( TestCase const& testCase ) {
- std::string name = testCase.getTestCaseInfo().name;
- if( name.empty() ) {
- std::ostringstream oss;
- oss << "Anonymous test case " << ++m_unnamedCount;
- return registerTest( testCase.withName( oss.str() ) );
- }
- m_functions.push_back( testCase );
- }
-
- virtual std::vector<TestCase> const& getAllTests() const {
- return m_functions;
- }
- virtual std::vector<TestCase> const& getAllTestsSorted( IConfig const& config ) const {
- if( m_sortedFunctions.empty() )
- enforceNoDuplicateTestCases( m_functions );
-
- if( m_currentSortOrder != config.runOrder() || m_sortedFunctions.empty() ) {
- m_sortedFunctions = sortTests( config, m_functions );
- m_currentSortOrder = config.runOrder();
- }
- return m_sortedFunctions;
- }
-
- private:
- std::vector<TestCase> m_functions;
- mutable RunTests::InWhatOrder m_currentSortOrder;
- mutable std::vector<TestCase> m_sortedFunctions;
- size_t m_unnamedCount;
- std::ios_base::Init m_ostreamInit; // Forces cout/ cerr to be initialised
- };
-
- ///////////////////////////////////////////////////////////////////////////
-
- class FreeFunctionTestCase : public SharedImpl<ITestCase> {
- public:
-
- FreeFunctionTestCase( TestFunction fun ) : m_fun( fun ) {}
-
- virtual void invoke() const {
- m_fun();
- }
-
- private:
- virtual ~FreeFunctionTestCase();
-
- TestFunction m_fun;
- };
-
- inline std::string extractClassName( std::string const& classOrQualifiedMethodName ) {
- std::string className = classOrQualifiedMethodName;
- if( startsWith( className, '&' ) )
- {
- std::size_t lastColons = className.rfind( "::" );
- std::size_t penultimateColons = className.rfind( "::", lastColons-1 );
- if( penultimateColons == std::string::npos )
- penultimateColons = 1;
- className = className.substr( penultimateColons, lastColons-penultimateColons );
- }
- return className;
- }
-
- void registerTestCase
- ( ITestCase* testCase,
- char const* classOrQualifiedMethodName,
- NameAndDesc const& nameAndDesc,
- SourceLineInfo const& lineInfo ) {
-
- getMutableRegistryHub().registerTest
- ( makeTestCase
- ( testCase,
- extractClassName( classOrQualifiedMethodName ),
- nameAndDesc.name,
- nameAndDesc.description,
- lineInfo ) );
- }
- void registerTestCaseFunction
- ( TestFunction function,
- SourceLineInfo const& lineInfo,
- NameAndDesc const& nameAndDesc ) {
- registerTestCase( new FreeFunctionTestCase( function ), "", nameAndDesc, lineInfo );
- }
-
- ///////////////////////////////////////////////////////////////////////////
-
- AutoReg::AutoReg
- ( TestFunction function,
- SourceLineInfo const& lineInfo,
- NameAndDesc const& nameAndDesc ) {
- registerTestCaseFunction( function, lineInfo, nameAndDesc );
- }
-
- AutoReg::~AutoReg() {}
-
-} // end namespace Catch
-
-// #included from: catch_reporter_registry.hpp
-#define TWOBLUECUBES_CATCH_REPORTER_REGISTRY_HPP_INCLUDED
-
-#include <map>
-
-namespace Catch {
-
- class ReporterRegistry : public IReporterRegistry {
-
- public:
-
- virtual ~ReporterRegistry() CATCH_OVERRIDE {}
-
- virtual IStreamingReporter* create( std::string const& name, Ptr<IConfig const> const& config ) const CATCH_OVERRIDE {
- FactoryMap::const_iterator it = m_factories.find( name );
- if( it == m_factories.end() )
- return CATCH_NULL;
- return it->second->create( ReporterConfig( config ) );
- }
-
- void registerReporter( std::string const& name, Ptr<IReporterFactory> const& factory ) {
- m_factories.insert( std::make_pair( name, factory ) );
- }
- void registerListener( Ptr<IReporterFactory> const& factory ) {
- m_listeners.push_back( factory );
- }
-
- virtual FactoryMap const& getFactories() const CATCH_OVERRIDE {
- return m_factories;
- }
- virtual Listeners const& getListeners() const CATCH_OVERRIDE {
- return m_listeners;
- }
-
- private:
- FactoryMap m_factories;
- Listeners m_listeners;
- };
-}
-
-// #included from: catch_exception_translator_registry.hpp
-#define TWOBLUECUBES_CATCH_EXCEPTION_TRANSLATOR_REGISTRY_HPP_INCLUDED
-
-#ifdef __OBJC__
-#import "Foundation/Foundation.h"
-#endif
-
-namespace Catch {
-
- class ExceptionTranslatorRegistry : public IExceptionTranslatorRegistry {
- public:
- ~ExceptionTranslatorRegistry() {
- deleteAll( m_translators );
- }
-
- virtual void registerTranslator( const IExceptionTranslator* translator ) {
- m_translators.push_back( translator );
- }
-
- virtual std::string translateActiveException() const {
- try {
-#ifdef __OBJC__
- // In Objective-C try objective-c exceptions first
- @try {
- return tryTranslators();
- }
- @catch (NSException *exception) {
- return Catch::toString( [exception description] );
- }
-#else
- return tryTranslators();
-#endif
- }
- catch( TestFailureException& ) {
- throw;
- }
- catch( std::exception& ex ) {
- return ex.what();
- }
- catch( std::string& msg ) {
- return msg;
- }
- catch( const char* msg ) {
- return msg;
- }
- catch(...) {
- return "Unknown exception";
- }
- }
-
- std::string tryTranslators() const {
- if( m_translators.empty() )
- throw;
- else
- return m_translators[0]->translate( m_translators.begin()+1, m_translators.end() );
- }
-
- private:
- std::vector<const IExceptionTranslator*> m_translators;
- };
-}
-
-// #included from: catch_tag_alias_registry.h
-#define TWOBLUECUBES_CATCH_TAG_ALIAS_REGISTRY_H_INCLUDED
-
-#include <map>
-
-namespace Catch {
-
- class TagAliasRegistry : public ITagAliasRegistry {
- public:
- virtual ~TagAliasRegistry();
- virtual Option<TagAlias> find( std::string const& alias ) const;
- virtual std::string expandAliases( std::string const& unexpandedTestSpec ) const;
- void add( std::string const& alias, std::string const& tag, SourceLineInfo const& lineInfo );
-
- private:
- std::map<std::string, TagAlias> m_registry;
- };
-
-} // end namespace Catch
-
-namespace Catch {
-
- namespace {
-
- class RegistryHub : public IRegistryHub, public IMutableRegistryHub {
-
- RegistryHub( RegistryHub const& );
- void operator=( RegistryHub const& );
-
- public: // IRegistryHub
- RegistryHub() {
- }
- virtual IReporterRegistry const& getReporterRegistry() const CATCH_OVERRIDE {
- return m_reporterRegistry;
- }
- virtual ITestCaseRegistry const& getTestCaseRegistry() const CATCH_OVERRIDE {
- return m_testCaseRegistry;
- }
- virtual IExceptionTranslatorRegistry& getExceptionTranslatorRegistry() CATCH_OVERRIDE {
- return m_exceptionTranslatorRegistry;
- }
- virtual ITagAliasRegistry const& getTagAliasRegistry() const CATCH_OVERRIDE {
- return m_tagAliasRegistry;
- }
-
- public: // IMutableRegistryHub
- virtual void registerReporter( std::string const& name, Ptr<IReporterFactory> const& factory ) CATCH_OVERRIDE {
- m_reporterRegistry.registerReporter( name, factory );
- }
- virtual void registerListener( Ptr<IReporterFactory> const& factory ) CATCH_OVERRIDE {
- m_reporterRegistry.registerListener( factory );
- }
- virtual void registerTest( TestCase const& testInfo ) CATCH_OVERRIDE {
- m_testCaseRegistry.registerTest( testInfo );
- }
- virtual void registerTranslator( const IExceptionTranslator* translator ) CATCH_OVERRIDE {
- m_exceptionTranslatorRegistry.registerTranslator( translator );
- }
- virtual void registerTagAlias( std::string const& alias, std::string const& tag, SourceLineInfo const& lineInfo ) CATCH_OVERRIDE {
- m_tagAliasRegistry.add( alias, tag, lineInfo );
- }
-
- private:
- TestRegistry m_testCaseRegistry;
- ReporterRegistry m_reporterRegistry;
- ExceptionTranslatorRegistry m_exceptionTranslatorRegistry;
- TagAliasRegistry m_tagAliasRegistry;
- };
-
- // Single, global, instance
- inline RegistryHub*& getTheRegistryHub() {
- static RegistryHub* theRegistryHub = CATCH_NULL;
- if( !theRegistryHub )
- theRegistryHub = new RegistryHub();
- return theRegistryHub;
- }
- }
-
- IRegistryHub& getRegistryHub() {
- return *getTheRegistryHub();
- }
- IMutableRegistryHub& getMutableRegistryHub() {
- return *getTheRegistryHub();
- }
- void cleanUp() {
- delete getTheRegistryHub();
- getTheRegistryHub() = CATCH_NULL;
- cleanUpContext();
- }
- std::string translateActiveException() {
- return getRegistryHub().getExceptionTranslatorRegistry().translateActiveException();
- }
-
-} // end namespace Catch
-
-// #included from: catch_notimplemented_exception.hpp
-#define TWOBLUECUBES_CATCH_NOTIMPLEMENTED_EXCEPTION_HPP_INCLUDED
-
-#include <sstream>
-
-namespace Catch {
-
- NotImplementedException::NotImplementedException( SourceLineInfo const& lineInfo )
- : m_lineInfo( lineInfo ) {
- std::ostringstream oss;
- oss << lineInfo << ": function ";
- oss << "not implemented";
- m_what = oss.str();
- }
-
- const char* NotImplementedException::what() const CATCH_NOEXCEPT {
- return m_what.c_str();
- }
-
-} // end namespace Catch
-
-// #included from: catch_context_impl.hpp
-#define TWOBLUECUBES_CATCH_CONTEXT_IMPL_HPP_INCLUDED
-
-// #included from: catch_stream.hpp
-#define TWOBLUECUBES_CATCH_STREAM_HPP_INCLUDED
-
-#include <stdexcept>
-#include <cstdio>
-#include <iostream>
-
-namespace Catch {
-
- template<typename WriterF, size_t bufferSize=256>
- class StreamBufImpl : public StreamBufBase {
- char data[bufferSize];
- WriterF m_writer;
-
- public:
- StreamBufImpl() {
- setp( data, data + sizeof(data) );
- }
-
- ~StreamBufImpl() CATCH_NOEXCEPT {
- sync();
- }
-
- private:
- int overflow( int c ) {
- sync();
-
- if( c != EOF ) {
- if( pbase() == epptr() )
- m_writer( std::string( 1, static_cast<char>( c ) ) );
- else
- sputc( static_cast<char>( c ) );
- }
- return 0;
- }
-
- int sync() {
- if( pbase() != pptr() ) {
- m_writer( std::string( pbase(), static_cast<std::string::size_type>( pptr() - pbase() ) ) );
- setp( pbase(), epptr() );
- }
- return 0;
- }
- };
-
- ///////////////////////////////////////////////////////////////////////////
-
- FileStream::FileStream( std::string const& filename ) {
- m_ofs.open( filename.c_str() );
- if( m_ofs.fail() ) {
- std::ostringstream oss;
- oss << "Unable to open file: '" << filename << '\'';
- throw std::domain_error( oss.str() );
- }
- }
-
- std::ostream& FileStream::stream() const {
- return m_ofs;
- }
-
- struct OutputDebugWriter {
-
- void operator()( std::string const&str ) {
- writeToDebugConsole( str );
- }
- };
-
- DebugOutStream::DebugOutStream()
- : m_streamBuf( new StreamBufImpl<OutputDebugWriter>() ),
- m_os( m_streamBuf.get() )
- {}
-
- std::ostream& DebugOutStream::stream() const {
- return m_os;
- }
-
- // Store the streambuf from cout up-front because
- // cout may get redirected when running tests
- CoutStream::CoutStream()
- : m_os( Catch::cout().rdbuf() )
- {}
-
- std::ostream& CoutStream::stream() const {
- return m_os;
- }
-
-#ifndef CATCH_CONFIG_NOSTDOUT // If you #define this you must implement these functions
- std::ostream& cout() {
- return std::cout;
- }
- std::ostream& cerr() {
- return std::cerr;
- }
- std::ostream& clog() {
- return std::clog;
- }
-#endif
-}
-
-namespace Catch {
-
- class Context : public IMutableContext {
-
- Context() : m_config( CATCH_NULL ), m_runner( CATCH_NULL ), m_resultCapture( CATCH_NULL ) {}
- Context( Context const& );
- void operator=( Context const& );
-
- public:
- virtual ~Context() {
- deleteAllValues( m_generatorsByTestName );
- }
-
- public: // IContext
- virtual IResultCapture* getResultCapture() {
- return m_resultCapture;
- }
- virtual IRunner* getRunner() {
- return m_runner;
- }
- virtual size_t getGeneratorIndex( std::string const& fileInfo, size_t totalSize ) {
- return getGeneratorsForCurrentTest()
- .getGeneratorInfo( fileInfo, totalSize )
- .getCurrentIndex();
- }
- virtual bool advanceGeneratorsForCurrentTest() {
- IGeneratorsForTest* generators = findGeneratorsForCurrentTest();
- return generators && generators->moveNext();
- }
-
- virtual Ptr<IConfig const> getConfig() const {
- return m_config;
- }
-
- public: // IMutableContext
- virtual void setResultCapture( IResultCapture* resultCapture ) {
- m_resultCapture = resultCapture;
- }
- virtual void setRunner( IRunner* runner ) {
- m_runner = runner;
- }
- virtual void setConfig( Ptr<IConfig const> const& config ) {
- m_config = config;
- }
-
- friend IMutableContext& getCurrentMutableContext();
-
- private:
- IGeneratorsForTest* findGeneratorsForCurrentTest() {
- std::string testName = getResultCapture()->getCurrentTestName();
-
- std::map<std::string, IGeneratorsForTest*>::const_iterator it =
- m_generatorsByTestName.find( testName );
- return it != m_generatorsByTestName.end()
- ? it->second
- : CATCH_NULL;
- }
-
- IGeneratorsForTest& getGeneratorsForCurrentTest() {
- IGeneratorsForTest* generators = findGeneratorsForCurrentTest();
- if( !generators ) {
- std::string testName = getResultCapture()->getCurrentTestName();
- generators = createGeneratorsForTest();
- m_generatorsByTestName.insert( std::make_pair( testName, generators ) );
- }
- return *generators;
- }
-
- private:
- Ptr<IConfig const> m_config;
- IRunner* m_runner;
- IResultCapture* m_resultCapture;
- std::map<std::string, IGeneratorsForTest*> m_generatorsByTestName;
- };
-
- namespace {
- Context* currentContext = CATCH_NULL;
- }
- IMutableContext& getCurrentMutableContext() {
- if( !currentContext )
- currentContext = new Context();
- return *currentContext;
- }
- IContext& getCurrentContext() {
- return getCurrentMutableContext();
- }
-
- void cleanUpContext() {
- delete currentContext;
- currentContext = CATCH_NULL;
- }
-}
-
-// #included from: catch_console_colour_impl.hpp
-#define TWOBLUECUBES_CATCH_CONSOLE_COLOUR_IMPL_HPP_INCLUDED
-
-// #included from: catch_errno_guard.hpp
-#define TWOBLUECUBES_CATCH_ERRNO_GUARD_HPP_INCLUDED
-
-#include <cerrno>
-
-namespace Catch {
-
- class ErrnoGuard {
- public:
- ErrnoGuard():m_oldErrno(errno){}
- ~ErrnoGuard() { errno = m_oldErrno; }
- private:
- int m_oldErrno;
- };
-
-}
-
-namespace Catch {
- namespace {
-
- struct IColourImpl {
- virtual ~IColourImpl() {}
- virtual void use( Colour::Code _colourCode ) = 0;
- };
-
- struct NoColourImpl : IColourImpl {
- void use( Colour::Code ) {}
-
- static IColourImpl* instance() {
- static NoColourImpl s_instance;
- return &s_instance;
- }
- };
-
- } // anon namespace
-} // namespace Catch
-
-#if !defined( CATCH_CONFIG_COLOUR_NONE ) && !defined( CATCH_CONFIG_COLOUR_WINDOWS ) && !defined( CATCH_CONFIG_COLOUR_ANSI )
-# ifdef CATCH_PLATFORM_WINDOWS
-# define CATCH_CONFIG_COLOUR_WINDOWS
-# else
-# define CATCH_CONFIG_COLOUR_ANSI
-# endif
-#endif
-
-#if defined ( CATCH_CONFIG_COLOUR_WINDOWS ) /////////////////////////////////////////
-
-namespace Catch {
-namespace {
-
- class Win32ColourImpl : public IColourImpl {
- public:
- Win32ColourImpl() : stdoutHandle( GetStdHandle(STD_OUTPUT_HANDLE) )
- {
- CONSOLE_SCREEN_BUFFER_INFO csbiInfo;
- GetConsoleScreenBufferInfo( stdoutHandle, &csbiInfo );
- originalForegroundAttributes = csbiInfo.wAttributes & ~( BACKGROUND_GREEN | BACKGROUND_RED | BACKGROUND_BLUE | BACKGROUND_INTENSITY );
- originalBackgroundAttributes = csbiInfo.wAttributes & ~( FOREGROUND_GREEN | FOREGROUND_RED | FOREGROUND_BLUE | FOREGROUND_INTENSITY );
- }
-
- virtual void use( Colour::Code _colourCode ) {
- switch( _colourCode ) {
- case Colour::None: return setTextAttribute( originalForegroundAttributes );
- case Colour::White: return setTextAttribute( FOREGROUND_GREEN | FOREGROUND_RED | FOREGROUND_BLUE );
- case Colour::Red: return setTextAttribute( FOREGROUND_RED );
- case Colour::Green: return setTextAttribute( FOREGROUND_GREEN );
- case Colour::Blue: return setTextAttribute( FOREGROUND_BLUE );
- case Colour::Cyan: return setTextAttribute( FOREGROUND_BLUE | FOREGROUND_GREEN );
- case Colour::Yellow: return setTextAttribute( FOREGROUND_RED | FOREGROUND_GREEN );
- case Colour::Grey: return setTextAttribute( 0 );
-
- case Colour::LightGrey: return setTextAttribute( FOREGROUND_INTENSITY );
- case Colour::BrightRed: return setTextAttribute( FOREGROUND_INTENSITY | FOREGROUND_RED );
- case Colour::BrightGreen: return setTextAttribute( FOREGROUND_INTENSITY | FOREGROUND_GREEN );
- case Colour::BrightWhite: return setTextAttribute( FOREGROUND_INTENSITY | FOREGROUND_GREEN | FOREGROUND_RED | FOREGROUND_BLUE );
-
- case Colour::Bright: throw std::logic_error( "not a colour" );
- }
- }
-
- private:
- void setTextAttribute( WORD _textAttribute ) {
- SetConsoleTextAttribute( stdoutHandle, _textAttribute | originalBackgroundAttributes );
- }
- HANDLE stdoutHandle;
- WORD originalForegroundAttributes;
- WORD originalBackgroundAttributes;
- };
-
- IColourImpl* platformColourInstance() {
- static Win32ColourImpl s_instance;
-
- Ptr<IConfig const> config = getCurrentContext().getConfig();
- UseColour::YesOrNo colourMode = config
- ? config->useColour()
- : UseColour::Auto;
- if( colourMode == UseColour::Auto )
- colourMode = !isDebuggerActive()
- ? UseColour::Yes
- : UseColour::No;
- return colourMode == UseColour::Yes
- ? &s_instance
- : NoColourImpl::instance();
- }
-
-} // end anon namespace
-} // end namespace Catch
-
-#elif defined( CATCH_CONFIG_COLOUR_ANSI ) //////////////////////////////////////
-
-#include <unistd.h>
-
-namespace Catch {
-namespace {
-
- // use POSIX/ ANSI console terminal codes
- // Thanks to Adam Strzelecki for original contribution
- // (http://github.com/nanoant)
- // https://github.com/philsquared/Catch/pull/131
- class PosixColourImpl : public IColourImpl {
- public:
- virtual void use( Colour::Code _colourCode ) {
- switch( _colourCode ) {
- case Colour::None:
- case Colour::White: return setColour( "[0m" );
- case Colour::Red: return setColour( "[0;31m" );
- case Colour::Green: return setColour( "[0;32m" );
- case Colour::Blue: return setColour( "[0;34m" );
- case Colour::Cyan: return setColour( "[0;36m" );
- case Colour::Yellow: return setColour( "[0;33m" );
- case Colour::Grey: return setColour( "[1;30m" );
-
- case Colour::LightGrey: return setColour( "[0;37m" );
- case Colour::BrightRed: return setColour( "[1;31m" );
- case Colour::BrightGreen: return setColour( "[1;32m" );
- case Colour::BrightWhite: return setColour( "[1;37m" );
-
- case Colour::Bright: throw std::logic_error( "not a colour" );
- }
- }
- static IColourImpl* instance() {
- static PosixColourImpl s_instance;
- return &s_instance;
- }
-
- private:
- void setColour( const char* _escapeCode ) {
- Catch::cout() << '\033' << _escapeCode;
- }
- };
-
- IColourImpl* platformColourInstance() {
- ErrnoGuard guard;
- Ptr<IConfig const> config = getCurrentContext().getConfig();
- UseColour::YesOrNo colourMode = config
- ? config->useColour()
- : UseColour::Auto;
- if( colourMode == UseColour::Auto )
- colourMode = (!isDebuggerActive() && isatty(STDOUT_FILENO) )
- ? UseColour::Yes
- : UseColour::No;
- return colourMode == UseColour::Yes
- ? PosixColourImpl::instance()
- : NoColourImpl::instance();
- }
-
-} // end anon namespace
-} // end namespace Catch
-
-#else // not Windows or ANSI ///////////////////////////////////////////////
-
-namespace Catch {
-
- static IColourImpl* platformColourInstance() { return NoColourImpl::instance(); }
-
-} // end namespace Catch
-
-#endif // Windows/ ANSI/ None
-
-namespace Catch {
-
- Colour::Colour( Code _colourCode ) : m_moved( false ) { use( _colourCode ); }
- Colour::Colour( Colour const& _other ) : m_moved( false ) { const_cast<Colour&>( _other ).m_moved = true; }
- Colour::~Colour(){ if( !m_moved ) use( None ); }
-
- void Colour::use( Code _colourCode ) {
- static IColourImpl* impl = platformColourInstance();
- impl->use( _colourCode );
- }
-
-} // end namespace Catch
-
-// #included from: catch_generators_impl.hpp
-#define TWOBLUECUBES_CATCH_GENERATORS_IMPL_HPP_INCLUDED
-
-#include <vector>
-#include <string>
-#include <map>
-
-namespace Catch {
-
- struct GeneratorInfo : IGeneratorInfo {
-
- GeneratorInfo( std::size_t size )
- : m_size( size ),
- m_currentIndex( 0 )
- {}
-
- bool moveNext() {
- if( ++m_currentIndex == m_size ) {
- m_currentIndex = 0;
- return false;
- }
- return true;
- }
-
- std::size_t getCurrentIndex() const {
- return m_currentIndex;
- }
-
- std::size_t m_size;
- std::size_t m_currentIndex;
- };
-
- ///////////////////////////////////////////////////////////////////////////
-
- class GeneratorsForTest : public IGeneratorsForTest {
-
- public:
- ~GeneratorsForTest() {
- deleteAll( m_generatorsInOrder );
- }
-
- IGeneratorInfo& getGeneratorInfo( std::string const& fileInfo, std::size_t size ) {
- std::map<std::string, IGeneratorInfo*>::const_iterator it = m_generatorsByName.find( fileInfo );
- if( it == m_generatorsByName.end() ) {
- IGeneratorInfo* info = new GeneratorInfo( size );
- m_generatorsByName.insert( std::make_pair( fileInfo, info ) );
- m_generatorsInOrder.push_back( info );
- return *info;
- }
- return *it->second;
- }
-
- bool moveNext() {
- std::vector<IGeneratorInfo*>::const_iterator it = m_generatorsInOrder.begin();
- std::vector<IGeneratorInfo*>::const_iterator itEnd = m_generatorsInOrder.end();
- for(; it != itEnd; ++it ) {
- if( (*it)->moveNext() )
- return true;
- }
- return false;
- }
-
- private:
- std::map<std::string, IGeneratorInfo*> m_generatorsByName;
- std::vector<IGeneratorInfo*> m_generatorsInOrder;
- };
-
- IGeneratorsForTest* createGeneratorsForTest()
- {
- return new GeneratorsForTest();
- }
-
-} // end namespace Catch
-
-// #included from: catch_assertionresult.hpp
-#define TWOBLUECUBES_CATCH_ASSERTIONRESULT_HPP_INCLUDED
-
-namespace Catch {
-
- AssertionInfo::AssertionInfo():macroName(""), capturedExpression(""), resultDisposition(ResultDisposition::Normal), secondArg(""){}
-
- AssertionInfo::AssertionInfo( char const * _macroName,
- SourceLineInfo const& _lineInfo,
- char const * _capturedExpression,
- ResultDisposition::Flags _resultDisposition,
- char const * _secondArg)
- : macroName( _macroName ),
- lineInfo( _lineInfo ),
- capturedExpression( _capturedExpression ),
- resultDisposition( _resultDisposition ),
- secondArg( _secondArg )
- {}
-
- AssertionResult::AssertionResult() {}
-
- AssertionResult::AssertionResult( AssertionInfo const& info, AssertionResultData const& data )
- : m_info( info ),
- m_resultData( data )
- {}
-
- AssertionResult::~AssertionResult() {}
-
- // Result was a success
- bool AssertionResult::succeeded() const {
- return Catch::isOk( m_resultData.resultType );
- }
-
- // Result was a success, or failure is suppressed
- bool AssertionResult::isOk() const {
- return Catch::isOk( m_resultData.resultType ) || shouldSuppressFailure( m_info.resultDisposition );
- }
-
- ResultWas::OfType AssertionResult::getResultType() const {
- return m_resultData.resultType;
- }
-
- bool AssertionResult::hasExpression() const {
- return m_info.capturedExpression[0] != 0;
- }
-
- bool AssertionResult::hasMessage() const {
- return !m_resultData.message.empty();
- }
-
- std::string capturedExpressionWithSecondArgument( char const * capturedExpression, char const * secondArg ) {
- return (secondArg[0] == 0 || secondArg[0] == '"' && secondArg[1] == '"')
- ? capturedExpression
- : std::string(capturedExpression) + ", " + secondArg;
- }
-
- std::string AssertionResult::getExpression() const {
- if( isFalseTest( m_info.resultDisposition ) )
- return "!(" + capturedExpressionWithSecondArgument(m_info.capturedExpression, m_info.secondArg) + ")";
- else
- return capturedExpressionWithSecondArgument(m_info.capturedExpression, m_info.secondArg);
- }
- std::string AssertionResult::getExpressionInMacro() const {
- if( m_info.macroName[0] == 0 )
- return capturedExpressionWithSecondArgument(m_info.capturedExpression, m_info.secondArg);
- else
- return std::string(m_info.macroName) + "( " + capturedExpressionWithSecondArgument(m_info.capturedExpression, m_info.secondArg) + " )";
- }
-
- bool AssertionResult::hasExpandedExpression() const {
- return hasExpression() && getExpandedExpression() != getExpression();
- }
-
- std::string AssertionResult::getExpandedExpression() const {
- return m_resultData.reconstructExpression();
- }
-
- std::string AssertionResult::getMessage() const {
- return m_resultData.message;
- }
- SourceLineInfo AssertionResult::getSourceInfo() const {
- return m_info.lineInfo;
- }
-
- std::string AssertionResult::getTestMacroName() const {
- return m_info.macroName;
- }
-
- void AssertionResult::discardDecomposedExpression() const {
- m_resultData.decomposedExpression = CATCH_NULL;
- }
-
- void AssertionResult::expandDecomposedExpression() const {
- m_resultData.reconstructExpression();
- }
-
-} // end namespace Catch
-
-// #included from: catch_test_case_info.hpp
-#define TWOBLUECUBES_CATCH_TEST_CASE_INFO_HPP_INCLUDED
-
-#include <cctype>
-
-namespace Catch {
-
- inline TestCaseInfo::SpecialProperties parseSpecialTag( std::string const& tag ) {
- if( startsWith( tag, '.' ) ||
- tag == "hide" ||
- tag == "!hide" )
- return TestCaseInfo::IsHidden;
- else if( tag == "!throws" )
- return TestCaseInfo::Throws;
- else if( tag == "!shouldfail" )
- return TestCaseInfo::ShouldFail;
- else if( tag == "!mayfail" )
- return TestCaseInfo::MayFail;
- else if( tag == "!nonportable" )
- return TestCaseInfo::NonPortable;
- else
- return TestCaseInfo::None;
- }
- inline bool isReservedTag( std::string const& tag ) {
- return parseSpecialTag( tag ) == TestCaseInfo::None && tag.size() > 0 && !std::isalnum( tag[0] );
- }
- inline void enforceNotReservedTag( std::string const& tag, SourceLineInfo const& _lineInfo ) {
- if( isReservedTag( tag ) ) {
- std::ostringstream ss;
- ss << Colour(Colour::Red)
- << "Tag name [" << tag << "] not allowed.\n"
- << "Tag names starting with non alpha-numeric characters are reserved\n"
- << Colour(Colour::FileName)
- << _lineInfo << '\n';
- throw std::runtime_error(ss.str());
- }
- }
-
- TestCase makeTestCase( ITestCase* _testCase,
- std::string const& _className,
- std::string const& _name,
- std::string const& _descOrTags,
- SourceLineInfo const& _lineInfo )
- {
- bool isHidden( startsWith( _name, "./" ) ); // Legacy support
-
- // Parse out tags
- std::set<std::string> tags;
- std::string desc, tag;
- bool inTag = false;
- for( std::size_t i = 0; i < _descOrTags.size(); ++i ) {
- char c = _descOrTags[i];
- if( !inTag ) {
- if( c == '[' )
- inTag = true;
- else
- desc += c;
- }
- else {
- if( c == ']' ) {
- TestCaseInfo::SpecialProperties prop = parseSpecialTag( tag );
- if( prop == TestCaseInfo::IsHidden )
- isHidden = true;
- else if( prop == TestCaseInfo::None )
- enforceNotReservedTag( tag, _lineInfo );
-
- tags.insert( tag );
- tag.clear();
- inTag = false;
- }
- else
- tag += c;
- }
- }
- if( isHidden ) {
- tags.insert( "hide" );
- tags.insert( "." );
- }
-
- TestCaseInfo info( _name, _className, desc, tags, _lineInfo );
- return TestCase( _testCase, info );
- }
-
- void setTags( TestCaseInfo& testCaseInfo, std::set<std::string> const& tags )
- {
- testCaseInfo.tags = tags;
- testCaseInfo.lcaseTags.clear();
-
- std::ostringstream oss;
- for( std::set<std::string>::const_iterator it = tags.begin(), itEnd = tags.end(); it != itEnd; ++it ) {
- oss << '[' << *it << ']';
- std::string lcaseTag = toLower( *it );
- testCaseInfo.properties = static_cast<TestCaseInfo::SpecialProperties>( testCaseInfo.properties | parseSpecialTag( lcaseTag ) );
- testCaseInfo.lcaseTags.insert( lcaseTag );
- }
- testCaseInfo.tagsAsString = oss.str();
- }
-
- TestCaseInfo::TestCaseInfo( std::string const& _name,
- std::string const& _className,
- std::string const& _description,
- std::set<std::string> const& _tags,
- SourceLineInfo const& _lineInfo )
- : name( _name ),
- className( _className ),
- description( _description ),
- lineInfo( _lineInfo ),
- properties( None )
- {
- setTags( *this, _tags );
- }
-
- TestCaseInfo::TestCaseInfo( TestCaseInfo const& other )
- : name( other.name ),
- className( other.className ),
- description( other.description ),
- tags( other.tags ),
- lcaseTags( other.lcaseTags ),
- tagsAsString( other.tagsAsString ),
- lineInfo( other.lineInfo ),
- properties( other.properties )
- {}
-
- bool TestCaseInfo::isHidden() const {
- return ( properties & IsHidden ) != 0;
- }
- bool TestCaseInfo::throws() const {
- return ( properties & Throws ) != 0;
- }
- bool TestCaseInfo::okToFail() const {
- return ( properties & (ShouldFail | MayFail ) ) != 0;
- }
- bool TestCaseInfo::expectedToFail() const {
- return ( properties & (ShouldFail ) ) != 0;
- }
-
- TestCase::TestCase( ITestCase* testCase, TestCaseInfo const& info ) : TestCaseInfo( info ), test( testCase ) {}
-
- TestCase::TestCase( TestCase const& other )
- : TestCaseInfo( other ),
- test( other.test )
- {}
-
- TestCase TestCase::withName( std::string const& _newName ) const {
- TestCase other( *this );
- other.name = _newName;
- return other;
- }
-
- void TestCase::swap( TestCase& other ) {
- test.swap( other.test );
- name.swap( other.name );
- className.swap( other.className );
- description.swap( other.description );
- tags.swap( other.tags );
- lcaseTags.swap( other.lcaseTags );
- tagsAsString.swap( other.tagsAsString );
- std::swap( TestCaseInfo::properties, static_cast<TestCaseInfo&>( other ).properties );
- std::swap( lineInfo, other.lineInfo );
- }
-
- void TestCase::invoke() const {
- test->invoke();
- }
-
- bool TestCase::operator == ( TestCase const& other ) const {
- return test.get() == other.test.get() &&
- name == other.name &&
- className == other.className;
- }
-
- bool TestCase::operator < ( TestCase const& other ) const {
- return name < other.name;
- }
- TestCase& TestCase::operator = ( TestCase const& other ) {
- TestCase temp( other );
- swap( temp );
- return *this;
- }
-
- TestCaseInfo const& TestCase::getTestCaseInfo() const
- {
- return *this;
- }
-
-} // end namespace Catch
-
-// #included from: catch_version.hpp
-#define TWOBLUECUBES_CATCH_VERSION_HPP_INCLUDED
-
-namespace Catch {
-
- Version::Version
- ( unsigned int _majorVersion,
- unsigned int _minorVersion,
- unsigned int _patchNumber,
- char const * const _branchName,
- unsigned int _buildNumber )
- : majorVersion( _majorVersion ),
- minorVersion( _minorVersion ),
- patchNumber( _patchNumber ),
- branchName( _branchName ),
- buildNumber( _buildNumber )
- {}
-
- std::ostream& operator << ( std::ostream& os, Version const& version ) {
- os << version.majorVersion << '.'
- << version.minorVersion << '.'
- << version.patchNumber;
- // branchName is never null -> 0th char is \0 if it is empty
- if (version.branchName[0]) {
- os << '-' << version.branchName
- << '.' << version.buildNumber;
- }
- return os;
- }
-
- inline Version libraryVersion() {
- static Version version( 1, 12, 2, "", 0 );
- return version;
- }
-
-}
-
-// #included from: catch_message.hpp
-#define TWOBLUECUBES_CATCH_MESSAGE_HPP_INCLUDED
-
-namespace Catch {
-
- MessageInfo::MessageInfo( std::string const& _macroName,
- SourceLineInfo const& _lineInfo,
- ResultWas::OfType _type )
- : macroName( _macroName ),
- lineInfo( _lineInfo ),
- type( _type ),
- sequence( ++globalCount )
- {}
-
- // This may need protecting if threading support is added
- unsigned int MessageInfo::globalCount = 0;
-
- ////////////////////////////////////////////////////////////////////////////
-
- ScopedMessage::ScopedMessage( MessageBuilder const& builder )
- : m_info( builder.m_info )
- {
- m_info.message = builder.m_stream.str();
- getResultCapture().pushScopedMessage( m_info );
- }
- ScopedMessage::ScopedMessage( ScopedMessage const& other )
- : m_info( other.m_info )
- {}
-
-#if defined(_MSC_VER)
-#pragma warning(push)
-#pragma warning(disable:4996) // std::uncaught_exception is deprecated in C++17
-#endif
- ScopedMessage::~ScopedMessage() {
- if ( !std::uncaught_exception() ){
- getResultCapture().popScopedMessage(m_info);
- }
- }
-#if defined(_MSC_VER)
-#pragma warning(pop)
-#endif
-
-} // end namespace Catch
-
-// #included from: catch_legacy_reporter_adapter.hpp
-#define TWOBLUECUBES_CATCH_LEGACY_REPORTER_ADAPTER_HPP_INCLUDED
-
-// #included from: catch_legacy_reporter_adapter.h
-#define TWOBLUECUBES_CATCH_LEGACY_REPORTER_ADAPTER_H_INCLUDED
-
-namespace Catch
-{
- // Deprecated
- struct IReporter : IShared {
- virtual ~IReporter();
-
- virtual bool shouldRedirectStdout() const = 0;
-
- virtual void StartTesting() = 0;
- virtual void EndTesting( Totals const& totals ) = 0;
- virtual void StartGroup( std::string const& groupName ) = 0;
- virtual void EndGroup( std::string const& groupName, Totals const& totals ) = 0;
- virtual void StartTestCase( TestCaseInfo const& testInfo ) = 0;
- virtual void EndTestCase( TestCaseInfo const& testInfo, Totals const& totals, std::string const& stdOut, std::string const& stdErr ) = 0;
- virtual void StartSection( std::string const& sectionName, std::string const& description ) = 0;
- virtual void EndSection( std::string const& sectionName, Counts const& assertions ) = 0;
- virtual void NoAssertionsInSection( std::string const& sectionName ) = 0;
- virtual void NoAssertionsInTestCase( std::string const& testName ) = 0;
- virtual void Aborted() = 0;
- virtual void Result( AssertionResult const& result ) = 0;
- };
-
- class LegacyReporterAdapter : public SharedImpl<IStreamingReporter>
- {
- public:
- LegacyReporterAdapter( Ptr<IReporter> const& legacyReporter );
- virtual ~LegacyReporterAdapter();
-
- virtual ReporterPreferences getPreferences() const;
- virtual void noMatchingTestCases( std::string const& );
- virtual void testRunStarting( TestRunInfo const& );
- virtual void testGroupStarting( GroupInfo const& groupInfo );
- virtual void testCaseStarting( TestCaseInfo const& testInfo );
- virtual void sectionStarting( SectionInfo const& sectionInfo );
- virtual void assertionStarting( AssertionInfo const& );
- virtual bool assertionEnded( AssertionStats const& assertionStats );
- virtual void sectionEnded( SectionStats const& sectionStats );
- virtual void testCaseEnded( TestCaseStats const& testCaseStats );
- virtual void testGroupEnded( TestGroupStats const& testGroupStats );
- virtual void testRunEnded( TestRunStats const& testRunStats );
- virtual void skipTest( TestCaseInfo const& );
-
- private:
- Ptr<IReporter> m_legacyReporter;
- };
-}
-
-namespace Catch
-{
- LegacyReporterAdapter::LegacyReporterAdapter( Ptr<IReporter> const& legacyReporter )
- : m_legacyReporter( legacyReporter )
- {}
- LegacyReporterAdapter::~LegacyReporterAdapter() {}
-
- ReporterPreferences LegacyReporterAdapter::getPreferences() const {
- ReporterPreferences prefs;
- prefs.shouldRedirectStdOut = m_legacyReporter->shouldRedirectStdout();
- return prefs;
- }
-
- void LegacyReporterAdapter::noMatchingTestCases( std::string const& ) {}
- void LegacyReporterAdapter::testRunStarting( TestRunInfo const& ) {
- m_legacyReporter->StartTesting();
- }
- void LegacyReporterAdapter::testGroupStarting( GroupInfo const& groupInfo ) {
- m_legacyReporter->StartGroup( groupInfo.name );
- }
- void LegacyReporterAdapter::testCaseStarting( TestCaseInfo const& testInfo ) {
- m_legacyReporter->StartTestCase( testInfo );
- }
- void LegacyReporterAdapter::sectionStarting( SectionInfo const& sectionInfo ) {
- m_legacyReporter->StartSection( sectionInfo.name, sectionInfo.description );
- }
- void LegacyReporterAdapter::assertionStarting( AssertionInfo const& ) {
- // Not on legacy interface
- }
-
- bool LegacyReporterAdapter::assertionEnded( AssertionStats const& assertionStats ) {
- if( assertionStats.assertionResult.getResultType() != ResultWas::Ok ) {
- for( std::vector<MessageInfo>::const_iterator it = assertionStats.infoMessages.begin(), itEnd = assertionStats.infoMessages.end();
- it != itEnd;
- ++it ) {
- if( it->type == ResultWas::Info ) {
- ResultBuilder rb( it->macroName.c_str(), it->lineInfo, "", ResultDisposition::Normal );
- rb << it->message;
- rb.setResultType( ResultWas::Info );
- AssertionResult result = rb.build();
- m_legacyReporter->Result( result );
- }
- }
- }
- m_legacyReporter->Result( assertionStats.assertionResult );
- return true;
- }
- void LegacyReporterAdapter::sectionEnded( SectionStats const& sectionStats ) {
- if( sectionStats.missingAssertions )
- m_legacyReporter->NoAssertionsInSection( sectionStats.sectionInfo.name );
- m_legacyReporter->EndSection( sectionStats.sectionInfo.name, sectionStats.assertions );
- }
- void LegacyReporterAdapter::testCaseEnded( TestCaseStats const& testCaseStats ) {
- m_legacyReporter->EndTestCase
- ( testCaseStats.testInfo,
- testCaseStats.totals,
- testCaseStats.stdOut,
- testCaseStats.stdErr );
- }
- void LegacyReporterAdapter::testGroupEnded( TestGroupStats const& testGroupStats ) {
- if( testGroupStats.aborting )
- m_legacyReporter->Aborted();
- m_legacyReporter->EndGroup( testGroupStats.groupInfo.name, testGroupStats.totals );
- }
- void LegacyReporterAdapter::testRunEnded( TestRunStats const& testRunStats ) {
- m_legacyReporter->EndTesting( testRunStats.totals );
- }
- void LegacyReporterAdapter::skipTest( TestCaseInfo const& ) {
- }
-}
-
-// #included from: catch_timer.hpp
-
-#ifdef __clang__
-#pragma clang diagnostic push
-#pragma clang diagnostic ignored "-Wc++11-long-long"
-#endif
-
-#ifdef CATCH_PLATFORM_WINDOWS
-
-#else
-
-#include <sys/time.h>
-
-#endif
-
-namespace Catch {
-
- namespace {
-#ifdef CATCH_PLATFORM_WINDOWS
- UInt64 getCurrentTicks() {
- static UInt64 hz=0, hzo=0;
- if (!hz) {
- QueryPerformanceFrequency( reinterpret_cast<LARGE_INTEGER*>( &hz ) );
- QueryPerformanceCounter( reinterpret_cast<LARGE_INTEGER*>( &hzo ) );
- }
- UInt64 t;
- QueryPerformanceCounter( reinterpret_cast<LARGE_INTEGER*>( &t ) );
- return ((t-hzo)*1000000)/hz;
- }
-#else
- UInt64 getCurrentTicks() {
- timeval t;
- gettimeofday(&t,CATCH_NULL);
- return static_cast<UInt64>( t.tv_sec ) * 1000000ull + static_cast<UInt64>( t.tv_usec );
- }
-#endif
- }
-
- void Timer::start() {
- m_ticks = getCurrentTicks();
- }
- unsigned int Timer::getElapsedMicroseconds() const {
- return static_cast<unsigned int>(getCurrentTicks() - m_ticks);
- }
- unsigned int Timer::getElapsedMilliseconds() const {
- return static_cast<unsigned int>(getElapsedMicroseconds()/1000);
- }
- double Timer::getElapsedSeconds() const {
- return getElapsedMicroseconds()/1000000.0;
- }
-
-} // namespace Catch
-
-#ifdef __clang__
-#pragma clang diagnostic pop
-#endif
-// #included from: catch_common.hpp
-#define TWOBLUECUBES_CATCH_COMMON_HPP_INCLUDED
-
-#include <cstring>
-#include <cctype>
-
-namespace Catch {
-
- bool startsWith( std::string const& s, std::string const& prefix ) {
- return s.size() >= prefix.size() && std::equal(prefix.begin(), prefix.end(), s.begin());
- }
- bool startsWith( std::string const& s, char prefix ) {
- return !s.empty() && s[0] == prefix;
- }
- bool endsWith( std::string const& s, std::string const& suffix ) {
- return s.size() >= suffix.size() && std::equal(suffix.rbegin(), suffix.rend(), s.rbegin());
- }
- bool endsWith( std::string const& s, char suffix ) {
- return !s.empty() && s[s.size()-1] == suffix;
- }
- bool contains( std::string const& s, std::string const& infix ) {
- return s.find( infix ) != std::string::npos;
- }
- char toLowerCh(char c) {
- return static_cast<char>( std::tolower( c ) );
- }
- void toLowerInPlace( std::string& s ) {
- std::transform( s.begin(), s.end(), s.begin(), toLowerCh );
- }
- std::string toLower( std::string const& s ) {
- std::string lc = s;
- toLowerInPlace( lc );
- return lc;
- }
- std::string trim( std::string const& str ) {
- static char const* whitespaceChars = "\n\r\t ";
- std::string::size_type start = str.find_first_not_of( whitespaceChars );
- std::string::size_type end = str.find_last_not_of( whitespaceChars );
-
- return start != std::string::npos ? str.substr( start, 1+end-start ) : std::string();
- }
-
- bool replaceInPlace( std::string& str, std::string const& replaceThis, std::string const& withThis ) {
- bool replaced = false;
- std::size_t i = str.find( replaceThis );
- while( i != std::string::npos ) {
- replaced = true;
- str = str.substr( 0, i ) + withThis + str.substr( i+replaceThis.size() );
- if( i < str.size()-withThis.size() )
- i = str.find( replaceThis, i+withThis.size() );
- else
- i = std::string::npos;
- }
- return replaced;
- }
-
- pluralise::pluralise( std::size_t count, std::string const& label )
- : m_count( count ),
- m_label( label )
- {}
-
- std::ostream& operator << ( std::ostream& os, pluralise const& pluraliser ) {
- os << pluraliser.m_count << ' ' << pluraliser.m_label;
- if( pluraliser.m_count != 1 )
- os << 's';
- return os;
- }
-
- SourceLineInfo::SourceLineInfo() : file(""), line( 0 ){}
- SourceLineInfo::SourceLineInfo( char const* _file, std::size_t _line )
- : file( _file ),
- line( _line )
- {}
- bool SourceLineInfo::empty() const {
- return file[0] == '\0';
- }
- bool SourceLineInfo::operator == ( SourceLineInfo const& other ) const {
- return line == other.line && (file == other.file || std::strcmp(file, other.file) == 0);
- }
- bool SourceLineInfo::operator < ( SourceLineInfo const& other ) const {
- return line < other.line || ( line == other.line && (std::strcmp(file, other.file) < 0));
- }
-
- void seedRng( IConfig const& config ) {
- if( config.rngSeed() != 0 )
- std::srand( config.rngSeed() );
- }
- unsigned int rngSeed() {
- return getCurrentContext().getConfig()->rngSeed();
- }
-
- std::ostream& operator << ( std::ostream& os, SourceLineInfo const& info ) {
-#ifndef __GNUG__
- os << info.file << '(' << info.line << ')';
-#else
- os << info.file << ':' << info.line;
-#endif
- return os;
- }
-
- void throwLogicError( std::string const& message, SourceLineInfo const& locationInfo ) {
- std::ostringstream oss;
- oss << locationInfo << ": Internal Catch error: '" << message << '\'';
- if( alwaysTrue() )
- throw std::logic_error( oss.str() );
- }
-}
-
-// #included from: catch_section.hpp
-#define TWOBLUECUBES_CATCH_SECTION_HPP_INCLUDED
-
-namespace Catch {
-
- SectionInfo::SectionInfo
- ( SourceLineInfo const& _lineInfo,
- std::string const& _name,
- std::string const& _description )
- : name( _name ),
- description( _description ),
- lineInfo( _lineInfo )
- {}
-
- Section::Section( SectionInfo const& info )
- : m_info( info ),
- m_sectionIncluded( getResultCapture().sectionStarted( m_info, m_assertions ) )
- {
- m_timer.start();
- }
-
-#if defined(_MSC_VER)
-#pragma warning(push)
-#pragma warning(disable:4996) // std::uncaught_exception is deprecated in C++17
-#endif
- Section::~Section() {
- if( m_sectionIncluded ) {
- SectionEndInfo endInfo( m_info, m_assertions, m_timer.getElapsedSeconds() );
- if( std::uncaught_exception() )
- getResultCapture().sectionEndedEarly( endInfo );
- else
- getResultCapture().sectionEnded( endInfo );
- }
- }
-#if defined(_MSC_VER)
-#pragma warning(pop)
-#endif
-
- // This indicates whether the section should be executed or not
- Section::operator bool() const {
- return m_sectionIncluded;
- }
-
-} // end namespace Catch
-
-// #included from: catch_debugger.hpp
-#define TWOBLUECUBES_CATCH_DEBUGGER_HPP_INCLUDED
-
-#ifdef CATCH_PLATFORM_MAC
-
- #include <assert.h>
- #include <stdbool.h>
- #include <sys/types.h>
- #include <unistd.h>
- #include <sys/sysctl.h>
-
- namespace Catch{
-
- // The following function is taken directly from the following technical note:
- // http://developer.apple.com/library/mac/#qa/qa2004/qa1361.html
-
- // Returns true if the current process is being debugged (either
- // running under the debugger or has a debugger attached post facto).
- bool isDebuggerActive(){
-
- int mib[4];
- struct kinfo_proc info;
- size_t size;
-
- // Initialize the flags so that, if sysctl fails for some bizarre
- // reason, we get a predictable result.
-
- info.kp_proc.p_flag = 0;
-
- // Initialize mib, which tells sysctl the info we want, in this case
- // we're looking for information about a specific process ID.
-
- mib[0] = CTL_KERN;
- mib[1] = KERN_PROC;
- mib[2] = KERN_PROC_PID;
- mib[3] = getpid();
-
- // Call sysctl.
-
- size = sizeof(info);
- if( sysctl(mib, sizeof(mib) / sizeof(*mib), &info, &size, CATCH_NULL, 0) != 0 ) {
- Catch::cerr() << "\n** Call to sysctl failed - unable to determine if debugger is active **\n" << std::endl;
- return false;
- }
-
- // We're being debugged if the P_TRACED flag is set.
-
- return ( (info.kp_proc.p_flag & P_TRACED) != 0 );
- }
- } // namespace Catch
-
-#elif defined(CATCH_PLATFORM_LINUX)
- #include <fstream>
- #include <string>
-
- namespace Catch{
- // The standard POSIX way of detecting a debugger is to attempt to
- // ptrace() the process, but this needs to be done from a child and not
- // this process itself to still allow attaching to this process later
- // if wanted, so is rather heavy. Under Linux we have the PID of the
- // "debugger" (which doesn't need to be gdb, of course, it could also
- // be strace, for example) in /proc/$PID/status, so just get it from
- // there instead.
- bool isDebuggerActive(){
- // Libstdc++ has a bug, where std::ifstream sets errno to 0
- // This way our users can properly assert over errno values
- ErrnoGuard guard;
- std::ifstream in("/proc/self/status");
- for( std::string line; std::getline(in, line); ) {
- static const int PREFIX_LEN = 11;
- if( line.compare(0, PREFIX_LEN, "TracerPid:\t") == 0 ) {
- // We're traced if the PID is not 0 and no other PID starts
- // with 0 digit, so it's enough to check for just a single
- // character.
- return line.length() > PREFIX_LEN && line[PREFIX_LEN] != '0';
- }
- }
-
- return false;
- }
- } // namespace Catch
-#elif defined(_MSC_VER)
- extern "C" __declspec(dllimport) int __stdcall IsDebuggerPresent();
- namespace Catch {
- bool isDebuggerActive() {
- return IsDebuggerPresent() != 0;
- }
- }
-#elif defined(__MINGW32__)
- extern "C" __declspec(dllimport) int __stdcall IsDebuggerPresent();
- namespace Catch {
- bool isDebuggerActive() {
- return IsDebuggerPresent() != 0;
- }
- }
-#else
- namespace Catch {
- inline bool isDebuggerActive() { return false; }
- }
-#endif // Platform
-
-#ifdef CATCH_PLATFORM_WINDOWS
-
- namespace Catch {
- void writeToDebugConsole( std::string const& text ) {
- ::OutputDebugStringA( text.c_str() );
- }
- }
-#else
- namespace Catch {
- void writeToDebugConsole( std::string const& text ) {
- // !TBD: Need a version for Mac/ XCode and other IDEs
- Catch::cout() << text;
- }
- }
-#endif // Platform
-
-// #included from: catch_tostring.hpp
-#define TWOBLUECUBES_CATCH_TOSTRING_HPP_INCLUDED
-
-namespace Catch {
-
-namespace Detail {
-
- const std::string unprintableString = "{?}";
-
- namespace {
- const int hexThreshold = 255;
-
- struct Endianness {
- enum Arch { Big, Little };
-
- static Arch which() {
- union _{
- int asInt;
- char asChar[sizeof (int)];
- } u;
-
- u.asInt = 1;
- return ( u.asChar[sizeof(int)-1] == 1 ) ? Big : Little;
- }
- };
- }
-
- std::string rawMemoryToString( const void *object, std::size_t size )
- {
- // Reverse order for little endian architectures
- int i = 0, end = static_cast<int>( size ), inc = 1;
- if( Endianness::which() == Endianness::Little ) {
- i = end-1;
- end = inc = -1;
- }
-
- unsigned char const *bytes = static_cast<unsigned char const *>(object);
- std::ostringstream os;
- os << "0x" << std::setfill('0') << std::hex;
- for( ; i != end; i += inc )
- os << std::setw(2) << static_cast<unsigned>(bytes[i]);
- return os.str();
- }
-}
-
-std::string toString( std::string const& value ) {
- std::string s = value;
- if( getCurrentContext().getConfig()->showInvisibles() ) {
- for(size_t i = 0; i < s.size(); ++i ) {
- std::string subs;
- switch( s[i] ) {
- case '\n': subs = "\\n"; break;
- case '\t': subs = "\\t"; break;
- default: break;
- }
- if( !subs.empty() ) {
- s = s.substr( 0, i ) + subs + s.substr( i+1 );
- ++i;
- }
- }
- }
- return '"' + s + '"';
-}
-std::string toString( std::wstring const& value ) {
-
- std::string s;
- s.reserve( value.size() );
- for(size_t i = 0; i < value.size(); ++i )
- s += value[i] <= 0xff ? static_cast<char>( value[i] ) : '?';
- return Catch::toString( s );
-}
-
-std::string toString( const char* const value ) {
- return value ? Catch::toString( std::string( value ) ) : std::string( "{null string}" );
-}
-
-std::string toString( char* const value ) {
- return Catch::toString( static_cast<const char*>( value ) );
-}
-
-std::string toString( const wchar_t* const value )
-{
- return value ? Catch::toString( std::wstring(value) ) : std::string( "{null string}" );
-}
-
-std::string toString( wchar_t* const value )
-{
- return Catch::toString( static_cast<const wchar_t*>( value ) );
-}
-
-std::string toString( int value ) {
- std::ostringstream oss;
- oss << value;
- if( value > Detail::hexThreshold )
- oss << " (0x" << std::hex << value << ')';
- return oss.str();
-}
-
-std::string toString( unsigned long value ) {
- std::ostringstream oss;
- oss << value;
- if( value > Detail::hexThreshold )
- oss << " (0x" << std::hex << value << ')';
- return oss.str();
-}
-
-std::string toString( unsigned int value ) {
- return Catch::toString( static_cast<unsigned long>( value ) );
-}
-
-template<typename T>
-std::string fpToString( T value, int precision ) {
- std::ostringstream oss;
- oss << std::setprecision( precision )
- << std::fixed
- << value;
- std::string d = oss.str();
- std::size_t i = d.find_last_not_of( '0' );
- if( i != std::string::npos && i != d.size()-1 ) {
- if( d[i] == '.' )
- i++;
- d = d.substr( 0, i+1 );
- }
- return d;
-}
-
-std::string toString( const double value ) {
- return fpToString( value, 10 );
-}
-std::string toString( const float value ) {
- return fpToString( value, 5 ) + 'f';
-}
-
-std::string toString( bool value ) {
- return value ? "true" : "false";
-}
-
-std::string toString( char value ) {
- if ( value == '\r' )
- return "'\\r'";
- if ( value == '\f' )
- return "'\\f'";
- if ( value == '\n' )
- return "'\\n'";
- if ( value == '\t' )
- return "'\\t'";
- if ( '\0' <= value && value < ' ' )
- return toString( static_cast<unsigned int>( value ) );
- char chstr[] = "' '";
- chstr[1] = value;
- return chstr;
-}
-
-std::string toString( signed char value ) {
- return toString( static_cast<char>( value ) );
-}
-
-std::string toString( unsigned char value ) {
- return toString( static_cast<char>( value ) );
-}
-
-#ifdef CATCH_CONFIG_CPP11_LONG_LONG
-std::string toString( long long value ) {
- std::ostringstream oss;
- oss << value;
- if( value > Detail::hexThreshold )
- oss << " (0x" << std::hex << value << ')';
- return oss.str();
-}
-std::string toString( unsigned long long value ) {
- std::ostringstream oss;
- oss << value;
- if( value > Detail::hexThreshold )
- oss << " (0x" << std::hex << value << ')';
- return oss.str();
-}
-#endif
-
-#ifdef CATCH_CONFIG_CPP11_NULLPTR
-std::string toString( std::nullptr_t ) {
- return "nullptr";
-}
-#endif
-
-#ifdef __OBJC__
- std::string toString( NSString const * const& nsstring ) {
- if( !nsstring )
- return "nil";
- return "@" + toString([nsstring UTF8String]);
- }
- std::string toString( NSString * CATCH_ARC_STRONG & nsstring ) {
- if( !nsstring )
- return "nil";
- return "@" + toString([nsstring UTF8String]);
- }
- std::string toString( NSObject* const& nsObject ) {
- return toString( [nsObject description] );
- }
-#endif
-
-} // end namespace Catch
-
-// #included from: catch_result_builder.hpp
-#define TWOBLUECUBES_CATCH_RESULT_BUILDER_HPP_INCLUDED
-
-#include <cassert>
-
-namespace Catch {
-
- ResultBuilder::ResultBuilder( char const* macroName,
- SourceLineInfo const& lineInfo,
- char const* capturedExpression,
- ResultDisposition::Flags resultDisposition,
- char const* secondArg )
- : m_assertionInfo( macroName, lineInfo, capturedExpression, resultDisposition, secondArg ),
- m_shouldDebugBreak( false ),
- m_shouldThrow( false ),
- m_guardException( false ),
- m_usedStream( false )
- {}
-
- ResultBuilder::~ResultBuilder() {
-#if defined(CATCH_CONFIG_FAST_COMPILE)
- if ( m_guardException ) {
- stream().oss << "Exception translation was disabled by CATCH_CONFIG_FAST_COMPILE";
- captureResult( ResultWas::ThrewException );
- getCurrentContext().getResultCapture()->exceptionEarlyReported();
- }
-#endif
- }
-
- ResultBuilder& ResultBuilder::setResultType( ResultWas::OfType result ) {
- m_data.resultType = result;
- return *this;
- }
- ResultBuilder& ResultBuilder::setResultType( bool result ) {
- m_data.resultType = result ? ResultWas::Ok : ResultWas::ExpressionFailed;
- return *this;
- }
-
- void ResultBuilder::endExpression( DecomposedExpression const& expr ) {
- // Flip bool results if FalseTest flag is set
- if( isFalseTest( m_assertionInfo.resultDisposition ) ) {
- m_data.negate( expr.isBinaryExpression() );
- }
-
- getResultCapture().assertionRun();
-
- if(getCurrentContext().getConfig()->includeSuccessfulResults() || m_data.resultType != ResultWas::Ok)
- {
- AssertionResult result = build( expr );
- handleResult( result );
- }
- else
- getResultCapture().assertionPassed();
- }
-
- void ResultBuilder::useActiveException( ResultDisposition::Flags resultDisposition ) {
- m_assertionInfo.resultDisposition = resultDisposition;
- stream().oss << Catch::translateActiveException();
- captureResult( ResultWas::ThrewException );
- }
-
- void ResultBuilder::captureResult( ResultWas::OfType resultType ) {
- setResultType( resultType );
- captureExpression();
- }
-
- void ResultBuilder::captureExpectedException( std::string const& expectedMessage ) {
- if( expectedMessage.empty() )
- captureExpectedException( Matchers::Impl::MatchAllOf<std::string>() );
- else
- captureExpectedException( Matchers::Equals( expectedMessage ) );
- }
-
- void ResultBuilder::captureExpectedException( Matchers::Impl::MatcherBase<std::string> const& matcher ) {
-
- assert( !isFalseTest( m_assertionInfo.resultDisposition ) );
- AssertionResultData data = m_data;
- data.resultType = ResultWas::Ok;
- data.reconstructedExpression = capturedExpressionWithSecondArgument(m_assertionInfo.capturedExpression, m_assertionInfo.secondArg);
-
- std::string actualMessage = Catch::translateActiveException();
- if( !matcher.match( actualMessage ) ) {
- data.resultType = ResultWas::ExpressionFailed;
- data.reconstructedExpression = actualMessage;
- }
- AssertionResult result( m_assertionInfo, data );
- handleResult( result );
- }
-
- void ResultBuilder::captureExpression() {
- AssertionResult result = build();
- handleResult( result );
- }
-
- void ResultBuilder::handleResult( AssertionResult const& result )
- {
- getResultCapture().assertionEnded( result );
-
- if( !result.isOk() ) {
- if( getCurrentContext().getConfig()->shouldDebugBreak() )
- m_shouldDebugBreak = true;
- if( getCurrentContext().getRunner()->aborting() || (m_assertionInfo.resultDisposition & ResultDisposition::Normal) )
- m_shouldThrow = true;
- }
- }
-
- void ResultBuilder::react() {
-#if defined(CATCH_CONFIG_FAST_COMPILE)
- if (m_shouldDebugBreak) {
- ///////////////////////////////////////////////////////////////////
- // To inspect the state during test, you need to go one level up the callstack
- // To go back to the test and change execution, jump over the throw statement
- ///////////////////////////////////////////////////////////////////
- CATCH_BREAK_INTO_DEBUGGER();
- }
-#endif
- if( m_shouldThrow )
- throw Catch::TestFailureException();
- }
-
- bool ResultBuilder::shouldDebugBreak() const { return m_shouldDebugBreak; }
- bool ResultBuilder::allowThrows() const { return getCurrentContext().getConfig()->allowThrows(); }
-
- AssertionResult ResultBuilder::build() const
- {
- return build( *this );
- }
-
- // CAVEAT: The returned AssertionResult stores a pointer to the argument expr,
- // a temporary DecomposedExpression, which in turn holds references to
- // operands, possibly temporary as well.
- // It should immediately be passed to handleResult; if the expression
- // needs to be reported, its string expansion must be composed before
- // the temporaries are destroyed.
- AssertionResult ResultBuilder::build( DecomposedExpression const& expr ) const
- {
- assert( m_data.resultType != ResultWas::Unknown );
- AssertionResultData data = m_data;
-
- if(m_usedStream)
- data.message = m_stream().oss.str();
- data.decomposedExpression = &expr; // for lazy reconstruction
- return AssertionResult( m_assertionInfo, data );
- }
-
- void ResultBuilder::reconstructExpression( std::string& dest ) const {
- dest = capturedExpressionWithSecondArgument(m_assertionInfo.capturedExpression, m_assertionInfo.secondArg);
- }
-
- void ResultBuilder::setExceptionGuard() {
- m_guardException = true;
- }
- void ResultBuilder::unsetExceptionGuard() {
- m_guardException = false;
- }
-
-} // end namespace Catch
-
-// #included from: catch_tag_alias_registry.hpp
-#define TWOBLUECUBES_CATCH_TAG_ALIAS_REGISTRY_HPP_INCLUDED
-
-namespace Catch {
-
- TagAliasRegistry::~TagAliasRegistry() {}
-
- Option<TagAlias> TagAliasRegistry::find( std::string const& alias ) const {
- std::map<std::string, TagAlias>::const_iterator it = m_registry.find( alias );
- if( it != m_registry.end() )
- return it->second;
- else
- return Option<TagAlias>();
- }
-
- std::string TagAliasRegistry::expandAliases( std::string const& unexpandedTestSpec ) const {
- std::string expandedTestSpec = unexpandedTestSpec;
- for( std::map<std::string, TagAlias>::const_iterator it = m_registry.begin(), itEnd = m_registry.end();
- it != itEnd;
- ++it ) {
- std::size_t pos = expandedTestSpec.find( it->first );
- if( pos != std::string::npos ) {
- expandedTestSpec = expandedTestSpec.substr( 0, pos ) +
- it->second.tag +
- expandedTestSpec.substr( pos + it->first.size() );
- }
- }
- return expandedTestSpec;
- }
-
- void TagAliasRegistry::add( std::string const& alias, std::string const& tag, SourceLineInfo const& lineInfo ) {
-
- if( !startsWith( alias, "[@" ) || !endsWith( alias, ']' ) ) {
- std::ostringstream oss;
- oss << Colour( Colour::Red )
- << "error: tag alias, \"" << alias << "\" is not of the form [@alias name].\n"
- << Colour( Colour::FileName )
- << lineInfo << '\n';
- throw std::domain_error( oss.str().c_str() );
- }
- if( !m_registry.insert( std::make_pair( alias, TagAlias( tag, lineInfo ) ) ).second ) {
- std::ostringstream oss;
- oss << Colour( Colour::Red )
- << "error: tag alias, \"" << alias << "\" already registered.\n"
- << "\tFirst seen at "
- << Colour( Colour::Red ) << find(alias)->lineInfo << '\n'
- << Colour( Colour::Red ) << "\tRedefined at "
- << Colour( Colour::FileName) << lineInfo << '\n';
- throw std::domain_error( oss.str().c_str() );
- }
- }
-
- ITagAliasRegistry::~ITagAliasRegistry() {}
-
- ITagAliasRegistry const& ITagAliasRegistry::get() {
- return getRegistryHub().getTagAliasRegistry();
- }
-
- RegistrarForTagAliases::RegistrarForTagAliases( char const* alias, char const* tag, SourceLineInfo const& lineInfo ) {
- getMutableRegistryHub().registerTagAlias( alias, tag, lineInfo );
- }
-
-} // end namespace Catch
-
-// #included from: catch_matchers_string.hpp
-
-namespace Catch {
-namespace Matchers {
-
- namespace StdString {
-
- CasedString::CasedString( std::string const& str, CaseSensitive::Choice caseSensitivity )
- : m_caseSensitivity( caseSensitivity ),
- m_str( adjustString( str ) )
- {}
- std::string CasedString::adjustString( std::string const& str ) const {
- return m_caseSensitivity == CaseSensitive::No
- ? toLower( str )
- : str;
- }
- std::string CasedString::caseSensitivitySuffix() const {
- return m_caseSensitivity == CaseSensitive::No
- ? " (case insensitive)"
- : std::string();
- }
-
- StringMatcherBase::StringMatcherBase( std::string const& operation, CasedString const& comparator )
- : m_comparator( comparator ),
- m_operation( operation ) {
- }
-
- std::string StringMatcherBase::describe() const {
- std::string description;
- description.reserve(5 + m_operation.size() + m_comparator.m_str.size() +
- m_comparator.caseSensitivitySuffix().size());
- description += m_operation;
- description += ": \"";
- description += m_comparator.m_str;
- description += "\"";
- description += m_comparator.caseSensitivitySuffix();
- return description;
- }
-
- EqualsMatcher::EqualsMatcher( CasedString const& comparator ) : StringMatcherBase( "equals", comparator ) {}
-
- bool EqualsMatcher::match( std::string const& source ) const {
- return m_comparator.adjustString( source ) == m_comparator.m_str;
- }
-
- ContainsMatcher::ContainsMatcher( CasedString const& comparator ) : StringMatcherBase( "contains", comparator ) {}
-
- bool ContainsMatcher::match( std::string const& source ) const {
- return contains( m_comparator.adjustString( source ), m_comparator.m_str );
- }
-
- StartsWithMatcher::StartsWithMatcher( CasedString const& comparator ) : StringMatcherBase( "starts with", comparator ) {}
-
- bool StartsWithMatcher::match( std::string const& source ) const {
- return startsWith( m_comparator.adjustString( source ), m_comparator.m_str );
- }
-
- EndsWithMatcher::EndsWithMatcher( CasedString const& comparator ) : StringMatcherBase( "ends with", comparator ) {}
-
- bool EndsWithMatcher::match( std::string const& source ) const {
- return endsWith( m_comparator.adjustString( source ), m_comparator.m_str );
- }
-
- } // namespace StdString
-
- StdString::EqualsMatcher Equals( std::string const& str, CaseSensitive::Choice caseSensitivity ) {
- return StdString::EqualsMatcher( StdString::CasedString( str, caseSensitivity) );
- }
- StdString::ContainsMatcher Contains( std::string const& str, CaseSensitive::Choice caseSensitivity ) {
- return StdString::ContainsMatcher( StdString::CasedString( str, caseSensitivity) );
- }
- StdString::EndsWithMatcher EndsWith( std::string const& str, CaseSensitive::Choice caseSensitivity ) {
- return StdString::EndsWithMatcher( StdString::CasedString( str, caseSensitivity) );
- }
- StdString::StartsWithMatcher StartsWith( std::string const& str, CaseSensitive::Choice caseSensitivity ) {
- return StdString::StartsWithMatcher( StdString::CasedString( str, caseSensitivity) );
- }
-
-} // namespace Matchers
-} // namespace Catch
-// #included from: ../reporters/catch_reporter_multi.hpp
-#define TWOBLUECUBES_CATCH_REPORTER_MULTI_HPP_INCLUDED
-
-namespace Catch {
-
-class MultipleReporters : public SharedImpl<IStreamingReporter> {
- typedef std::vector<Ptr<IStreamingReporter> > Reporters;
- Reporters m_reporters;
-
-public:
- void add( Ptr<IStreamingReporter> const& reporter ) {
- m_reporters.push_back( reporter );
- }
-
-public: // IStreamingReporter
-
- virtual ReporterPreferences getPreferences() const CATCH_OVERRIDE {
- return m_reporters[0]->getPreferences();
- }
-
- virtual void noMatchingTestCases( std::string const& spec ) CATCH_OVERRIDE {
- for( Reporters::const_iterator it = m_reporters.begin(), itEnd = m_reporters.end();
- it != itEnd;
- ++it )
- (*it)->noMatchingTestCases( spec );
- }
-
- virtual void testRunStarting( TestRunInfo const& testRunInfo ) CATCH_OVERRIDE {
- for( Reporters::const_iterator it = m_reporters.begin(), itEnd = m_reporters.end();
- it != itEnd;
- ++it )
- (*it)->testRunStarting( testRunInfo );
- }
-
- virtual void testGroupStarting( GroupInfo const& groupInfo ) CATCH_OVERRIDE {
- for( Reporters::const_iterator it = m_reporters.begin(), itEnd = m_reporters.end();
- it != itEnd;
- ++it )
- (*it)->testGroupStarting( groupInfo );
- }
-
- virtual void testCaseStarting( TestCaseInfo const& testInfo ) CATCH_OVERRIDE {
- for( Reporters::const_iterator it = m_reporters.begin(), itEnd = m_reporters.end();
- it != itEnd;
- ++it )
- (*it)->testCaseStarting( testInfo );
- }
-
- virtual void sectionStarting( SectionInfo const& sectionInfo ) CATCH_OVERRIDE {
- for( Reporters::const_iterator it = m_reporters.begin(), itEnd = m_reporters.end();
- it != itEnd;
- ++it )
- (*it)->sectionStarting( sectionInfo );
- }
-
- virtual void assertionStarting( AssertionInfo const& assertionInfo ) CATCH_OVERRIDE {
- for( Reporters::const_iterator it = m_reporters.begin(), itEnd = m_reporters.end();
- it != itEnd;
- ++it )
- (*it)->assertionStarting( assertionInfo );
- }
-
- // The return value indicates if the messages buffer should be cleared:
- virtual bool assertionEnded( AssertionStats const& assertionStats ) CATCH_OVERRIDE {
- bool clearBuffer = false;
- for( Reporters::const_iterator it = m_reporters.begin(), itEnd = m_reporters.end();
- it != itEnd;
- ++it )
- clearBuffer |= (*it)->assertionEnded( assertionStats );
- return clearBuffer;
- }
-
- virtual void sectionEnded( SectionStats const& sectionStats ) CATCH_OVERRIDE {
- for( Reporters::const_iterator it = m_reporters.begin(), itEnd = m_reporters.end();
- it != itEnd;
- ++it )
- (*it)->sectionEnded( sectionStats );
- }
-
- virtual void testCaseEnded( TestCaseStats const& testCaseStats ) CATCH_OVERRIDE {
- for( Reporters::const_iterator it = m_reporters.begin(), itEnd = m_reporters.end();
- it != itEnd;
- ++it )
- (*it)->testCaseEnded( testCaseStats );
- }
-
- virtual void testGroupEnded( TestGroupStats const& testGroupStats ) CATCH_OVERRIDE {
- for( Reporters::const_iterator it = m_reporters.begin(), itEnd = m_reporters.end();
- it != itEnd;
- ++it )
- (*it)->testGroupEnded( testGroupStats );
- }
-
- virtual void testRunEnded( TestRunStats const& testRunStats ) CATCH_OVERRIDE {
- for( Reporters::const_iterator it = m_reporters.begin(), itEnd = m_reporters.end();
- it != itEnd;
- ++it )
- (*it)->testRunEnded( testRunStats );
- }
-
- virtual void skipTest( TestCaseInfo const& testInfo ) CATCH_OVERRIDE {
- for( Reporters::const_iterator it = m_reporters.begin(), itEnd = m_reporters.end();
- it != itEnd;
- ++it )
- (*it)->skipTest( testInfo );
- }
-
- virtual MultipleReporters* tryAsMulti() CATCH_OVERRIDE {
- return this;
- }
-
-};
-
-Ptr<IStreamingReporter> addReporter( Ptr<IStreamingReporter> const& existingReporter, Ptr<IStreamingReporter> const& additionalReporter ) {
- Ptr<IStreamingReporter> resultingReporter;
-
- if( existingReporter ) {
- MultipleReporters* multi = existingReporter->tryAsMulti();
- if( !multi ) {
- multi = new MultipleReporters;
- resultingReporter = Ptr<IStreamingReporter>( multi );
- if( existingReporter )
- multi->add( existingReporter );
- }
- else
- resultingReporter = existingReporter;
- multi->add( additionalReporter );
- }
- else
- resultingReporter = additionalReporter;
-
- return resultingReporter;
-}
-
-} // end namespace Catch
-
-// #included from: ../reporters/catch_reporter_xml.hpp
-#define TWOBLUECUBES_CATCH_REPORTER_XML_HPP_INCLUDED
-
-// #included from: catch_reporter_bases.hpp
-#define TWOBLUECUBES_CATCH_REPORTER_BASES_HPP_INCLUDED
-
-#include <cstring>
-#include <cfloat>
-#include <cstdio>
-#include <assert.h>
-
-namespace Catch {
-
- namespace {
- // Because formatting using c++ streams is stateful, drop down to C is required
- // Alternatively we could use stringstream, but its performance is... not good.
- std::string getFormattedDuration( double duration ) {
- // Max exponent + 1 is required to represent the whole part
- // + 1 for decimal point
- // + 3 for the 3 decimal places
- // + 1 for null terminator
- const size_t maxDoubleSize = DBL_MAX_10_EXP + 1 + 1 + 3 + 1;
- char buffer[maxDoubleSize];
-
- // Save previous errno, to prevent sprintf from overwriting it
- ErrnoGuard guard;
-#ifdef _MSC_VER
- sprintf_s(buffer, "%.3f", duration);
-#else
- sprintf(buffer, "%.3f", duration);
-#endif
- return std::string(buffer);
- }
- }
-
- struct StreamingReporterBase : SharedImpl<IStreamingReporter> {
-
- StreamingReporterBase( ReporterConfig const& _config )
- : m_config( _config.fullConfig() ),
- stream( _config.stream() )
- {
- m_reporterPrefs.shouldRedirectStdOut = false;
- }
-
- virtual ReporterPreferences getPreferences() const CATCH_OVERRIDE {
- return m_reporterPrefs;
- }
-
- virtual ~StreamingReporterBase() CATCH_OVERRIDE;
-
- virtual void noMatchingTestCases( std::string const& ) CATCH_OVERRIDE {}
-
- virtual void testRunStarting( TestRunInfo const& _testRunInfo ) CATCH_OVERRIDE {
- currentTestRunInfo = _testRunInfo;
- }
- virtual void testGroupStarting( GroupInfo const& _groupInfo ) CATCH_OVERRIDE {
- currentGroupInfo = _groupInfo;
- }
-
- virtual void testCaseStarting( TestCaseInfo const& _testInfo ) CATCH_OVERRIDE {
- currentTestCaseInfo = _testInfo;
- }
- virtual void sectionStarting( SectionInfo const& _sectionInfo ) CATCH_OVERRIDE {
- m_sectionStack.push_back( _sectionInfo );
- }
-
- virtual void sectionEnded( SectionStats const& /* _sectionStats */ ) CATCH_OVERRIDE {
- m_sectionStack.pop_back();
- }
- virtual void testCaseEnded( TestCaseStats const& /* _testCaseStats */ ) CATCH_OVERRIDE {
- currentTestCaseInfo.reset();
- }
- virtual void testGroupEnded( TestGroupStats const& /* _testGroupStats */ ) CATCH_OVERRIDE {
- currentGroupInfo.reset();
- }
- virtual void testRunEnded( TestRunStats const& /* _testRunStats */ ) CATCH_OVERRIDE {
- currentTestCaseInfo.reset();
- currentGroupInfo.reset();
- currentTestRunInfo.reset();
- }
-
- virtual void skipTest( TestCaseInfo const& ) CATCH_OVERRIDE {
- // Don't do anything with this by default.
- // It can optionally be overridden in the derived class.
- }
-
- Ptr<IConfig const> m_config;
- std::ostream& stream;
-
- LazyStat<TestRunInfo> currentTestRunInfo;
- LazyStat<GroupInfo> currentGroupInfo;
- LazyStat<TestCaseInfo> currentTestCaseInfo;
-
- std::vector<SectionInfo> m_sectionStack;
- ReporterPreferences m_reporterPrefs;
- };
-
- struct CumulativeReporterBase : SharedImpl<IStreamingReporter> {
- template<typename T, typename ChildNodeT>
- struct Node : SharedImpl<> {
- explicit Node( T const& _value ) : value( _value ) {}
- virtual ~Node() {}
-
- typedef std::vector<Ptr<ChildNodeT> > ChildNodes;
- T value;
- ChildNodes children;
- };
- struct SectionNode : SharedImpl<> {
- explicit SectionNode( SectionStats const& _stats ) : stats( _stats ) {}
- virtual ~SectionNode();
-
- bool operator == ( SectionNode const& other ) const {
- return stats.sectionInfo.lineInfo == other.stats.sectionInfo.lineInfo;
- }
- bool operator == ( Ptr<SectionNode> const& other ) const {
- return operator==( *other );
- }
-
- SectionStats stats;
- typedef std::vector<Ptr<SectionNode> > ChildSections;
- typedef std::vector<AssertionStats> Assertions;
- ChildSections childSections;
- Assertions assertions;
- std::string stdOut;
- std::string stdErr;
- };
-
- struct BySectionInfo {
- BySectionInfo( SectionInfo const& other ) : m_other( other ) {}
- BySectionInfo( BySectionInfo const& other ) : m_other( other.m_other ) {}
- bool operator() ( Ptr<SectionNode> const& node ) const {
- return ((node->stats.sectionInfo.name == m_other.name) &&
- (node->stats.sectionInfo.lineInfo == m_other.lineInfo));
- }
- private:
- void operator=( BySectionInfo const& );
- SectionInfo const& m_other;
- };
-
- typedef Node<TestCaseStats, SectionNode> TestCaseNode;
- typedef Node<TestGroupStats, TestCaseNode> TestGroupNode;
- typedef Node<TestRunStats, TestGroupNode> TestRunNode;
-
- CumulativeReporterBase( ReporterConfig const& _config )
- : m_config( _config.fullConfig() ),
- stream( _config.stream() )
- {
- m_reporterPrefs.shouldRedirectStdOut = false;
- }
- ~CumulativeReporterBase();
-
- virtual ReporterPreferences getPreferences() const CATCH_OVERRIDE {
- return m_reporterPrefs;
- }
-
- virtual void testRunStarting( TestRunInfo const& ) CATCH_OVERRIDE {}
- virtual void testGroupStarting( GroupInfo const& ) CATCH_OVERRIDE {}
-
- virtual void testCaseStarting( TestCaseInfo const& ) CATCH_OVERRIDE {}
-
- virtual void sectionStarting( SectionInfo const& sectionInfo ) CATCH_OVERRIDE {
- SectionStats incompleteStats( sectionInfo, Counts(), 0, false );
- Ptr<SectionNode> node;
- if( m_sectionStack.empty() ) {
- if( !m_rootSection )
- m_rootSection = new SectionNode( incompleteStats );
- node = m_rootSection;
- }
- else {
- SectionNode& parentNode = *m_sectionStack.back();
- SectionNode::ChildSections::const_iterator it =
- std::find_if( parentNode.childSections.begin(),
- parentNode.childSections.end(),
- BySectionInfo( sectionInfo ) );
- if( it == parentNode.childSections.end() ) {
- node = new SectionNode( incompleteStats );
- parentNode.childSections.push_back( node );
- }
- else
- node = *it;
- }
- m_sectionStack.push_back( node );
- m_deepestSection = node;
- }
-
- virtual void assertionStarting( AssertionInfo const& ) CATCH_OVERRIDE {}
-
- virtual bool assertionEnded( AssertionStats const& assertionStats ) CATCH_OVERRIDE {
- assert( !m_sectionStack.empty() );
- SectionNode& sectionNode = *m_sectionStack.back();
- sectionNode.assertions.push_back( assertionStats );
- // AssertionResult holds a pointer to a temporary DecomposedExpression,
- // which getExpandedExpression() calls to build the expression string.
- // Our section stack copy of the assertionResult will likely outlive the
- // temporary, so it must be expanded or discarded now to avoid calling
- // a destroyed object later.
- prepareExpandedExpression( sectionNode.assertions.back().assertionResult );
- return true;
- }
- virtual void sectionEnded( SectionStats const& sectionStats ) CATCH_OVERRIDE {
- assert( !m_sectionStack.empty() );
- SectionNode& node = *m_sectionStack.back();
- node.stats = sectionStats;
- m_sectionStack.pop_back();
- }
- virtual void testCaseEnded( TestCaseStats const& testCaseStats ) CATCH_OVERRIDE {
- Ptr<TestCaseNode> node = new TestCaseNode( testCaseStats );
- assert( m_sectionStack.size() == 0 );
- node->children.push_back( m_rootSection );
- m_testCases.push_back( node );
- m_rootSection.reset();
-
- assert( m_deepestSection );
- m_deepestSection->stdOut = testCaseStats.stdOut;
- m_deepestSection->stdErr = testCaseStats.stdErr;
- }
- virtual void testGroupEnded( TestGroupStats const& testGroupStats ) CATCH_OVERRIDE {
- Ptr<TestGroupNode> node = new TestGroupNode( testGroupStats );
- node->children.swap( m_testCases );
- m_testGroups.push_back( node );
- }
- virtual void testRunEnded( TestRunStats const& testRunStats ) CATCH_OVERRIDE {
- Ptr<TestRunNode> node = new TestRunNode( testRunStats );
- node->children.swap( m_testGroups );
- m_testRuns.push_back( node );
- testRunEndedCumulative();
- }
- virtual void testRunEndedCumulative() = 0;
-
- virtual void skipTest( TestCaseInfo const& ) CATCH_OVERRIDE {}
-
- virtual void prepareExpandedExpression( AssertionResult& result ) const {
- if( result.isOk() )
- result.discardDecomposedExpression();
- else
- result.expandDecomposedExpression();
- }
-
- Ptr<IConfig const> m_config;
- std::ostream& stream;
- std::vector<AssertionStats> m_assertions;
- std::vector<std::vector<Ptr<SectionNode> > > m_sections;
- std::vector<Ptr<TestCaseNode> > m_testCases;
- std::vector<Ptr<TestGroupNode> > m_testGroups;
-
- std::vector<Ptr<TestRunNode> > m_testRuns;
-
- Ptr<SectionNode> m_rootSection;
- Ptr<SectionNode> m_deepestSection;
- std::vector<Ptr<SectionNode> > m_sectionStack;
- ReporterPreferences m_reporterPrefs;
-
- };
-
- template<char C>
- char const* getLineOfChars() {
- static char line[CATCH_CONFIG_CONSOLE_WIDTH] = {0};
- if( !*line ) {
- std::memset( line, C, CATCH_CONFIG_CONSOLE_WIDTH-1 );
- line[CATCH_CONFIG_CONSOLE_WIDTH-1] = 0;
- }
- return line;
- }
-
- struct TestEventListenerBase : StreamingReporterBase {
- TestEventListenerBase( ReporterConfig const& _config )
- : StreamingReporterBase( _config )
- {}
-
- virtual void assertionStarting( AssertionInfo const& ) CATCH_OVERRIDE {}
- virtual bool assertionEnded( AssertionStats const& ) CATCH_OVERRIDE {
- return false;
- }
- };
-
-} // end namespace Catch
-
-// #included from: ../internal/catch_reporter_registrars.hpp
-#define TWOBLUECUBES_CATCH_REPORTER_REGISTRARS_HPP_INCLUDED
-
-namespace Catch {
-
- template<typename T>
- class LegacyReporterRegistrar {
-
- class ReporterFactory : public IReporterFactory {
- virtual IStreamingReporter* create( ReporterConfig const& config ) const {
- return new LegacyReporterAdapter( new T( config ) );
- }
-
- virtual std::string getDescription() const {
- return T::getDescription();
- }
- };
-
- public:
-
- LegacyReporterRegistrar( std::string const& name ) {
- getMutableRegistryHub().registerReporter( name, new ReporterFactory() );
- }
- };
-
- template<typename T>
- class ReporterRegistrar {
-
- class ReporterFactory : public SharedImpl<IReporterFactory> {
-
- // *** Please Note ***:
- // - If you end up here looking at a compiler error because it's trying to register
- // your custom reporter class be aware that the native reporter interface has changed
- // to IStreamingReporter. The "legacy" interface, IReporter, is still supported via
- // an adapter. Just use REGISTER_LEGACY_REPORTER to take advantage of the adapter.
- // However please consider updating to the new interface as the old one is now
- // deprecated and will probably be removed quite soon!
- // Please contact me via github if you have any questions at all about this.
- // In fact, ideally, please contact me anyway to let me know you've hit this - as I have
- // no idea who is actually using custom reporters at all (possibly no-one!).
- // The new interface is designed to minimise exposure to interface changes in the future.
- virtual IStreamingReporter* create( ReporterConfig const& config ) const {
- return new T( config );
- }
-
- virtual std::string getDescription() const {
- return T::getDescription();
- }
- };
-
- public:
-
- ReporterRegistrar( std::string const& name ) {
- getMutableRegistryHub().registerReporter( name, new ReporterFactory() );
- }
- };
-
- template<typename T>
- class ListenerRegistrar {
-
- class ListenerFactory : public SharedImpl<IReporterFactory> {
-
- virtual IStreamingReporter* create( ReporterConfig const& config ) const {
- return new T( config );
- }
- virtual std::string getDescription() const {
- return std::string();
- }
- };
-
- public:
-
- ListenerRegistrar() {
- getMutableRegistryHub().registerListener( new ListenerFactory() );
- }
- };
-}
-
-#define INTERNAL_CATCH_REGISTER_LEGACY_REPORTER( name, reporterType ) \
- namespace{ Catch::LegacyReporterRegistrar<reporterType> catch_internal_RegistrarFor##reporterType( name ); }
-
-#define INTERNAL_CATCH_REGISTER_REPORTER( name, reporterType ) \
- namespace{ Catch::ReporterRegistrar<reporterType> catch_internal_RegistrarFor##reporterType( name ); }
-
-// Deprecated - use the form without INTERNAL_
-#define INTERNAL_CATCH_REGISTER_LISTENER( listenerType ) \
- namespace{ Catch::ListenerRegistrar<listenerType> catch_internal_RegistrarFor##listenerType; }
-
-#define CATCH_REGISTER_LISTENER( listenerType ) \
- namespace{ Catch::ListenerRegistrar<listenerType> catch_internal_RegistrarFor##listenerType; }
-
-// #included from: ../internal/catch_xmlwriter.hpp
-#define TWOBLUECUBES_CATCH_XMLWRITER_HPP_INCLUDED
-
-#include <sstream>
-#include <string>
-#include <vector>
-#include <iomanip>
-
-namespace Catch {
-
- class XmlEncode {
- public:
- enum ForWhat { ForTextNodes, ForAttributes };
-
- XmlEncode( std::string const& str, ForWhat forWhat = ForTextNodes )
- : m_str( str ),
- m_forWhat( forWhat )
- {}
-
- void encodeTo( std::ostream& os ) const {
-
- // Apostrophe escaping not necessary if we always use " to write attributes
- // (see: http://www.w3.org/TR/xml/#syntax)
-
- for( std::size_t i = 0; i < m_str.size(); ++ i ) {
- char c = m_str[i];
- switch( c ) {
- case '<': os << "<"; break;
- case '&': os << "&"; break;
-
- case '>':
- // See: http://www.w3.org/TR/xml/#syntax
- if( i > 2 && m_str[i-1] == ']' && m_str[i-2] == ']' )
- os << ">";
- else
- os << c;
- break;
-
- case '\"':
- if( m_forWhat == ForAttributes )
- os << """;
- else
- os << c;
- break;
-
- default:
- // Escape control chars - based on contribution by @espenalb in PR #465 and
- // by @mrpi PR #588
- if ( ( c >= 0 && c < '\x09' ) || ( c > '\x0D' && c < '\x20') || c=='\x7F' ) {
- // see http://stackoverflow.com/questions/404107/why-are-control-characters-illegal-in-xml-1-0
- os << "\\x" << std::uppercase << std::hex << std::setfill('0') << std::setw(2)
- << static_cast<int>( c );
- }
- else
- os << c;
- }
- }
- }
-
- friend std::ostream& operator << ( std::ostream& os, XmlEncode const& xmlEncode ) {
- xmlEncode.encodeTo( os );
- return os;
- }
-
- private:
- std::string m_str;
- ForWhat m_forWhat;
- };
-
- class XmlWriter {
- public:
-
- class ScopedElement {
- public:
- ScopedElement( XmlWriter* writer )
- : m_writer( writer )
- {}
-
- ScopedElement( ScopedElement const& other )
- : m_writer( other.m_writer ){
- other.m_writer = CATCH_NULL;
- }
-
- ~ScopedElement() {
- if( m_writer )
- m_writer->endElement();
- }
-
- ScopedElement& writeText( std::string const& text, bool indent = true ) {
- m_writer->writeText( text, indent );
- return *this;
- }
-
- template<typename T>
- ScopedElement& writeAttribute( std::string const& name, T const& attribute ) {
- m_writer->writeAttribute( name, attribute );
- return *this;
- }
-
- private:
- mutable XmlWriter* m_writer;
- };
-
- XmlWriter()
- : m_tagIsOpen( false ),
- m_needsNewline( false ),
- m_os( Catch::cout() )
- {
- writeDeclaration();
- }
-
- XmlWriter( std::ostream& os )
- : m_tagIsOpen( false ),
- m_needsNewline( false ),
- m_os( os )
- {
- writeDeclaration();
- }
-
- ~XmlWriter() {
- while( !m_tags.empty() )
- endElement();
- }
-
- XmlWriter& startElement( std::string const& name ) {
- ensureTagClosed();
- newlineIfNecessary();
- m_os << m_indent << '<' << name;
- m_tags.push_back( name );
- m_indent += " ";
- m_tagIsOpen = true;
- return *this;
- }
-
- ScopedElement scopedElement( std::string const& name ) {
- ScopedElement scoped( this );
- startElement( name );
- return scoped;
- }
-
- XmlWriter& endElement() {
- newlineIfNecessary();
- m_indent = m_indent.substr( 0, m_indent.size()-2 );
- if( m_tagIsOpen ) {
- m_os << "/>";
- m_tagIsOpen = false;
- }
- else {
- m_os << m_indent << "</" << m_tags.back() << ">";
- }
- m_os << std::endl;
- m_tags.pop_back();
- return *this;
- }
-
- XmlWriter& writeAttribute( std::string const& name, std::string const& attribute ) {
- if( !name.empty() && !attribute.empty() )
- m_os << ' ' << name << "=\"" << XmlEncode( attribute, XmlEncode::ForAttributes ) << '"';
- return *this;
- }
-
- XmlWriter& writeAttribute( std::string const& name, bool attribute ) {
- m_os << ' ' << name << "=\"" << ( attribute ? "true" : "false" ) << '"';
- return *this;
- }
-
- template<typename T>
- XmlWriter& writeAttribute( std::string const& name, T const& attribute ) {
- std::ostringstream oss;
- oss << attribute;
- return writeAttribute( name, oss.str() );
- }
-
- XmlWriter& writeText( std::string const& text, bool indent = true ) {
- if( !text.empty() ){
- bool tagWasOpen = m_tagIsOpen;
- ensureTagClosed();
- if( tagWasOpen && indent )
- m_os << m_indent;
- m_os << XmlEncode( text );
- m_needsNewline = true;
- }
- return *this;
- }
-
- XmlWriter& writeComment( std::string const& text ) {
- ensureTagClosed();
- m_os << m_indent << "<!--" << text << "-->";
- m_needsNewline = true;
- return *this;
- }
-
- void writeStylesheetRef( std::string const& url ) {
- m_os << "<?xml-stylesheet type=\"text/xsl\" href=\"" << url << "\"?>\n";
- }
-
- XmlWriter& writeBlankLine() {
- ensureTagClosed();
- m_os << '\n';
- return *this;
- }
-
- void ensureTagClosed() {
- if( m_tagIsOpen ) {
- m_os << ">" << std::endl;
- m_tagIsOpen = false;
- }
- }
-
- private:
- XmlWriter( XmlWriter const& );
- void operator=( XmlWriter const& );
-
- void writeDeclaration() {
- m_os << "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n";
- }
-
- void newlineIfNecessary() {
- if( m_needsNewline ) {
- m_os << std::endl;
- m_needsNewline = false;
- }
- }
-
- bool m_tagIsOpen;
- bool m_needsNewline;
- std::vector<std::string> m_tags;
- std::string m_indent;
- std::ostream& m_os;
- };
-
-}
-
-namespace Catch {
- class XmlReporter : public StreamingReporterBase {
- public:
- XmlReporter( ReporterConfig const& _config )
- : StreamingReporterBase( _config ),
- m_xml(_config.stream()),
- m_sectionDepth( 0 )
- {
- m_reporterPrefs.shouldRedirectStdOut = true;
- }
-
- virtual ~XmlReporter() CATCH_OVERRIDE;
-
- static std::string getDescription() {
- return "Reports test results as an XML document";
- }
-
- virtual std::string getStylesheetRef() const {
- return std::string();
- }
-
- void writeSourceInfo( SourceLineInfo const& sourceInfo ) {
- m_xml
- .writeAttribute( "filename", sourceInfo.file )
- .writeAttribute( "line", sourceInfo.line );
- }
-
- public: // StreamingReporterBase
-
- virtual void noMatchingTestCases( std::string const& s ) CATCH_OVERRIDE {
- StreamingReporterBase::noMatchingTestCases( s );
- }
-
- virtual void testRunStarting( TestRunInfo const& testInfo ) CATCH_OVERRIDE {
- StreamingReporterBase::testRunStarting( testInfo );
- std::string stylesheetRef = getStylesheetRef();
- if( !stylesheetRef.empty() )
- m_xml.writeStylesheetRef( stylesheetRef );
- m_xml.startElement( "Catch" );
- if( !m_config->name().empty() )
- m_xml.writeAttribute( "name", m_config->name() );
- }
-
- virtual void testGroupStarting( GroupInfo const& groupInfo ) CATCH_OVERRIDE {
- StreamingReporterBase::testGroupStarting( groupInfo );
- m_xml.startElement( "Group" )
- .writeAttribute( "name", groupInfo.name );
- }
-
- virtual void testCaseStarting( TestCaseInfo const& testInfo ) CATCH_OVERRIDE {
- StreamingReporterBase::testCaseStarting(testInfo);
- m_xml.startElement( "TestCase" )
- .writeAttribute( "name", trim( testInfo.name ) )
- .writeAttribute( "description", testInfo.description )
- .writeAttribute( "tags", testInfo.tagsAsString );
-
- writeSourceInfo( testInfo.lineInfo );
-
- if ( m_config->showDurations() == ShowDurations::Always )
- m_testCaseTimer.start();
- m_xml.ensureTagClosed();
- }
-
- virtual void sectionStarting( SectionInfo const& sectionInfo ) CATCH_OVERRIDE {
- StreamingReporterBase::sectionStarting( sectionInfo );
- if( m_sectionDepth++ > 0 ) {
- m_xml.startElement( "Section" )
- .writeAttribute( "name", trim( sectionInfo.name ) )
- .writeAttribute( "description", sectionInfo.description );
- writeSourceInfo( sectionInfo.lineInfo );
- m_xml.ensureTagClosed();
- }
- }
-
- virtual void assertionStarting( AssertionInfo const& ) CATCH_OVERRIDE { }
-
- virtual bool assertionEnded( AssertionStats const& assertionStats ) CATCH_OVERRIDE {
-
- AssertionResult const& result = assertionStats.assertionResult;
-
- bool includeResults = m_config->includeSuccessfulResults() || !result.isOk();
-
- if( includeResults || result.getResultType() == ResultWas::Warning ) {
- // Print any info messages in <Info> tags.
- for( std::vector<MessageInfo>::const_iterator it = assertionStats.infoMessages.begin(), itEnd = assertionStats.infoMessages.end();
- it != itEnd;
- ++it ) {
- if( it->type == ResultWas::Info && includeResults ) {
- m_xml.scopedElement( "Info" )
- .writeText( it->message );
- } else if ( it->type == ResultWas::Warning ) {
- m_xml.scopedElement( "Warning" )
- .writeText( it->message );
- }
- }
- }
-
- // Drop out if result was successful but we're not printing them.
- if( !includeResults && result.getResultType() != ResultWas::Warning )
- return true;
-
- // Print the expression if there is one.
- if( result.hasExpression() ) {
- m_xml.startElement( "Expression" )
- .writeAttribute( "success", result.succeeded() )
- .writeAttribute( "type", result.getTestMacroName() );
-
- writeSourceInfo( result.getSourceInfo() );
-
- m_xml.scopedElement( "Original" )
- .writeText( result.getExpression() );
- m_xml.scopedElement( "Expanded" )
- .writeText( result.getExpandedExpression() );
- }
-
- // And... Print a result applicable to each result type.
- switch( result.getResultType() ) {
- case ResultWas::ThrewException:
- m_xml.startElement( "Exception" );
- writeSourceInfo( result.getSourceInfo() );
- m_xml.writeText( result.getMessage() );
- m_xml.endElement();
- break;
- case ResultWas::FatalErrorCondition:
- m_xml.startElement( "FatalErrorCondition" );
- writeSourceInfo( result.getSourceInfo() );
- m_xml.writeText( result.getMessage() );
- m_xml.endElement();
- break;
- case ResultWas::Info:
- m_xml.scopedElement( "Info" )
- .writeText( result.getMessage() );
- break;
- case ResultWas::Warning:
- // Warning will already have been written
- break;
- case ResultWas::ExplicitFailure:
- m_xml.startElement( "Failure" );
- writeSourceInfo( result.getSourceInfo() );
- m_xml.writeText( result.getMessage() );
- m_xml.endElement();
- break;
- default:
- break;
- }
-
- if( result.hasExpression() )
- m_xml.endElement();
-
- return true;
- }
-
- virtual void sectionEnded( SectionStats const& sectionStats ) CATCH_OVERRIDE {
- StreamingReporterBase::sectionEnded( sectionStats );
- if( --m_sectionDepth > 0 ) {
- XmlWriter::ScopedElement e = m_xml.scopedElement( "OverallResults" );
- e.writeAttribute( "successes", sectionStats.assertions.passed );
- e.writeAttribute( "failures", sectionStats.assertions.failed );
- e.writeAttribute( "expectedFailures", sectionStats.assertions.failedButOk );
-
- if ( m_config->showDurations() == ShowDurations::Always )
- e.writeAttribute( "durationInSeconds", sectionStats.durationInSeconds );
-
- m_xml.endElement();
- }
- }
-
- virtual void testCaseEnded( TestCaseStats const& testCaseStats ) CATCH_OVERRIDE {
- StreamingReporterBase::testCaseEnded( testCaseStats );
- XmlWriter::ScopedElement e = m_xml.scopedElement( "OverallResult" );
- e.writeAttribute( "success", testCaseStats.totals.assertions.allOk() );
-
- if ( m_config->showDurations() == ShowDurations::Always )
- e.writeAttribute( "durationInSeconds", m_testCaseTimer.getElapsedSeconds() );
-
- if( !testCaseStats.stdOut.empty() )
- m_xml.scopedElement( "StdOut" ).writeText( trim( testCaseStats.stdOut ), false );
- if( !testCaseStats.stdErr.empty() )
- m_xml.scopedElement( "StdErr" ).writeText( trim( testCaseStats.stdErr ), false );
-
- m_xml.endElement();
- }
-
- virtual void testGroupEnded( TestGroupStats const& testGroupStats ) CATCH_OVERRIDE {
- StreamingReporterBase::testGroupEnded( testGroupStats );
- // TODO: Check testGroupStats.aborting and act accordingly.
- m_xml.scopedElement( "OverallResults" )
- .writeAttribute( "successes", testGroupStats.totals.assertions.passed )
- .writeAttribute( "failures", testGroupStats.totals.assertions.failed )
- .writeAttribute( "expectedFailures", testGroupStats.totals.assertions.failedButOk );
- m_xml.endElement();
- }
-
- virtual void testRunEnded( TestRunStats const& testRunStats ) CATCH_OVERRIDE {
- StreamingReporterBase::testRunEnded( testRunStats );
- m_xml.scopedElement( "OverallResults" )
- .writeAttribute( "successes", testRunStats.totals.assertions.passed )
- .writeAttribute( "failures", testRunStats.totals.assertions.failed )
- .writeAttribute( "expectedFailures", testRunStats.totals.assertions.failedButOk );
- m_xml.endElement();
- }
-
- private:
- Timer m_testCaseTimer;
- XmlWriter m_xml;
- int m_sectionDepth;
- };
-
- INTERNAL_CATCH_REGISTER_REPORTER( "xml", XmlReporter )
-
-} // end namespace Catch
-
-// #included from: ../reporters/catch_reporter_junit.hpp
-#define TWOBLUECUBES_CATCH_REPORTER_JUNIT_HPP_INCLUDED
-
-#include <assert.h>
-
-namespace Catch {
-
- namespace {
- std::string getCurrentTimestamp() {
- // Beware, this is not reentrant because of backward compatibility issues
- // Also, UTC only, again because of backward compatibility (%z is C++11)
- time_t rawtime;
- std::time(&rawtime);
- const size_t timeStampSize = sizeof("2017-01-16T17:06:45Z");
-
-#ifdef _MSC_VER
- std::tm timeInfo = {};
- gmtime_s(&timeInfo, &rawtime);
-#else
- std::tm* timeInfo;
- timeInfo = std::gmtime(&rawtime);
-#endif
-
- char timeStamp[timeStampSize];
- const char * const fmt = "%Y-%m-%dT%H:%M:%SZ";
-
-#ifdef _MSC_VER
- std::strftime(timeStamp, timeStampSize, fmt, &timeInfo);
-#else
- std::strftime(timeStamp, timeStampSize, fmt, timeInfo);
-#endif
- return std::string(timeStamp);
- }
-
- }
-
- class JunitReporter : public CumulativeReporterBase {
- public:
- JunitReporter( ReporterConfig const& _config )
- : CumulativeReporterBase( _config ),
- xml( _config.stream() ),
- unexpectedExceptions( 0 ),
- m_okToFail( false )
- {
- m_reporterPrefs.shouldRedirectStdOut = true;
- }
-
- virtual ~JunitReporter() CATCH_OVERRIDE;
-
- static std::string getDescription() {
- return "Reports test results in an XML format that looks like Ant's junitreport target";
- }
-
- virtual void noMatchingTestCases( std::string const& /*spec*/ ) CATCH_OVERRIDE {}
-
- virtual void testRunStarting( TestRunInfo const& runInfo ) CATCH_OVERRIDE {
- CumulativeReporterBase::testRunStarting( runInfo );
- xml.startElement( "testsuites" );
- }
-
- virtual void testGroupStarting( GroupInfo const& groupInfo ) CATCH_OVERRIDE {
- suiteTimer.start();
- stdOutForSuite.str("");
- stdErrForSuite.str("");
- unexpectedExceptions = 0;
- CumulativeReporterBase::testGroupStarting( groupInfo );
- }
-
- virtual void testCaseStarting( TestCaseInfo const& testCaseInfo ) CATCH_OVERRIDE {
- m_okToFail = testCaseInfo.okToFail();
- }
- virtual bool assertionEnded( AssertionStats const& assertionStats ) CATCH_OVERRIDE {
- if( assertionStats.assertionResult.getResultType() == ResultWas::ThrewException && !m_okToFail )
- unexpectedExceptions++;
- return CumulativeReporterBase::assertionEnded( assertionStats );
- }
-
- virtual void testCaseEnded( TestCaseStats const& testCaseStats ) CATCH_OVERRIDE {
- stdOutForSuite << testCaseStats.stdOut;
- stdErrForSuite << testCaseStats.stdErr;
- CumulativeReporterBase::testCaseEnded( testCaseStats );
- }
-
- virtual void testGroupEnded( TestGroupStats const& testGroupStats ) CATCH_OVERRIDE {
- double suiteTime = suiteTimer.getElapsedSeconds();
- CumulativeReporterBase::testGroupEnded( testGroupStats );
- writeGroup( *m_testGroups.back(), suiteTime );
- }
-
- virtual void testRunEndedCumulative() CATCH_OVERRIDE {
- xml.endElement();
- }
-
- void writeGroup( TestGroupNode const& groupNode, double suiteTime ) {
- XmlWriter::ScopedElement e = xml.scopedElement( "testsuite" );
- TestGroupStats const& stats = groupNode.value;
- xml.writeAttribute( "name", stats.groupInfo.name );
- xml.writeAttribute( "errors", unexpectedExceptions );
- xml.writeAttribute( "failures", stats.totals.assertions.failed-unexpectedExceptions );
- xml.writeAttribute( "tests", stats.totals.assertions.total() );
- xml.writeAttribute( "hostname", "tbd" ); // !TBD
- if( m_config->showDurations() == ShowDurations::Never )
- xml.writeAttribute( "time", "" );
- else
- xml.writeAttribute( "time", suiteTime );
- xml.writeAttribute( "timestamp", getCurrentTimestamp() );
-
- // Write test cases
- for( TestGroupNode::ChildNodes::const_iterator
- it = groupNode.children.begin(), itEnd = groupNode.children.end();
- it != itEnd;
- ++it )
- writeTestCase( **it );
-
- xml.scopedElement( "system-out" ).writeText( trim( stdOutForSuite.str() ), false );
- xml.scopedElement( "system-err" ).writeText( trim( stdErrForSuite.str() ), false );
- }
-
- void writeTestCase( TestCaseNode const& testCaseNode ) {
- TestCaseStats const& stats = testCaseNode.value;
-
- // All test cases have exactly one section - which represents the
- // test case itself. That section may have 0-n nested sections
- assert( testCaseNode.children.size() == 1 );
- SectionNode const& rootSection = *testCaseNode.children.front();
-
- std::string className = stats.testInfo.className;
-
- if( className.empty() ) {
- if( rootSection.childSections.empty() )
- className = "global";
- }
- writeSection( className, "", rootSection );
- }
-
- void writeSection( std::string const& className,
- std::string const& rootName,
- SectionNode const& sectionNode ) {
- std::string name = trim( sectionNode.stats.sectionInfo.name );
- if( !rootName.empty() )
- name = rootName + '/' + name;
-
- if( !sectionNode.assertions.empty() ||
- !sectionNode.stdOut.empty() ||
- !sectionNode.stdErr.empty() ) {
- XmlWriter::ScopedElement e = xml.scopedElement( "testcase" );
- if( className.empty() ) {
- xml.writeAttribute( "classname", name );
- xml.writeAttribute( "name", "root" );
- }
- else {
- xml.writeAttribute( "classname", className );
- xml.writeAttribute( "name", name );
- }
- xml.writeAttribute( "time", Catch::toString( sectionNode.stats.durationInSeconds ) );
-
- writeAssertions( sectionNode );
-
- if( !sectionNode.stdOut.empty() )
- xml.scopedElement( "system-out" ).writeText( trim( sectionNode.stdOut ), false );
- if( !sectionNode.stdErr.empty() )
- xml.scopedElement( "system-err" ).writeText( trim( sectionNode.stdErr ), false );
- }
- for( SectionNode::ChildSections::const_iterator
- it = sectionNode.childSections.begin(),
- itEnd = sectionNode.childSections.end();
- it != itEnd;
- ++it )
- if( className.empty() )
- writeSection( name, "", **it );
- else
- writeSection( className, name, **it );
- }
-
- void writeAssertions( SectionNode const& sectionNode ) {
- for( SectionNode::Assertions::const_iterator
- it = sectionNode.assertions.begin(), itEnd = sectionNode.assertions.end();
- it != itEnd;
- ++it )
- writeAssertion( *it );
- }
- void writeAssertion( AssertionStats const& stats ) {
- AssertionResult const& result = stats.assertionResult;
- if( !result.isOk() ) {
- std::string elementName;
- switch( result.getResultType() ) {
- case ResultWas::ThrewException:
- case ResultWas::FatalErrorCondition:
- elementName = "error";
- break;
- case ResultWas::ExplicitFailure:
- elementName = "failure";
- break;
- case ResultWas::ExpressionFailed:
- elementName = "failure";
- break;
- case ResultWas::DidntThrowException:
- elementName = "failure";
- break;
-
- // We should never see these here:
- case ResultWas::Info:
- case ResultWas::Warning:
- case ResultWas::Ok:
- case ResultWas::Unknown:
- case ResultWas::FailureBit:
- case ResultWas::Exception:
- elementName = "internalError";
- break;
- }
-
- XmlWriter::ScopedElement e = xml.scopedElement( elementName );
-
- xml.writeAttribute( "message", result.getExpandedExpression() );
- xml.writeAttribute( "type", result.getTestMacroName() );
-
- std::ostringstream oss;
- if( !result.getMessage().empty() )
- oss << result.getMessage() << '\n';
- for( std::vector<MessageInfo>::const_iterator
- it = stats.infoMessages.begin(),
- itEnd = stats.infoMessages.end();
- it != itEnd;
- ++it )
- if( it->type == ResultWas::Info )
- oss << it->message << '\n';
-
- oss << "at " << result.getSourceInfo();
- xml.writeText( oss.str(), false );
- }
- }
-
- XmlWriter xml;
- Timer suiteTimer;
- std::ostringstream stdOutForSuite;
- std::ostringstream stdErrForSuite;
- unsigned int unexpectedExceptions;
- bool m_okToFail;
- };
-
- INTERNAL_CATCH_REGISTER_REPORTER( "junit", JunitReporter )
-
-} // end namespace Catch
-
-// #included from: ../reporters/catch_reporter_console.hpp
-#define TWOBLUECUBES_CATCH_REPORTER_CONSOLE_HPP_INCLUDED
-
-#include <cassert>
-#include <cfloat>
-#include <cstdio>
-
-namespace Catch {
-
- struct ConsoleReporter : StreamingReporterBase {
- ConsoleReporter( ReporterConfig const& _config )
- : StreamingReporterBase( _config ),
- m_headerPrinted( false )
- {}
-
- virtual ~ConsoleReporter() CATCH_OVERRIDE;
- static std::string getDescription() {
- return "Reports test results as plain lines of text";
- }
-
- virtual void noMatchingTestCases( std::string const& spec ) CATCH_OVERRIDE {
- stream << "No test cases matched '" << spec << '\'' << std::endl;
- }
-
- virtual void assertionStarting( AssertionInfo const& ) CATCH_OVERRIDE {
- }
-
- virtual bool assertionEnded( AssertionStats const& _assertionStats ) CATCH_OVERRIDE {
- AssertionResult const& result = _assertionStats.assertionResult;
-
- bool includeResults = m_config->includeSuccessfulResults() || !result.isOk();
-
- // Drop out if result was successful but we're not printing them.
- if( !includeResults && result.getResultType() != ResultWas::Warning )
- return false;
-
- lazyPrint();
-
- AssertionPrinter printer( stream, _assertionStats, includeResults );
- printer.print();
- stream << std::endl;
- return true;
- }
-
- virtual void sectionStarting( SectionInfo const& _sectionInfo ) CATCH_OVERRIDE {
- m_headerPrinted = false;
- StreamingReporterBase::sectionStarting( _sectionInfo );
- }
- virtual void sectionEnded( SectionStats const& _sectionStats ) CATCH_OVERRIDE {
- if( _sectionStats.missingAssertions ) {
- lazyPrint();
- Colour colour( Colour::ResultError );
- if( m_sectionStack.size() > 1 )
- stream << "\nNo assertions in section";
- else
- stream << "\nNo assertions in test case";
- stream << " '" << _sectionStats.sectionInfo.name << "'\n" << std::endl;
- }
- if( m_config->showDurations() == ShowDurations::Always ) {
- stream << getFormattedDuration(_sectionStats.durationInSeconds) << " s: " << _sectionStats.sectionInfo.name << std::endl;
- }
- if( m_headerPrinted ) {
- m_headerPrinted = false;
- }
- StreamingReporterBase::sectionEnded( _sectionStats );
- }
-
- virtual void testCaseEnded( TestCaseStats const& _testCaseStats ) CATCH_OVERRIDE {
- StreamingReporterBase::testCaseEnded( _testCaseStats );
- m_headerPrinted = false;
- }
- virtual void testGroupEnded( TestGroupStats const& _testGroupStats ) CATCH_OVERRIDE {
- if( currentGroupInfo.used ) {
- printSummaryDivider();
- stream << "Summary for group '" << _testGroupStats.groupInfo.name << "':\n";
- printTotals( _testGroupStats.totals );
- stream << '\n' << std::endl;
- }
- StreamingReporterBase::testGroupEnded( _testGroupStats );
- }
- virtual void testRunEnded( TestRunStats const& _testRunStats ) CATCH_OVERRIDE {
- printTotalsDivider( _testRunStats.totals );
- printTotals( _testRunStats.totals );
- stream << std::endl;
- StreamingReporterBase::testRunEnded( _testRunStats );
- }
-
- private:
-
- class AssertionPrinter {
- void operator= ( AssertionPrinter const& );
- public:
- AssertionPrinter( std::ostream& _stream, AssertionStats const& _stats, bool _printInfoMessages )
- : stream( _stream ),
- stats( _stats ),
- result( _stats.assertionResult ),
- colour( Colour::None ),
- message( result.getMessage() ),
- messages( _stats.infoMessages ),
- printInfoMessages( _printInfoMessages )
- {
- switch( result.getResultType() ) {
- case ResultWas::Ok:
- colour = Colour::Success;
- passOrFail = "PASSED";
- //if( result.hasMessage() )
- if( _stats.infoMessages.size() == 1 )
- messageLabel = "with message";
- if( _stats.infoMessages.size() > 1 )
- messageLabel = "with messages";
- break;
- case ResultWas::ExpressionFailed:
- if( result.isOk() ) {
- colour = Colour::Success;
- passOrFail = "FAILED - but was ok";
- }
- else {
- colour = Colour::Error;
- passOrFail = "FAILED";
- }
- if( _stats.infoMessages.size() == 1 )
- messageLabel = "with message";
- if( _stats.infoMessages.size() > 1 )
- messageLabel = "with messages";
- break;
- case ResultWas::ThrewException:
- colour = Colour::Error;
- passOrFail = "FAILED";
- messageLabel = "due to unexpected exception with ";
- if (_stats.infoMessages.size() == 1)
- messageLabel += "message";
- if (_stats.infoMessages.size() > 1)
- messageLabel += "messages";
- break;
- case ResultWas::FatalErrorCondition:
- colour = Colour::Error;
- passOrFail = "FAILED";
- messageLabel = "due to a fatal error condition";
- break;
- case ResultWas::DidntThrowException:
- colour = Colour::Error;
- passOrFail = "FAILED";
- messageLabel = "because no exception was thrown where one was expected";
- break;
- case ResultWas::Info:
- messageLabel = "info";
- break;
- case ResultWas::Warning:
- messageLabel = "warning";
- break;
- case ResultWas::ExplicitFailure:
- passOrFail = "FAILED";
- colour = Colour::Error;
- if( _stats.infoMessages.size() == 1 )
- messageLabel = "explicitly with message";
- if( _stats.infoMessages.size() > 1 )
- messageLabel = "explicitly with messages";
- break;
- // These cases are here to prevent compiler warnings
- case ResultWas::Unknown:
- case ResultWas::FailureBit:
- case ResultWas::Exception:
- passOrFail = "** internal error **";
- colour = Colour::Error;
- break;
- }
- }
-
- void print() const {
- printSourceInfo();
- if( stats.totals.assertions.total() > 0 ) {
- if( result.isOk() )
- stream << '\n';
- printResultType();
- printOriginalExpression();
- printReconstructedExpression();
- }
- else {
- stream << '\n';
- }
- printMessage();
- }
-
- private:
- void printResultType() const {
- if( !passOrFail.empty() ) {
- Colour colourGuard( colour );
- stream << passOrFail << ":\n";
- }
- }
- void printOriginalExpression() const {
- if( result.hasExpression() ) {
- Colour colourGuard( Colour::OriginalExpression );
- stream << " ";
- stream << result.getExpressionInMacro();
- stream << '\n';
- }
- }
- void printReconstructedExpression() const {
- if( result.hasExpandedExpression() ) {
- stream << "with expansion:\n";
- Colour colourGuard( Colour::ReconstructedExpression );
- stream << Text( result.getExpandedExpression(), TextAttributes().setIndent(2) ) << '\n';
- }
- }
- void printMessage() const {
- if( !messageLabel.empty() )
- stream << messageLabel << ':' << '\n';
- for( std::vector<MessageInfo>::const_iterator it = messages.begin(), itEnd = messages.end();
- it != itEnd;
- ++it ) {
- // If this assertion is a warning ignore any INFO messages
- if( printInfoMessages || it->type != ResultWas::Info )
- stream << Text( it->message, TextAttributes().setIndent(2) ) << '\n';
- }
- }
- void printSourceInfo() const {
- Colour colourGuard( Colour::FileName );
- stream << result.getSourceInfo() << ": ";
- }
-
- std::ostream& stream;
- AssertionStats const& stats;
- AssertionResult const& result;
- Colour::Code colour;
- std::string passOrFail;
- std::string messageLabel;
- std::string message;
- std::vector<MessageInfo> messages;
- bool printInfoMessages;
- };
-
- void lazyPrint() {
-
- if( !currentTestRunInfo.used )
- lazyPrintRunInfo();
- if( !currentGroupInfo.used )
- lazyPrintGroupInfo();
-
- if( !m_headerPrinted ) {
- printTestCaseAndSectionHeader();
- m_headerPrinted = true;
- }
- }
- void lazyPrintRunInfo() {
- stream << '\n' << getLineOfChars<'~'>() << '\n';
- Colour colour( Colour::SecondaryText );
- stream << currentTestRunInfo->name
- << " is a Catch v" << libraryVersion() << " host application.\n"
- << "Run with -? for options\n\n";
-
- if( m_config->rngSeed() != 0 )
- stream << "Randomness seeded to: " << m_config->rngSeed() << "\n\n";
-
- currentTestRunInfo.used = true;
- }
- void lazyPrintGroupInfo() {
- if( !currentGroupInfo->name.empty() && currentGroupInfo->groupsCounts > 1 ) {
- printClosedHeader( "Group: " + currentGroupInfo->name );
- currentGroupInfo.used = true;
- }
- }
- void printTestCaseAndSectionHeader() {
- assert( !m_sectionStack.empty() );
- printOpenHeader( currentTestCaseInfo->name );
-
- if( m_sectionStack.size() > 1 ) {
- Colour colourGuard( Colour::Headers );
-
- std::vector<SectionInfo>::const_iterator
- it = m_sectionStack.begin()+1, // Skip first section (test case)
- itEnd = m_sectionStack.end();
- for( ; it != itEnd; ++it )
- printHeaderString( it->name, 2 );
- }
-
- SourceLineInfo lineInfo = m_sectionStack.back().lineInfo;
-
- if( !lineInfo.empty() ){
- stream << getLineOfChars<'-'>() << '\n';
- Colour colourGuard( Colour::FileName );
- stream << lineInfo << '\n';
- }
- stream << getLineOfChars<'.'>() << '\n' << std::endl;
- }
-
- void printClosedHeader( std::string const& _name ) {
- printOpenHeader( _name );
- stream << getLineOfChars<'.'>() << '\n';
- }
- void printOpenHeader( std::string const& _name ) {
- stream << getLineOfChars<'-'>() << '\n';
- {
- Colour colourGuard( Colour::Headers );
- printHeaderString( _name );
- }
- }
-
- // if string has a : in first line will set indent to follow it on
- // subsequent lines
- void printHeaderString( std::string const& _string, std::size_t indent = 0 ) {
- std::size_t i = _string.find( ": " );
- if( i != std::string::npos )
- i+=2;
- else
- i = 0;
- stream << Text( _string, TextAttributes()
- .setIndent( indent+i)
- .setInitialIndent( indent ) ) << '\n';
- }
-
- struct SummaryColumn {
-
- SummaryColumn( std::string const& _label, Colour::Code _colour )
- : label( _label ),
- colour( _colour )
- {}
- SummaryColumn addRow( std::size_t count ) {
- std::ostringstream oss;
- oss << count;
- std::string row = oss.str();
- for( std::vector<std::string>::iterator it = rows.begin(); it != rows.end(); ++it ) {
- while( it->size() < row.size() )
- *it = ' ' + *it;
- while( it->size() > row.size() )
- row = ' ' + row;
- }
- rows.push_back( row );
- return *this;
- }
-
- std::string label;
- Colour::Code colour;
- std::vector<std::string> rows;
-
- };
-
- void printTotals( Totals const& totals ) {
- if( totals.testCases.total() == 0 ) {
- stream << Colour( Colour::Warning ) << "No tests ran\n";
- }
- else if( totals.assertions.total() > 0 && totals.testCases.allPassed() ) {
- stream << Colour( Colour::ResultSuccess ) << "All tests passed";
- stream << " ("
- << pluralise( totals.assertions.passed, "assertion" ) << " in "
- << pluralise( totals.testCases.passed, "test case" ) << ')'
- << '\n';
- }
- else {
-
- std::vector<SummaryColumn> columns;
- columns.push_back( SummaryColumn( "", Colour::None )
- .addRow( totals.testCases.total() )
- .addRow( totals.assertions.total() ) );
- columns.push_back( SummaryColumn( "passed", Colour::Success )
- .addRow( totals.testCases.passed )
- .addRow( totals.assertions.passed ) );
- columns.push_back( SummaryColumn( "failed", Colour::ResultError )
- .addRow( totals.testCases.failed )
- .addRow( totals.assertions.failed ) );
- columns.push_back( SummaryColumn( "failed as expected", Colour::ResultExpectedFailure )
- .addRow( totals.testCases.failedButOk )
- .addRow( totals.assertions.failedButOk ) );
-
- printSummaryRow( "test cases", columns, 0 );
- printSummaryRow( "assertions", columns, 1 );
- }
- }
- void printSummaryRow( std::string const& label, std::vector<SummaryColumn> const& cols, std::size_t row ) {
- for( std::vector<SummaryColumn>::const_iterator it = cols.begin(); it != cols.end(); ++it ) {
- std::string value = it->rows[row];
- if( it->label.empty() ) {
- stream << label << ": ";
- if( value != "0" )
- stream << value;
- else
- stream << Colour( Colour::Warning ) << "- none -";
- }
- else if( value != "0" ) {
- stream << Colour( Colour::LightGrey ) << " | ";
- stream << Colour( it->colour )
- << value << ' ' << it->label;
- }
- }
- stream << '\n';
- }
-
- static std::size_t makeRatio( std::size_t number, std::size_t total ) {
- std::size_t ratio = total > 0 ? CATCH_CONFIG_CONSOLE_WIDTH * number/ total : 0;
- return ( ratio == 0 && number > 0 ) ? 1 : ratio;
- }
- static std::size_t& findMax( std::size_t& i, std::size_t& j, std::size_t& k ) {
- if( i > j && i > k )
- return i;
- else if( j > k )
- return j;
- else
- return k;
- }
-
- void printTotalsDivider( Totals const& totals ) {
- if( totals.testCases.total() > 0 ) {
- std::size_t failedRatio = makeRatio( totals.testCases.failed, totals.testCases.total() );
- std::size_t failedButOkRatio = makeRatio( totals.testCases.failedButOk, totals.testCases.total() );
- std::size_t passedRatio = makeRatio( totals.testCases.passed, totals.testCases.total() );
- while( failedRatio + failedButOkRatio + passedRatio < CATCH_CONFIG_CONSOLE_WIDTH-1 )
- findMax( failedRatio, failedButOkRatio, passedRatio )++;
- while( failedRatio + failedButOkRatio + passedRatio > CATCH_CONFIG_CONSOLE_WIDTH-1 )
- findMax( failedRatio, failedButOkRatio, passedRatio )--;
-
- stream << Colour( Colour::Error ) << std::string( failedRatio, '=' );
- stream << Colour( Colour::ResultExpectedFailure ) << std::string( failedButOkRatio, '=' );
- if( totals.testCases.allPassed() )
- stream << Colour( Colour::ResultSuccess ) << std::string( passedRatio, '=' );
- else
- stream << Colour( Colour::Success ) << std::string( passedRatio, '=' );
- }
- else {
- stream << Colour( Colour::Warning ) << std::string( CATCH_CONFIG_CONSOLE_WIDTH-1, '=' );
- }
- stream << '\n';
- }
- void printSummaryDivider() {
- stream << getLineOfChars<'-'>() << '\n';
- }
-
- private:
- bool m_headerPrinted;
- };
-
- INTERNAL_CATCH_REGISTER_REPORTER( "console", ConsoleReporter )
-
-} // end namespace Catch
-
-// #included from: ../reporters/catch_reporter_compact.hpp
-#define TWOBLUECUBES_CATCH_REPORTER_COMPACT_HPP_INCLUDED
-
-namespace Catch {
-
- struct CompactReporter : StreamingReporterBase {
-
- CompactReporter( ReporterConfig const& _config )
- : StreamingReporterBase( _config )
- {}
-
- virtual ~CompactReporter();
-
- static std::string getDescription() {
- return "Reports test results on a single line, suitable for IDEs";
- }
-
- virtual ReporterPreferences getPreferences() const {
- ReporterPreferences prefs;
- prefs.shouldRedirectStdOut = false;
- return prefs;
- }
-
- virtual void noMatchingTestCases( std::string const& spec ) {
- stream << "No test cases matched '" << spec << '\'' << std::endl;
- }
-
- virtual void assertionStarting( AssertionInfo const& ) {}
-
- virtual bool assertionEnded( AssertionStats const& _assertionStats ) {
- AssertionResult const& result = _assertionStats.assertionResult;
-
- bool printInfoMessages = true;
-
- // Drop out if result was successful and we're not printing those
- if( !m_config->includeSuccessfulResults() && result.isOk() ) {
- if( result.getResultType() != ResultWas::Warning )
- return false;
- printInfoMessages = false;
- }
-
- AssertionPrinter printer( stream, _assertionStats, printInfoMessages );
- printer.print();
-
- stream << std::endl;
- return true;
- }
-
- virtual void sectionEnded(SectionStats const& _sectionStats) CATCH_OVERRIDE {
- if (m_config->showDurations() == ShowDurations::Always) {
- stream << getFormattedDuration(_sectionStats.durationInSeconds) << " s: " << _sectionStats.sectionInfo.name << std::endl;
- }
- }
-
- virtual void testRunEnded( TestRunStats const& _testRunStats ) {
- printTotals( _testRunStats.totals );
- stream << '\n' << std::endl;
- StreamingReporterBase::testRunEnded( _testRunStats );
- }
-
- private:
- class AssertionPrinter {
- void operator= ( AssertionPrinter const& );
- public:
- AssertionPrinter( std::ostream& _stream, AssertionStats const& _stats, bool _printInfoMessages )
- : stream( _stream )
- , stats( _stats )
- , result( _stats.assertionResult )
- , messages( _stats.infoMessages )
- , itMessage( _stats.infoMessages.begin() )
- , printInfoMessages( _printInfoMessages )
- {}
-
- void print() {
- printSourceInfo();
-
- itMessage = messages.begin();
-
- switch( result.getResultType() ) {
- case ResultWas::Ok:
- printResultType( Colour::ResultSuccess, passedString() );
- printOriginalExpression();
- printReconstructedExpression();
- if ( ! result.hasExpression() )
- printRemainingMessages( Colour::None );
- else
- printRemainingMessages();
- break;
- case ResultWas::ExpressionFailed:
- if( result.isOk() )
- printResultType( Colour::ResultSuccess, failedString() + std::string( " - but was ok" ) );
- else
- printResultType( Colour::Error, failedString() );
- printOriginalExpression();
- printReconstructedExpression();
- printRemainingMessages();
- break;
- case ResultWas::ThrewException:
- printResultType( Colour::Error, failedString() );
- printIssue( "unexpected exception with message:" );
- printMessage();
- printExpressionWas();
- printRemainingMessages();
- break;
- case ResultWas::FatalErrorCondition:
- printResultType( Colour::Error, failedString() );
- printIssue( "fatal error condition with message:" );
- printMessage();
- printExpressionWas();
- printRemainingMessages();
- break;
- case ResultWas::DidntThrowException:
- printResultType( Colour::Error, failedString() );
- printIssue( "expected exception, got none" );
- printExpressionWas();
- printRemainingMessages();
- break;
- case ResultWas::Info:
- printResultType( Colour::None, "info" );
- printMessage();
- printRemainingMessages();
- break;
- case ResultWas::Warning:
- printResultType( Colour::None, "warning" );
- printMessage();
- printRemainingMessages();
- break;
- case ResultWas::ExplicitFailure:
- printResultType( Colour::Error, failedString() );
- printIssue( "explicitly" );
- printRemainingMessages( Colour::None );
- break;
- // These cases are here to prevent compiler warnings
- case ResultWas::Unknown:
- case ResultWas::FailureBit:
- case ResultWas::Exception:
- printResultType( Colour::Error, "** internal error **" );
- break;
- }
- }
-
- private:
- // Colour::LightGrey
-
- static Colour::Code dimColour() { return Colour::FileName; }
-
-#ifdef CATCH_PLATFORM_MAC
- static const char* failedString() { return "FAILED"; }
- static const char* passedString() { return "PASSED"; }
-#else
- static const char* failedString() { return "failed"; }
- static const char* passedString() { return "passed"; }
-#endif
-
- void printSourceInfo() const {
- Colour colourGuard( Colour::FileName );
- stream << result.getSourceInfo() << ':';
- }
-
- void printResultType( Colour::Code colour, std::string const& passOrFail ) const {
- if( !passOrFail.empty() ) {
- {
- Colour colourGuard( colour );
- stream << ' ' << passOrFail;
- }
- stream << ':';
- }
- }
-
- void printIssue( std::string const& issue ) const {
- stream << ' ' << issue;
- }
-
- void printExpressionWas() {
- if( result.hasExpression() ) {
- stream << ';';
- {
- Colour colour( dimColour() );
- stream << " expression was:";
- }
- printOriginalExpression();
- }
- }
-
- void printOriginalExpression() const {
- if( result.hasExpression() ) {
- stream << ' ' << result.getExpression();
- }
- }
-
- void printReconstructedExpression() const {
- if( result.hasExpandedExpression() ) {
- {
- Colour colour( dimColour() );
- stream << " for: ";
- }
- stream << result.getExpandedExpression();
- }
- }
-
- void printMessage() {
- if ( itMessage != messages.end() ) {
- stream << " '" << itMessage->message << '\'';
- ++itMessage;
- }
- }
-
- void printRemainingMessages( Colour::Code colour = dimColour() ) {
- if ( itMessage == messages.end() )
- return;
-
- // using messages.end() directly yields compilation error:
- std::vector<MessageInfo>::const_iterator itEnd = messages.end();
- const std::size_t N = static_cast<std::size_t>( std::distance( itMessage, itEnd ) );
-
- {
- Colour colourGuard( colour );
- stream << " with " << pluralise( N, "message" ) << ':';
- }
-
- for(; itMessage != itEnd; ) {
- // If this assertion is a warning ignore any INFO messages
- if( printInfoMessages || itMessage->type != ResultWas::Info ) {
- stream << " '" << itMessage->message << '\'';
- if ( ++itMessage != itEnd ) {
- Colour colourGuard( dimColour() );
- stream << " and";
- }
- }
- }
- }
-
- private:
- std::ostream& stream;
- AssertionStats const& stats;
- AssertionResult const& result;
- std::vector<MessageInfo> messages;
- std::vector<MessageInfo>::const_iterator itMessage;
- bool printInfoMessages;
- };
-
- // Colour, message variants:
- // - white: No tests ran.
- // - red: Failed [both/all] N test cases, failed [both/all] M assertions.
- // - white: Passed [both/all] N test cases (no assertions).
- // - red: Failed N tests cases, failed M assertions.
- // - green: Passed [both/all] N tests cases with M assertions.
-
- std::string bothOrAll( std::size_t count ) const {
- return count == 1 ? std::string() : count == 2 ? "both " : "all " ;
- }
-
- void printTotals( const Totals& totals ) const {
- if( totals.testCases.total() == 0 ) {
- stream << "No tests ran.";
- }
- else if( totals.testCases.failed == totals.testCases.total() ) {
- Colour colour( Colour::ResultError );
- const std::string qualify_assertions_failed =
- totals.assertions.failed == totals.assertions.total() ?
- bothOrAll( totals.assertions.failed ) : std::string();
- stream <<
- "Failed " << bothOrAll( totals.testCases.failed )
- << pluralise( totals.testCases.failed, "test case" ) << ", "
- "failed " << qualify_assertions_failed <<
- pluralise( totals.assertions.failed, "assertion" ) << '.';
- }
- else if( totals.assertions.total() == 0 ) {
- stream <<
- "Passed " << bothOrAll( totals.testCases.total() )
- << pluralise( totals.testCases.total(), "test case" )
- << " (no assertions).";
- }
- else if( totals.assertions.failed ) {
- Colour colour( Colour::ResultError );
- stream <<
- "Failed " << pluralise( totals.testCases.failed, "test case" ) << ", "
- "failed " << pluralise( totals.assertions.failed, "assertion" ) << '.';
- }
- else {
- Colour colour( Colour::ResultSuccess );
- stream <<
- "Passed " << bothOrAll( totals.testCases.passed )
- << pluralise( totals.testCases.passed, "test case" ) <<
- " with " << pluralise( totals.assertions.passed, "assertion" ) << '.';
- }
- }
- };
-
- INTERNAL_CATCH_REGISTER_REPORTER( "compact", CompactReporter )
-
-} // end namespace Catch
-
-namespace Catch {
- // These are all here to avoid warnings about not having any out of line
- // virtual methods
- NonCopyable::~NonCopyable() {}
- IShared::~IShared() {}
- IStream::~IStream() CATCH_NOEXCEPT {}
- FileStream::~FileStream() CATCH_NOEXCEPT {}
- CoutStream::~CoutStream() CATCH_NOEXCEPT {}
- DebugOutStream::~DebugOutStream() CATCH_NOEXCEPT {}
- StreamBufBase::~StreamBufBase() CATCH_NOEXCEPT {}
- IContext::~IContext() {}
- IResultCapture::~IResultCapture() {}
- ITestCase::~ITestCase() {}
- ITestCaseRegistry::~ITestCaseRegistry() {}
- IRegistryHub::~IRegistryHub() {}
- IMutableRegistryHub::~IMutableRegistryHub() {}
- IExceptionTranslator::~IExceptionTranslator() {}
- IExceptionTranslatorRegistry::~IExceptionTranslatorRegistry() {}
- IReporter::~IReporter() {}
- IReporterFactory::~IReporterFactory() {}
- IReporterRegistry::~IReporterRegistry() {}
- IStreamingReporter::~IStreamingReporter() {}
- AssertionStats::~AssertionStats() {}
- SectionStats::~SectionStats() {}
- TestCaseStats::~TestCaseStats() {}
- TestGroupStats::~TestGroupStats() {}
- TestRunStats::~TestRunStats() {}
- CumulativeReporterBase::SectionNode::~SectionNode() {}
- CumulativeReporterBase::~CumulativeReporterBase() {}
-
- StreamingReporterBase::~StreamingReporterBase() {}
- ConsoleReporter::~ConsoleReporter() {}
- CompactReporter::~CompactReporter() {}
- IRunner::~IRunner() {}
- IMutableContext::~IMutableContext() {}
- IConfig::~IConfig() {}
- XmlReporter::~XmlReporter() {}
- JunitReporter::~JunitReporter() {}
- TestRegistry::~TestRegistry() {}
- FreeFunctionTestCase::~FreeFunctionTestCase() {}
- IGeneratorInfo::~IGeneratorInfo() {}
- IGeneratorsForTest::~IGeneratorsForTest() {}
- WildcardPattern::~WildcardPattern() {}
- TestSpec::Pattern::~Pattern() {}
- TestSpec::NamePattern::~NamePattern() {}
- TestSpec::TagPattern::~TagPattern() {}
- TestSpec::ExcludedPattern::~ExcludedPattern() {}
- Matchers::Impl::MatcherUntypedBase::~MatcherUntypedBase() {}
-
- void Config::dummy() {}
-
- namespace TestCaseTracking {
- ITracker::~ITracker() {}
- TrackerBase::~TrackerBase() {}
- SectionTracker::~SectionTracker() {}
- IndexTracker::~IndexTracker() {}
- }
-}
-
-#ifdef __clang__
-#pragma clang diagnostic pop
-#endif
-
-#endif
-
-#ifdef CATCH_CONFIG_MAIN
-// #included from: internal/catch_default_main.hpp
-#define TWOBLUECUBES_CATCH_DEFAULT_MAIN_HPP_INCLUDED
-
-#ifndef __OBJC__
-
-#if defined(WIN32) && defined(_UNICODE) && !defined(DO_NOT_USE_WMAIN)
-// Standard C/C++ Win32 Unicode wmain entry point
-extern "C" int wmain (int argc, wchar_t * argv[], wchar_t * []) {
-#else
-// Standard C/C++ main entry point
-int main (int argc, char * argv[]) {
-#endif
-
- int result = Catch::Session().run( argc, argv );
- return ( result < 0xff ? result : 0xff );
-}
-
-#else // __OBJC__
-
-// Objective-C entry point
-int main (int argc, char * const argv[]) {
-#if !CATCH_ARC_ENABLED
- NSAutoreleasePool * pool = [[NSAutoreleasePool alloc] init];
-#endif
-
- Catch::registerTestMethods();
- int result = Catch::Session().run( argc, (char* const*)argv );
-
-#if !CATCH_ARC_ENABLED
- [pool drain];
-#endif
-
- return ( result < 0xff ? result : 0xff );
-}
-
-#endif // __OBJC__
-
-#endif
-
-#ifdef CLARA_CONFIG_MAIN_NOT_DEFINED
-# undef CLARA_CONFIG_MAIN
-#endif
-
-//////
-
-// If this config identifier is defined then all CATCH macros are prefixed with CATCH_
-#ifdef CATCH_CONFIG_PREFIX_ALL
-
-#if defined(CATCH_CONFIG_FAST_COMPILE)
-#define CATCH_REQUIRE( expr ) INTERNAL_CATCH_TEST_NO_TRY( "CATCH_REQUIRE", Catch::ResultDisposition::Normal, expr )
-#define CATCH_REQUIRE_FALSE( expr ) INTERNAL_CATCH_TEST_NO_TRY( "CATCH_REQUIRE_FALSE", Catch::ResultDisposition::Normal | Catch::ResultDisposition::FalseTest, expr )
-#else
-#define CATCH_REQUIRE( expr ) INTERNAL_CATCH_TEST( "CATCH_REQUIRE", Catch::ResultDisposition::Normal, expr )
-#define CATCH_REQUIRE_FALSE( expr ) INTERNAL_CATCH_TEST( "CATCH_REQUIRE_FALSE", Catch::ResultDisposition::Normal | Catch::ResultDisposition::FalseTest, expr )
-#endif
-
-#define CATCH_REQUIRE_THROWS( expr ) INTERNAL_CATCH_THROWS( "CATCH_REQUIRE_THROWS", Catch::ResultDisposition::Normal, "", expr )
-#define CATCH_REQUIRE_THROWS_AS( expr, exceptionType ) INTERNAL_CATCH_THROWS_AS( "CATCH_REQUIRE_THROWS_AS", exceptionType, Catch::ResultDisposition::Normal, expr )
-#define CATCH_REQUIRE_THROWS_WITH( expr, matcher ) INTERNAL_CATCH_THROWS( "CATCH_REQUIRE_THROWS_WITH", Catch::ResultDisposition::Normal, matcher, expr )
-#define CATCH_REQUIRE_NOTHROW( expr ) INTERNAL_CATCH_NO_THROW( "CATCH_REQUIRE_NOTHROW", Catch::ResultDisposition::Normal, expr )
-
-#define CATCH_CHECK( expr ) INTERNAL_CATCH_TEST( "CATCH_CHECK", Catch::ResultDisposition::ContinueOnFailure, expr )
-#define CATCH_CHECK_FALSE( expr ) INTERNAL_CATCH_TEST( "CATCH_CHECK_FALSE", Catch::ResultDisposition::ContinueOnFailure | Catch::ResultDisposition::FalseTest, expr )
-#define CATCH_CHECKED_IF( expr ) INTERNAL_CATCH_IF( "CATCH_CHECKED_IF", Catch::ResultDisposition::ContinueOnFailure, expr )
-#define CATCH_CHECKED_ELSE( expr ) INTERNAL_CATCH_ELSE( "CATCH_CHECKED_ELSE", Catch::ResultDisposition::ContinueOnFailure, expr )
-#define CATCH_CHECK_NOFAIL( expr ) INTERNAL_CATCH_TEST( "CATCH_CHECK_NOFAIL", Catch::ResultDisposition::ContinueOnFailure | Catch::ResultDisposition::SuppressFail, expr )
-
-#define CATCH_CHECK_THROWS( expr ) INTERNAL_CATCH_THROWS( "CATCH_CHECK_THROWS", Catch::ResultDisposition::ContinueOnFailure, "", expr )
-#define CATCH_CHECK_THROWS_AS( expr, exceptionType ) INTERNAL_CATCH_THROWS_AS( "CATCH_CHECK_THROWS_AS", exceptionType, Catch::ResultDisposition::ContinueOnFailure, expr )
-#define CATCH_CHECK_THROWS_WITH( expr, matcher ) INTERNAL_CATCH_THROWS( "CATCH_CHECK_THROWS_WITH", Catch::ResultDisposition::ContinueOnFailure, matcher, expr )
-#define CATCH_CHECK_NOTHROW( expr ) INTERNAL_CATCH_NO_THROW( "CATCH_CHECK_NOTHROW", Catch::ResultDisposition::ContinueOnFailure, expr )
-
-#define CATCH_CHECK_THAT( arg, matcher ) INTERNAL_CHECK_THAT( "CATCH_CHECK_THAT", matcher, Catch::ResultDisposition::ContinueOnFailure, arg )
-
-#if defined(CATCH_CONFIG_FAST_COMPILE)
-#define CATCH_REQUIRE_THAT( arg, matcher ) INTERNAL_CHECK_THAT_NO_TRY( "CATCH_REQUIRE_THAT", matcher, Catch::ResultDisposition::Normal, arg )
-#else
-#define CATCH_REQUIRE_THAT( arg, matcher ) INTERNAL_CHECK_THAT( "CATCH_REQUIRE_THAT", matcher, Catch::ResultDisposition::Normal, arg )
-#endif
-
-#define CATCH_INFO( msg ) INTERNAL_CATCH_INFO( "CATCH_INFO", msg )
-#define CATCH_WARN( msg ) INTERNAL_CATCH_MSG( "CATCH_WARN", Catch::ResultWas::Warning, Catch::ResultDisposition::ContinueOnFailure, msg )
-#define CATCH_SCOPED_INFO( msg ) INTERNAL_CATCH_INFO( "CATCH_INFO", msg )
-#define CATCH_CAPTURE( msg ) INTERNAL_CATCH_INFO( "CATCH_CAPTURE", #msg " := " << Catch::toString(msg) )
-#define CATCH_SCOPED_CAPTURE( msg ) INTERNAL_CATCH_INFO( "CATCH_CAPTURE", #msg " := " << Catch::toString(msg) )
-
-#ifdef CATCH_CONFIG_VARIADIC_MACROS
- #define CATCH_TEST_CASE( ... ) INTERNAL_CATCH_TESTCASE( __VA_ARGS__ )
- #define CATCH_TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_TEST_CASE_METHOD( className, __VA_ARGS__ )
- #define CATCH_METHOD_AS_TEST_CASE( method, ... ) INTERNAL_CATCH_METHOD_AS_TEST_CASE( method, __VA_ARGS__ )
- #define CATCH_REGISTER_TEST_CASE( Function, ... ) INTERNAL_CATCH_REGISTER_TESTCASE( Function, __VA_ARGS__ )
- #define CATCH_SECTION( ... ) INTERNAL_CATCH_SECTION( __VA_ARGS__ )
- #define CATCH_FAIL( ... ) INTERNAL_CATCH_MSG( "CATCH_FAIL", Catch::ResultWas::ExplicitFailure, Catch::ResultDisposition::Normal, __VA_ARGS__ )
- #define CATCH_FAIL_CHECK( ... ) INTERNAL_CATCH_MSG( "CATCH_FAIL_CHECK", Catch::ResultWas::ExplicitFailure, Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ )
- #define CATCH_SUCCEED( ... ) INTERNAL_CATCH_MSG( "CATCH_SUCCEED", Catch::ResultWas::Ok, Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ )
-#else
- #define CATCH_TEST_CASE( name, description ) INTERNAL_CATCH_TESTCASE( name, description )
- #define CATCH_TEST_CASE_METHOD( className, name, description ) INTERNAL_CATCH_TEST_CASE_METHOD( className, name, description )
- #define CATCH_METHOD_AS_TEST_CASE( method, name, description ) INTERNAL_CATCH_METHOD_AS_TEST_CASE( method, name, description )
- #define CATCH_REGISTER_TEST_CASE( function, name, description ) INTERNAL_CATCH_REGISTER_TESTCASE( function, name, description )
- #define CATCH_SECTION( name, description ) INTERNAL_CATCH_SECTION( name, description )
- #define CATCH_FAIL( msg ) INTERNAL_CATCH_MSG( "CATCH_FAIL", Catch::ResultWas::ExplicitFailure, Catch::ResultDisposition::Normal, msg )
- #define CATCH_FAIL_CHECK( msg ) INTERNAL_CATCH_MSG( "CATCH_FAIL_CHECK", Catch::ResultWas::ExplicitFailure, Catch::ResultDisposition::ContinueOnFailure, msg )
- #define CATCH_SUCCEED( msg ) INTERNAL_CATCH_MSG( "CATCH_SUCCEED", Catch::ResultWas::Ok, Catch::ResultDisposition::ContinueOnFailure, msg )
-#endif
-#define CATCH_ANON_TEST_CASE() INTERNAL_CATCH_TESTCASE( "", "" )
-
-#define CATCH_REGISTER_REPORTER( name, reporterType ) INTERNAL_CATCH_REGISTER_REPORTER( name, reporterType )
-#define CATCH_REGISTER_LEGACY_REPORTER( name, reporterType ) INTERNAL_CATCH_REGISTER_LEGACY_REPORTER( name, reporterType )
-
-#define CATCH_GENERATE( expr) INTERNAL_CATCH_GENERATE( expr )
-
-// "BDD-style" convenience wrappers
-#ifdef CATCH_CONFIG_VARIADIC_MACROS
-#define CATCH_SCENARIO( ... ) CATCH_TEST_CASE( "Scenario: " __VA_ARGS__ )
-#define CATCH_SCENARIO_METHOD( className, ... ) INTERNAL_CATCH_TEST_CASE_METHOD( className, "Scenario: " __VA_ARGS__ )
-#else
-#define CATCH_SCENARIO( name, tags ) CATCH_TEST_CASE( "Scenario: " name, tags )
-#define CATCH_SCENARIO_METHOD( className, name, tags ) INTERNAL_CATCH_TEST_CASE_METHOD( className, "Scenario: " name, tags )
-#endif
-#define CATCH_GIVEN( desc ) CATCH_SECTION( std::string( "Given: ") + desc, "" )
-#define CATCH_WHEN( desc ) CATCH_SECTION( std::string( " When: ") + desc, "" )
-#define CATCH_AND_WHEN( desc ) CATCH_SECTION( std::string( " And: ") + desc, "" )
-#define CATCH_THEN( desc ) CATCH_SECTION( std::string( " Then: ") + desc, "" )
-#define CATCH_AND_THEN( desc ) CATCH_SECTION( std::string( " And: ") + desc, "" )
-
-// If CATCH_CONFIG_PREFIX_ALL is not defined then the CATCH_ prefix is not required
-#else
-
-#if defined(CATCH_CONFIG_FAST_COMPILE)
-#define REQUIRE( expr ) INTERNAL_CATCH_TEST_NO_TRY( "REQUIRE", Catch::ResultDisposition::Normal, expr )
-#define REQUIRE_FALSE( expr ) INTERNAL_CATCH_TEST_NO_TRY( "REQUIRE_FALSE", Catch::ResultDisposition::Normal | Catch::ResultDisposition::FalseTest, expr )
-
-#else
-#define REQUIRE( expr ) INTERNAL_CATCH_TEST( "REQUIRE", Catch::ResultDisposition::Normal, expr )
-#define REQUIRE_FALSE( expr ) INTERNAL_CATCH_TEST( "REQUIRE_FALSE", Catch::ResultDisposition::Normal | Catch::ResultDisposition::FalseTest, expr )
-#endif
-
-#define REQUIRE_THROWS( expr ) INTERNAL_CATCH_THROWS( "REQUIRE_THROWS", Catch::ResultDisposition::Normal, "", expr )
-#define REQUIRE_THROWS_AS( expr, exceptionType ) INTERNAL_CATCH_THROWS_AS( "REQUIRE_THROWS_AS", exceptionType, Catch::ResultDisposition::Normal, expr )
-#define REQUIRE_THROWS_WITH( expr, matcher ) INTERNAL_CATCH_THROWS( "REQUIRE_THROWS_WITH", Catch::ResultDisposition::Normal, matcher, expr )
-#define REQUIRE_NOTHROW( expr ) INTERNAL_CATCH_NO_THROW( "REQUIRE_NOTHROW", Catch::ResultDisposition::Normal, expr )
-
-#define CHECK( expr ) INTERNAL_CATCH_TEST( "CHECK", Catch::ResultDisposition::ContinueOnFailure, expr )
-#define CHECK_FALSE( expr ) INTERNAL_CATCH_TEST( "CHECK_FALSE", Catch::ResultDisposition::ContinueOnFailure | Catch::ResultDisposition::FalseTest, expr )
-#define CHECKED_IF( expr ) INTERNAL_CATCH_IF( "CHECKED_IF", Catch::ResultDisposition::ContinueOnFailure, expr )
-#define CHECKED_ELSE( expr ) INTERNAL_CATCH_ELSE( "CHECKED_ELSE", Catch::ResultDisposition::ContinueOnFailure, expr )
-#define CHECK_NOFAIL( expr ) INTERNAL_CATCH_TEST( "CHECK_NOFAIL", Catch::ResultDisposition::ContinueOnFailure | Catch::ResultDisposition::SuppressFail, expr )
-
-#define CHECK_THROWS( expr ) INTERNAL_CATCH_THROWS( "CHECK_THROWS", Catch::ResultDisposition::ContinueOnFailure, "", expr )
-#define CHECK_THROWS_AS( expr, exceptionType ) INTERNAL_CATCH_THROWS_AS( "CHECK_THROWS_AS", exceptionType, Catch::ResultDisposition::ContinueOnFailure, expr )
-#define CHECK_THROWS_WITH( expr, matcher ) INTERNAL_CATCH_THROWS( "CHECK_THROWS_WITH", Catch::ResultDisposition::ContinueOnFailure, matcher, expr )
-#define CHECK_NOTHROW( expr ) INTERNAL_CATCH_NO_THROW( "CHECK_NOTHROW", Catch::ResultDisposition::ContinueOnFailure, expr )
-
-#define CHECK_THAT( arg, matcher ) INTERNAL_CHECK_THAT( "CHECK_THAT", matcher, Catch::ResultDisposition::ContinueOnFailure, arg )
-
-#if defined(CATCH_CONFIG_FAST_COMPILE)
-#define REQUIRE_THAT( arg, matcher ) INTERNAL_CHECK_THAT_NO_TRY( "REQUIRE_THAT", matcher, Catch::ResultDisposition::Normal, arg )
-#else
-#define REQUIRE_THAT( arg, matcher ) INTERNAL_CHECK_THAT( "REQUIRE_THAT", matcher, Catch::ResultDisposition::Normal, arg )
-#endif
-
-#define INFO( msg ) INTERNAL_CATCH_INFO( "INFO", msg )
-#define WARN( msg ) INTERNAL_CATCH_MSG( "WARN", Catch::ResultWas::Warning, Catch::ResultDisposition::ContinueOnFailure, msg )
-#define SCOPED_INFO( msg ) INTERNAL_CATCH_INFO( "INFO", msg )
-#define CAPTURE( msg ) INTERNAL_CATCH_INFO( "CAPTURE", #msg " := " << Catch::toString(msg) )
-#define SCOPED_CAPTURE( msg ) INTERNAL_CATCH_INFO( "CAPTURE", #msg " := " << Catch::toString(msg) )
-
-#ifdef CATCH_CONFIG_VARIADIC_MACROS
-#define TEST_CASE( ... ) INTERNAL_CATCH_TESTCASE( __VA_ARGS__ )
-#define TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_TEST_CASE_METHOD( className, __VA_ARGS__ )
-#define METHOD_AS_TEST_CASE( method, ... ) INTERNAL_CATCH_METHOD_AS_TEST_CASE( method, __VA_ARGS__ )
-#define REGISTER_TEST_CASE( Function, ... ) INTERNAL_CATCH_REGISTER_TESTCASE( Function, __VA_ARGS__ )
-#define SECTION( ... ) INTERNAL_CATCH_SECTION( __VA_ARGS__ )
-#define FAIL( ... ) INTERNAL_CATCH_MSG( "FAIL", Catch::ResultWas::ExplicitFailure, Catch::ResultDisposition::Normal, __VA_ARGS__ )
-#define FAIL_CHECK( ... ) INTERNAL_CATCH_MSG( "FAIL_CHECK", Catch::ResultWas::ExplicitFailure, Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ )
-#define SUCCEED( ... ) INTERNAL_CATCH_MSG( "SUCCEED", Catch::ResultWas::Ok, Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ )
-#else
-#define TEST_CASE( name, description ) INTERNAL_CATCH_TESTCASE( name, description )
- #define TEST_CASE_METHOD( className, name, description ) INTERNAL_CATCH_TEST_CASE_METHOD( className, name, description )
- #define METHOD_AS_TEST_CASE( method, name, description ) INTERNAL_CATCH_METHOD_AS_TEST_CASE( method, name, description )
- #define REGISTER_TEST_CASE( method, name, description ) INTERNAL_CATCH_REGISTER_TESTCASE( method, name, description )
- #define SECTION( name, description ) INTERNAL_CATCH_SECTION( name, description )
- #define FAIL( msg ) INTERNAL_CATCH_MSG( "FAIL", Catch::ResultWas::ExplicitFailure, Catch::ResultDisposition::Normal, msg )
- #define FAIL_CHECK( msg ) INTERNAL_CATCH_MSG( "FAIL_CHECK", Catch::ResultWas::ExplicitFailure, Catch::ResultDisposition::ContinueOnFailure, msg )
- #define SUCCEED( msg ) INTERNAL_CATCH_MSG( "SUCCEED", Catch::ResultWas::Ok, Catch::ResultDisposition::ContinueOnFailure, msg )
-#endif
-#define ANON_TEST_CASE() INTERNAL_CATCH_TESTCASE( "", "" )
-
-#define REGISTER_REPORTER( name, reporterType ) INTERNAL_CATCH_REGISTER_REPORTER( name, reporterType )
-#define REGISTER_LEGACY_REPORTER( name, reporterType ) INTERNAL_CATCH_REGISTER_LEGACY_REPORTER( name, reporterType )
-
-#define GENERATE( expr) INTERNAL_CATCH_GENERATE( expr )
-
-#endif
-
-#define CATCH_TRANSLATE_EXCEPTION( signature ) INTERNAL_CATCH_TRANSLATE_EXCEPTION( signature )
-
-// "BDD-style" convenience wrappers
-#ifdef CATCH_CONFIG_VARIADIC_MACROS
-#define SCENARIO( ... ) TEST_CASE( "Scenario: " __VA_ARGS__ )
-#define SCENARIO_METHOD( className, ... ) INTERNAL_CATCH_TEST_CASE_METHOD( className, "Scenario: " __VA_ARGS__ )
-#else
-#define SCENARIO( name, tags ) TEST_CASE( "Scenario: " name, tags )
-#define SCENARIO_METHOD( className, name, tags ) INTERNAL_CATCH_TEST_CASE_METHOD( className, "Scenario: " name, tags )
-#endif
-#define GIVEN( desc ) SECTION( std::string(" Given: ") + desc, "" )
-#define WHEN( desc ) SECTION( std::string(" When: ") + desc, "" )
-#define AND_WHEN( desc ) SECTION( std::string("And when: ") + desc, "" )
-#define THEN( desc ) SECTION( std::string(" Then: ") + desc, "" )
-#define AND_THEN( desc ) SECTION( std::string(" And: ") + desc, "" )
-
-using Catch::Detail::Approx;
-
-// #included from: internal/catch_reenable_warnings.h
-
-#define TWOBLUECUBES_CATCH_REENABLE_WARNINGS_H_INCLUDED
-
-#ifdef __clang__
-# ifdef __ICC // icpc defines the __clang__ macro
-# pragma warning(pop)
-# else
-# pragma clang diagnostic pop
-# endif
-#elif defined __GNUC__
-# pragma GCC diagnostic pop
-#endif
-
-#endif // TWOBLUECUBES_SINGLE_INCLUDE_CATCH_HPP_INCLUDED
-
diff --git a/bitpacking/tests/manual-test-bitpacker.cpp b/bitpacking/tests/manual-test-bitpacker.cpp
deleted file mode 100644
index 41c92ac7a114cfcc101ca835f9924d89e95dca57..0000000000000000000000000000000000000000
--- a/bitpacking/tests/manual-test-bitpacker.cpp
+++ /dev/null
@@ -1,30 +0,0 @@
-
-#include "../BitPacker.h"
-#include <stdint.h>
-#include <stdio.h>
-
-int main() {
-
- uint8_t array[BitPacker::DEFAULT_PACKET_SIZE] = {0};
- BitPacker packer(array);
-
- unsigned int pos;
- unsigned int bits;
- uint64_t value;
- uint64_t result;
-
- printf("%ld\n", sizeof(uint64_t));
-
- while(1) {
- printf("\nposition: ");
- scanf("%u", &pos);
- printf("number of bits: ");
- scanf("%u", &bits);
- printf("value: ");
- scanf("%lu", &value);
- packer.pack(pos, bits, value);
- packer.printPacket();
- packer.unpack(pos, bits, &result);
- printf("result: %ld\n", result);
- }
-}
\ No newline at end of file
diff --git a/bitpacking/tests/test-bitpacker.cpp b/bitpacking/tests/test-bitpacker.cpp
deleted file mode 100644
index 76070e48f03cfcf3bc6c92660013e3ea122c67b1..0000000000000000000000000000000000000000
--- a/bitpacking/tests/test-bitpacker.cpp
+++ /dev/null
@@ -1,789 +0,0 @@
-
-#define CATCH_CONFIG_MAIN
-#include "include/catch.hpp"
-
-#include "../BitPacker.h"
-
-SCENARIO("check parameters validity", "[param_check]") {
-
- GIVEN("an array of bytes and a BitPacker object") {
- uint8_t array[5] = {0};
- BitPacker packer(array, 5);
- bool res;
-
- WHEN("the position is negative") {
- res = packer.pack(-1, 5, (uint8_t)4);
- THEN("the array is unchanged") {
- bool ok = true;
- for (unsigned int i = 0; i < sizeof(array) && ok; i++) {
- if (array[i] != 0) {
- ok = false;
- }
- }
- REQUIRE(ok == true);
- REQUIRE(res == false);
- }
- }
- WHEN("trying to write 0 bits") {
- res = packer.pack(0, 0, (uint8_t)2);
- THEN("the array is unchanged") {
- bool ok = true;
- for (unsigned int i = 0; i < sizeof(array) && ok; i++) {
- if (array[i] != 0) {
- ok = false;
- }
- }
- REQUIRE(ok == true);
- REQUIRE(res == false);
- }
- }
- WHEN("trying to write a negative number of bits") {
- res = packer.pack(43, -5, (uint8_t)12);
- THEN("the array is unchanged") {
- bool ok = true;
- for (unsigned int i = 0; i < sizeof(array) && ok; i++) {
- if (array[i] != 0) {
- ok = false;
- }
- }
- REQUIRE(ok == true);
- REQUIRE(res == false);
- }
- }
- WHEN("the position is greater than array size") {
- res = packer.pack(25*8, 1, (uint8_t)10);
- THEN("the array is unchanged") {
- bool ok = true;
- for (unsigned int i = 0; i < sizeof(array) && ok; i++) {
- if (array[i] != 0) {
- ok = false;
- }
- }
- REQUIRE(ok == true);
- REQUIRE(res == false);
- }
- }
- WHEN("the sum between position and number of bits is greater than array size") {
- res = packer.pack(32, 15, (uint64_t)10);
- THEN("the array is unchanged") {
- bool ok = true;
- for (unsigned int i = 0; i < sizeof(array) && ok; i++) {
- if (array[i] != 0) {
- ok = false;
- }
- }
- REQUIRE(ok == true);
- REQUIRE(res == false);
- }
- }
- WHEN("the value has less bits than the bits to be written") {
- res = packer.pack(0, 16, (uint8_t)10);
- bool res2 = packer.pack(26, 17, (uint16_t)74);
- bool res3 = packer.pack(13, 23, (uint16_t)74);
- bool res4 = packer.pack(13, 24, (uint16_t)74);
- THEN("the array is unchanged") {
- bool ok = true;
- for (unsigned int i = 0; i < sizeof(array) && ok; i++) {
- if (array[i] != 0) {
- ok = false;
- }
- }
- REQUIRE(ok == true);
- REQUIRE(res == false);
- REQUIRE(res2 == false);
- REQUIRE(res3 == false);
- REQUIRE(res4 == false);
- }
- }
- WHEN("trying to unpack to much bits, w.r.t. those of the result variable") {
- uint8_t result = 0;
- packer.pack(0, 16, (uint32_t)65535); // 16 bits to 1
- res = packer.unpack(0, 16, &result);
- THEN("the array is unchanged") {
- REQUIRE(res == false);
- REQUIRE(result == 0); // should have not read the 65535 value
- }
- }
-
- /*
- Uncomment this to check static_asserts conditions.
- The compilation should fail.
- Leave this commented if you want to try all the
- other tests (compilation needs to be successful)
-
- WHEN("passing a number that is not unsigned") {
- packer.pack(0, 16, 5.4); // 16 bits to 1
- THEN("the compilation fails") {
-
- }
- }
- WHEN("passing a number that is not unsigned") {
- packer.pack(0, 16, 'c'); // 16 bits to 1
- THEN("the compilation fails") {
-
- }
- }
- WHEN("passing a number that is not unsigned") {
- packer.pack(0, 16, (int)5); // 16 bits to 1
- THEN("the compilation fails") {
-
- }
- }
- WHEN("passing a number that is not unsigned") {
- //packer.pack(0, 16, 5.4); // 16 bits to 1
- float result;
- res = packer.unpack(0, 16, &result);
- THEN("the compilation fails") {
-
- }
- }*/
- }
-}
-
-SCENARIO("writing correct values, aligned with array bytes") {
-
- GIVEN("an array of bytes and a BitPacker object") {
- uint8_t array[BitPacker::DEFAULT_PACKET_SIZE] = {0};
- BitPacker packer(array);
- uint64_t result;
-
- WHEN("writing in the first array byte") {
- packer.pack(0, 8, (uint8_t)129);
- packer.unpack(0, 8, &result);
- THEN("bits are correctly written") {
- REQUIRE(array[0] == 129);
- REQUIRE(result == 129);
- }
- }
- WHEN("writing in an intermediate array byte") {
- packer.pack(16, 8, (uint8_t)255);
- packer.unpack(16, 8, &result);
- THEN("bits are correctly written") {
- REQUIRE(array[2] == 255);
- REQUIRE(result == 255);
- }
- }
- WHEN("writing in the last array byte") {
- packer.pack(192, 8, (uint8_t)53);
- packer.unpack(192, 8, &result);
- THEN("bits are correctly written") {
- REQUIRE(array[24] == 53);
- REQUIRE(result == 53);
- }
- }
- WHEN("writing only the first bit of the array") {
- packer.pack(0, 1, (uint8_t)53); // 53 = 00110101
- packer.unpack(0, 1, &result);
- THEN("bits are correctly written") {
- REQUIRE(array[0] == 128);
- REQUIRE(result == 1); // only the last bit of 53 has been kept
- }
- }
- WHEN("writing only the last bit of the array") {
- packer.pack(199, 1, (uint8_t)53);
- packer.unpack(199, 1, &result);
- THEN("bits are correctly written") {
- REQUIRE(array[24] == 1);
- REQUIRE(result == 1); // only the last bit of 53 has been kept
- }
- }
- }
-}
-
-SCENARIO("writing correct values that are not aligned with array elements") {
-
- GIVEN("an array of bytes and a BitPacker object") {
- uint8_t array[BitPacker::DEFAULT_PACKET_SIZE] = {0};
- BitPacker packer(array);
- uint64_t result;
-
- WHEN("writing in the array with valid parameters") {
- packer.pack(2, 1, (uint8_t)128);
- packer.unpack(2, 1, &result);
- THEN("bits are correctly written") {
- REQUIRE(array[0] == 0);
- REQUIRE(result == 0);
- }
- }
- WHEN("writing in the array with valid parameters") {
- packer.pack(2, 1, (uint8_t)1);
- packer.unpack(2, 1, &result);
- THEN("bits are correctly written") {
- REQUIRE(array[0] == 32);
- REQUIRE(result == 1);
- }
- }
- WHEN("writing in the array with valid parameters") {
- packer.pack(46, 8, (uint8_t)23); // 23 = 00010111
- // 11 = 00001011
- packer.unpack(46, 8, &result);
- // 00000000 00000000 00000000 00000000 00000000 00000000 01011100 00000000 00000000
- THEN("bits are correctly written") {
- REQUIRE(array[5] == 0);
- REQUIRE(array[6] == 92);
- REQUIRE(result == 23);
- }
- }
- WHEN("writing less than 8 bits (less than 1 byte) in position 0") {
- packer.pack(0, 5, (uint8_t)55); // 55 keeping only 5 least significant bits becomes 23
- // 00110111 -> 10111000
- packer.unpack(0, 5, &result);
- THEN("bits are correctly written") {
- REQUIRE(array[0] == 184);
- REQUIRE(result == 23);
- }
- }
- WHEN("writing less than 8 bits (less than 1 byte) in an intermediate position") {
- packer.pack(9, 5, (uint8_t)55); // 55 keeping only 5 least significant bits becomes 23
- // 00110111 -> 10111000
- packer.unpack(9, 5, &result);
- THEN("bits are correctly written") {
- REQUIRE(array[0] == 0);
- REQUIRE(array[1] == 92);
- REQUIRE(array[2] == 0);
- REQUIRE(result == 23);
- }
- }
- }
-}
-
-SCENARIO("writing multiple overlapping correct values") {
-
- GIVEN("an array of bytes and a BitPacker object") {
- uint8_t array[BitPacker::DEFAULT_PACKET_SIZE] = {0};
- BitPacker packer(array);
- uint64_t result;
- WHEN("writing overlapping values (on adjacent bytes)") {
- packer.pack(0, 5, (uint8_t)63);
- packer.pack(2, 7, (uint8_t)23);
- // 63 = 00111111 -> 11111000 = 11111000
- // 23 = 00010111 -> 00101110 >> 00001011 10(000000)
- // bits in position 2-3-4-5-6-7-8 are reset before writing 23
- // ---> 11001011 10000000 ... = [203, 128, ...]
- THEN("bits are correctly updated and written") {
- REQUIRE(array[0] == 203);
- REQUIRE(array[1] == 128);
-
- packer.unpack(0, 5, &result);
- REQUIRE(result == 25);
- packer.unpack(2, 7, &result);
- REQUIRE(result == 23);
- }
- }
- }
-}
-
-SCENARIO("writing contiguous sequences of bits") {
-
- GIVEN("an array of bytes and a BitPacker object") {
- uint8_t array[BitPacker::DEFAULT_PACKET_SIZE] = {0};
- BitPacker packer(array);
- uint64_t result;
-
- WHEN("writing contiguous values (on adjacent bytes)") {
- packer.pack(10, 4, (uint8_t)20);
- packer.pack(14, 7, (uint8_t)65);
- // 20 = 00010100 -> 01000000 -> 00010000
- // 65 = 01000001 -> 10000010 -> 00000010 00001000
- // | 00010010 00001000
- // = 00010010 00001000
- THEN("bits are correctly updated and written") {
- REQUIRE(array[1] == 18);
- REQUIRE(array[2] == 8);
-
- packer.unpack(10, 4, &result);
- REQUIRE(result == 4);
- packer.unpack(14, 7, &result);
- REQUIRE(result == 65);
- }
- }
- WHEN("writing contiguous values (on adjacent bytes)") {
- packer.pack(10, 4, (uint32_t)20);
- packer.pack(14, 16, (uint32_t)65);
- // 20 = 00010100 -> 01000000 -> 00010000
- // 65 = 00000000 00000000 00000000 01000001 -> 00000000 01000001 00000000 00000000
- // -> 00000000 00000001 00000100 00000000
- // => 00010000 ...
- // | 00000000 00000001 00000100 00000000
- THEN("bits are correctly updated and written") {
- REQUIRE(array[1] == 16);
- REQUIRE(array[2] == 1);
- REQUIRE(array[3] == 4);
-
- packer.unpack(10, 4, &result);
- REQUIRE(result == 4);
- packer.unpack(14, 16, &result);
- REQUIRE(result == 65);
- }
- }
- }
-}
-
-SCENARIO("writing numbers that spread over multiple bytes") {
-
- GIVEN("an array of bytes and a BitPacker object") {
- uint8_t array[BitPacker::DEFAULT_PACKET_SIZE] = {0};
- BitPacker packer(array);
- uint64_t result;
-
- WHEN("writing a value that touches 3 bytes of the array") {
- packer.pack(12, 16, (uint32_t)65); // 65 = 00000000 00000000 00000000 01000001
- // DESIRED BEHAVIOUR:
- // shift left by 16 << 00000000 01000001
- // shift right by 4 >> 00000000 00000100 00010000
- // packet = 00000000 00000000 00000100 00010000 ...
- packer.unpack(12, 16, &result);
- THEN("bits are correctly updated and written") {
- REQUIRE(array[0] == 0);
- REQUIRE(array[1] == 0);
- REQUIRE(array[2] == 4);
- REQUIRE(array[3] == 16);
- REQUIRE(array[4] == 0);
- REQUIRE(result == 65);
- }
- }
- WHEN("writing a value that touches 3 bytes of the array") {
- packer.pack(12, 15, (uint32_t)65); // 65 = 00000000 00000000 00000000 01000001
- // DESIRED BEHAVIOUR:
- // shift left by 17 (32-15) << 00000000 10000010
- // shift right by 4 >> 00000000 00001000 0010000
- // packet = 00000000 00000000 00001000 0010000 ...
- packer.unpack(12, 15, &result);
- THEN("bits are correctly updated and written") {
- REQUIRE(array[0] == 0);
- REQUIRE(array[1] == 0);
- REQUIRE(array[2] == 8);
- REQUIRE(array[3] == 32);
- REQUIRE(array[4] == 0);
- REQUIRE(result == 65);
- }
- }
- WHEN("writing a value that touches 5 bytes of the array") {
- packer.pack(12, 32, (uint32_t)65); // 65 = 00000000 00000000 00000000 01000001
- // DESIRED BEHAVIOUR:
- // keep all the bits
- // shift right by 4 >> 00000000 00000000 00000000 00000100 00010000 ...
- // packet = 00000000 00000000 00000000 00000000 00000100 00010000 ...
- packer.unpack(12, 32, &result);
- THEN("bits are correctly updated and written") {
- REQUIRE(array[0] == 0);
- REQUIRE(array[1] == 0);
- REQUIRE(array[2] == 0);
- REQUIRE(array[3] == 0);
- REQUIRE(array[4] == 4);
- REQUIRE(array[5] == 16);
- REQUIRE(array[6] == 0);
- REQUIRE(result == 65);
- }
- }
- WHEN("writing a value that touches 5 bytes of the array") {
- packer.pack(13, 32, (uint64_t)2155872321); // 10000000 10000000 00000000 01000001
- packer.unpack(13, 32, &result);
- THEN("bits are correctly updated and written") {
- // DESIRED BEHAVIOUR:
- // keep all the bits
- // shift by 5 to the right >> 00000100 00000100 00000000 00000010 00001000
- // packet = 00000000 00000100 00000100 00000000 00000010 00001000 ...
- REQUIRE(array[0] == 0);
- REQUIRE(array[1] == 4);
- REQUIRE(array[2] == 4);
- REQUIRE(array[3] == 0);
- REQUIRE(array[4] == 2);
- REQUIRE(array[5] == 8);
- REQUIRE(array[6] == 0);
- REQUIRE(result == 2155872321);
- }
- }
- WHEN("writing a value that touches 4 bytes of the array") {
- packer.pack(8, 25, (uint32_t)16777217); // 00000001 00000000 00000000 00000001
- // -> 10000000 00000000 00000000 1(0000000)
- packer.unpack(8, 25, &result);
- THEN("bits are correctly updated and written") {
- REQUIRE(array[0] == 0);
- REQUIRE(array[1] == 128);
- REQUIRE(array[2] == 0);
- REQUIRE(array[3] == 0);
- REQUIRE(array[4] == 128);
- REQUIRE(result == 16777217);
- }
- }
- WHEN("writing a value that touches 8 bytes of the array") {
- packer.pack(100, 60, (uint64_t)0b1000000010000000100000001000000010000000100000001000000010000000);
- // 10000000 10000000 10000000 10000000 10000000 10000000 10000000 10000000
- // shift by 4 left (keep 64-60 bits) << 00001000 00001000 00001000 00001000 00001000 00001000 00001000 00000(000)
- // shift by 4 right (position 100-96 in the 12th byte) >> 00000000 10000000 10000000 10000000 10000000 10000000 10000000 10000000 00000000
- packer.unpack(100, 60, &result);
- THEN("bits are correctly updated and written") {
- REQUIRE(array[10] == 0);
- REQUIRE(array[11] == 0);
- REQUIRE(array[12] == 0);
- REQUIRE(array[13] == 128);
- REQUIRE(array[14] == 128);
- REQUIRE(array[15] == 128);
- REQUIRE(array[16] == 128);
- REQUIRE(array[17] == 128);
- REQUIRE(array[18] == 128);
- REQUIRE(array[19] == 128);
- REQUIRE(array[20] == 0);
- REQUIRE(result == (uint64_t)0b000010000000100000001000000010000000100000001000000010000000); // only 60 of the above 64 bits number
- }
- }
- WHEN("writing a value that touches 4 bytes of the array from 0 position") {
- packer.pack(0, 27, (uint32_t)67108865); // 00000100 00000000 00000000 00000001
- // -> 10000000 00000000 00000000 001(00000)
- packer.unpack(0, 27, &result);
- THEN("bits are correctly updated and written") {
- REQUIRE(array[0] == 128);
- REQUIRE(array[1] == 0);
- REQUIRE(array[2] == 0);
- REQUIRE(array[3] == 32);
- REQUIRE(array[4] == 0);
- REQUIRE(result == 67108865);
- }
- }
- WHEN("writing a value that touches 4 bytes, reaching the end of the array") {
- packer.pack(175, 25, (uint32_t)2164260865); // 10000001 00000000 00000000 00000001
- packer.unpack(175, 25, &result);
- THEN("bits are correctly updated and written") {
- REQUIRE(array[20] == 0);
- REQUIRE(array[21] == 1);
- REQUIRE(array[22] == 0);
- REQUIRE(array[23] == 0);
- REQUIRE(array[24] == 1);
- REQUIRE(result == (uint64_t)16777217); // only 25 of the above 32 bits number
- }
- }
- }
-}
-
-SCENARIO("writing on contiguous bytes, but not in the order they appear in packet") {
-
- GIVEN("an array of bytes and a BitPacker object") {
- uint8_t array[BitPacker::DEFAULT_PACKET_SIZE] = {0};
- BitPacker packer(array);
- uint64_t result;
-
- // 00100000 01100000 00000011 00000000 ...
- WHEN("writing the first byte, then the third and then the one in the middle") {
- packer.pack(2, 8, (uint8_t)129);
- packer.pack(23, 8,(uint8_t) 128);
- packer.pack(10, 13, (uint16_t)4097);
- THEN("array elements are correctly updated") {
- REQUIRE(array[0] == 32);
- REQUIRE(array[1] == 96);
- REQUIRE(array[2] == 3);
- REQUIRE(array[3] == 0);
-
- packer.unpack(2, 8, &result);
- REQUIRE(result == 129);
- packer.unpack(23, 8, &result);
- REQUIRE(result == 128);
- packer.unpack(10, 13, &result);
- REQUIRE(result == 4097);
- }
- }
- }
-}
-
-SCENARIO("writing a complete packet") {
-
- GIVEN("an array of bytes and a BitPacker object") {
- uint8_t array[BitPacker::DEFAULT_PACKET_SIZE] = {0};
- BitPacker packer(array);
- uint64_t result;
-
- WHEN("writing all the values in the array") {
- packer.pack(0, 25, (uint32_t)16777216); // 16777216 = 2^24 = 10000000 00000000 00000000 0 (25 bits)
- packer.pack(25, 12, (uint32_t)2048); // 2048 = 2^11 = 10000000 0000 (12 bits)
- packer.pack(37, 13, (uint32_t)4096); // 4096 = 2^12 = 10000000 00000 (13 bits)
- packer.pack(50, 12, (uint32_t)2048); // 2048 = 2^11 = 10000000 0000 (12 bits)
- packer.pack(62, 9, (uint32_t)256); // 256 = 2^8 = 10000000 0 (9 bits)
- packer.pack(71, 10, (uint32_t)512); // 512 = 2^9 = 10000000 00 (10 bits)
- packer.pack(81, 10, (uint32_t)512); // 512 = 2^9 = 10000000 00 (10 bits)
- packer.pack(91, 11, (uint32_t)1024); // 1024 = 2^10 = 10000000000 (11 bits)
- packer.pack(102, 11, (uint32_t)1024); // 1024 = 2^10 = 10000000 000 (11 bits)
- packer.pack(113, 11, (uint32_t)1024); // 1024 = 2^10 = 10000000 000 (11 bits)
- packer.pack(124, 11, (uint32_t)1024); // 1024 = 2^10 = 10000000 000 (11 bits)
- packer.pack(135, 11, (uint32_t)1024); // 1024 = 2^10 = 10000000 000 (11 bits)
- packer.pack(146, 11, (uint32_t)1024); // 1024 = 2^10 = 10000000 000 (11 bits)
- packer.pack(157, 11, (uint32_t)1024); // 1024 = 2^10 = 10000000 000 (11 bits)
- packer.pack(168, 11, (uint32_t)1024); // 1024 = 2^10 = 10000000 000 (11 bits)
- packer.pack(179, 10, (uint32_t)512); // 512 = 2^9 = 10000000 00 (10 bits)
- packer.pack(189, 5, (uint8_t)16); // 16 = 2^4 = 10000 (5 bits)
- packer.pack(194, 3, (uint8_t)4); // 4 = 2^2 = 100 (3 bits)
- packer.pack(197, 1, (uint8_t)1); // 1 = 2^0 = 1 (1 bit)
- packer.pack(198, 1, (uint8_t)1); // 1 = 2^0 = 1 (1 bit)
- packer.pack(199, 1, (uint8_t)1); // 1 = 2^0 = 1 (1 bit)
- // total = 200 bit (from 0 to 199)
-
- // packer.printPacket();
-
- // it should be:
- // 10000000 00000000 00000000 01000000 00000100 00000000 00100000 00000010 00000001 00000000
- // 01000000 00010000 00000010 00000000 01000000 00001000 00000001 00000000 00100000 00000100
- // 00000000 10000000 00010000 00000100 00100111
- THEN("bits are correctly updated and written") {
- // 00000001 00000000 00000000 00000000
- REQUIRE(array[0] == 128);
- REQUIRE(array[1] == 0);
- REQUIRE(array[2] == 0);
- REQUIRE(array[3] == 64);
- REQUIRE(array[4] == 4);
- REQUIRE(array[5] == 0);
- REQUIRE(array[6] == 32);
- REQUIRE(array[7] == 2);
- REQUIRE(array[8] == 1);
- REQUIRE(array[9] == 0);
- REQUIRE(array[10] == 64);
- REQUIRE(array[11] == 16);
- REQUIRE(array[12] == 2);
- REQUIRE(array[13] == 0);
- REQUIRE(array[14] == 64);
- REQUIRE(array[15] == 8);
- REQUIRE(array[16] == 1);
- REQUIRE(array[17] == 0);
- REQUIRE(array[18] == 32);
- REQUIRE(array[19] == 4);
- REQUIRE(array[20] == 0);
- REQUIRE(array[21] == 128);
- REQUIRE(array[22] == 16);
- REQUIRE(array[23] == 4);
- REQUIRE(array[24] == 39);
-
- packer.unpack(0, 25, &result);
- REQUIRE(result == (uint32_t)16777216);
- packer.unpack(25, 12, &result);
- REQUIRE(result == (uint32_t)2048);
- packer.unpack(37, 13, &result);
- REQUIRE(result == (uint32_t)4096);
- packer.unpack(50, 12, &result);
- REQUIRE(result == (uint32_t)2048);
- packer.unpack(62, 9, &result);
- REQUIRE(result == (uint32_t)256);
- packer.unpack(71, 10, &result);
- REQUIRE(result == (uint32_t)512);
- packer.unpack(81, 10, &result);
- REQUIRE(result == (uint32_t)512);
- packer.unpack(91, 11, &result);
- REQUIRE(result == (uint32_t)1024);
- packer.unpack(102, 11, &result);
- REQUIRE(result == (uint32_t)1024);
- packer.unpack(113, 11, &result);
- REQUIRE(result == (uint32_t)1024);
- packer.unpack(124, 11, &result);
- REQUIRE(result == (uint32_t)1024);
- packer.unpack(135, 11, &result);
- REQUIRE(result == (uint32_t)1024);
- packer.unpack(146, 11, &result);
- REQUIRE(result == (uint32_t)1024);
- packer.unpack(157, 11, &result);
- REQUIRE(result == (uint32_t)1024);
- packer.unpack(168, 11, &result);
- REQUIRE(result == (uint32_t)1024);
- packer.unpack(179, 10, &result);
- REQUIRE(result == (uint32_t)512);
- packer.unpack(189, 5, &result);
- REQUIRE(result == (uint8_t)16);
- packer.unpack(194, 3, &result);
- REQUIRE(result == (uint8_t)4);
- packer.unpack(197, 1, &result);
- REQUIRE(result == (uint8_t)1);
- packer.unpack(198, 1, &result);
- REQUIRE(result == (uint8_t)1);
- packer.unpack(199, 1, &result);
- REQUIRE(result == (uint8_t)1);
- }
- }
- }
-}
-
-SCENARIO("writing a complete packet that has a size which is different from the default one") {
-
- GIVEN("an array of bytes and a BitPacker object") {
- uint8_t array[12] = {0};
- BitPacker packer(array, 12);
- uint64_t result;
-
- WHEN("the array has a size which is different from the default one") {
- THEN("an array with the specified size is created") {
- REQUIRE(packer.getPacketSize() == 12);
- }
- }
- WHEN("writing all the values in the array") {
- THEN("bits are correctly updated and written") {
- packer.pack(0, 8, (uint8_t)255); // 11111111
- // NOTICE THE 2 MISSING BITS!
- packer.pack(10, 15, (uint32_t)16400); // 10000000 0010000
- packer.pack(25, 3, (uint8_t)7); // 111
- packer.pack(28, 145, (uint64_t)0); // this should fail: too much bits (exceed array size)
- packer.pack(28, 20, (uint32_t)128); // 00000000 00001000 0000
- packer.pack(48, 23, (uint32_t)4210752); // 10000000 10000000 1000000
- packer.pack(71, 25, (uint32_t)16843011); // 10000000 10000000 10000001 1
- // ---> 11111111 00100000 00001000 01110000 00000000 10000000
- // 10000000 10000000 10000001 00000001 00000001 00000011
- REQUIRE(array[0] == 255);
- REQUIRE(array[1] == 32);
- REQUIRE(array[2] == 8);
- REQUIRE(array[3] == 112);
- REQUIRE(array[4] == 0);
- REQUIRE(array[5] == 128);
- REQUIRE(array[6] == 128);
- REQUIRE(array[7] == 128);
- REQUIRE(array[8] == 129);
- REQUIRE(array[9] == 1);
- REQUIRE(array[10] == 1);
- REQUIRE(array[11] == 3);
-
- packer.unpack(0, 8, &result);
- REQUIRE(result == 255);
- packer.unpack(10, 15, &result);
- REQUIRE(result == 16400);
- packer.unpack(25, 3, &result);
- REQUIRE(result == 7);
- packer.unpack(28, 20, &result);
- REQUIRE(result == 128);
- packer.unpack(48, 23, &result);
- REQUIRE(result == 4210752);
- packer.unpack(71, 25, &result);
- REQUIRE(result == 16843011);
- }
- }
- }
-}
-
-SCENARIO("clearing the packet") {
-
- GIVEN("an array of bytes and a BitPacker object") {
- uint8_t array[BitPacker::DEFAULT_PACKET_SIZE] = {0};
- BitPacker packer(array);
- packer.pack(8, 8, (uint8_t)255);
- WHEN("writing a value in the array and then clearing the entire array") {
- packer.resetAll();
- bool allZeros = true;
- for(unsigned int i = 0; i < sizeof(array) && allZeros; i++) {
- if (array[i] != 0)
- allZeros = false;
- }
- THEN("array elements are all set to 0") {
- REQUIRE(allZeros == true);
- }
- }
- WHEN("writing a value in the array and then clearing one element") {
- packer.resetByte(1);
- THEN("that element is set to 0") {
- REQUIRE(array[1] == 0);
- }
- }
- WHEN("writing a value in the array and then clearing one element") {
- packer.pack(8, 8, (uint8_t)255); // set array[1] = 255
- packer.pack(16, 16, (uint16_t)65535); // set array[2] = array[3] = 255
- packer.resetByte(2); // only array[2] is cleared
- THEN("that element is set to 0") {
- REQUIRE(array[0] == 0);
- REQUIRE(array[1] == 255);
- REQUIRE(array[2] == 0);
- REQUIRE(array[3] == 255);
- }
- }
- WHEN("resetting specific bits of the array") {
- THEN("only the specified bits are reset to zero") {
-
- }
- }
- }
-}
-
-SCENARIO("writing multiple times the same bits of the array") {
- GIVEN("an array of bytes and a BitPacker object") {
- uint8_t array[BitPacker::DEFAULT_PACKET_SIZE] = {0};
- BitPacker packer(array);
- uint64_t result = 0;
-
- WHEN("reading the same bits") {
- packer.pack(2, 4, (uint8_t)4);
- packer.pack(2, 4, (uint8_t)8);
- packer.unpack(2, 4, &result);
- THEN("the last written value is read when accessing the array") {
- REQUIRE(result == 8);
- }
- }
- WHEN("reading the same bits") {
- packer.pack(0, 25, (uint32_t)65535);
- packer.pack(0, 25, (uint32_t)12345678);
- packer.unpack(0, 25, &result);
- THEN("the last written value is read when accessing the array") {
- REQUIRE(result == 12345678);
- }
- }
- WHEN("reading the same bits") {
- packer.pack(100, 60, (uint64_t)0b1000100010001000100010001000100010001000100010001000100010001000);
- packer.pack(100, 60, (uint64_t)0b1000000010000000100000001000000010000000100000001000000010000000);
- // 10000000 10000000 10000000 10000000 10000000 10000000 10000000 10000000
- // shift by 4 left (keep 64-60 bits) << 00001000 00001000 00001000 00001000 00001000 00001000 00001000 00000(000)
- // shift by 4 right (position 100-96 in the 12th byte) >> 00000000 10000000 10000000 10000000 10000000 10000000 10000000 10000000 00000000
- packer.unpack(100, 60, &result);
- THEN("the last written value is read when accessing the array") {
- //REQUIRE(array[10] == 0);
- REQUIRE(array[11] == 0);
- REQUIRE(array[12] == 0);
- REQUIRE(array[13] == 128);
- REQUIRE(array[14] == 128);
- REQUIRE(array[15] == 128);
- REQUIRE(array[16] == 128);
- REQUIRE(array[17] == 128);
- REQUIRE(array[18] == 128);
- REQUIRE(array[19] == 128);
- REQUIRE(array[20] == 0);
- REQUIRE(result == (uint64_t)0b000010000000100000001000000010000000100000001000000010000000); // only 60 of the above 64 bits number
- }
- }
- }
-}
-
-SCENARIO("writing a complete packet multiple times") {
-
- GIVEN("an array of bytes and a BitPacker object") {
- uint8_t array[12] = {0};
- BitPacker packer(array, 12);
- uint64_t result;
-
- uint8_t v1 = 200;
- uint32_t v2 = 16400;
- uint8_t v3 = 7;
- uint32_t v4 = 128;
- uint32_t v5 = 4210752;
- uint32_t v6 = 16843011;
-
- WHEN("reading the values in the array") {
- THEN("the last written values are retrieved") {
- for (uint8_t i = 0; i <= 10; i++) {
- packer.pack(0, 8, (uint8_t)(v1+i)); // 11111111
- // NOTICE THE 2 MISSING BITS!
- packer.pack(10, 15, (uint32_t)(v2+i)); // 10000000 0010000
- packer.pack(25, 3, (uint8_t)(v3+i)); // 111
- packer.pack(28, 20, (uint32_t)(v4+i)); // 00000000 00001000 0000
- packer.pack(48, 23, (uint32_t)(v5+i)); // 10000000 10000000 1000000
- packer.pack(71, 25, (uint32_t)(v6+i)); // 10000000 10000000 10000001 1
- // ---> 11111111 00100000 00001000 01110000 00000000 10000000
- // 10000000 10000000 10000001 00000001 00000001 00000011
- }
-
- packer.unpack(0, 8, &result);
- REQUIRE(result == v1+10);
- packer.unpack(10, 15, &result);
- REQUIRE(result == v2+10);
- packer.unpack(25, 3, &result);
- REQUIRE(result == 1); // v3 = 7 with only 3 bits => it overflows
- // 7 = 00000111
- // 10 = 00001010
- // + = 00010001 = 1 (keeping only 3 lsb bits)
- packer.unpack(28, 20, &result);
- REQUIRE(result == v4+10);
- packer.unpack(48, 23, &result);
- REQUIRE(result == v5+10);
- packer.unpack(71, 25, &result);
- REQUIRE(result == v6+10);
- }
- }
- }
-}
\ No newline at end of file
diff --git a/bitpacking/tests/test-telemetry.cpp b/bitpacking/tests/test-telemetry.cpp
deleted file mode 100644
index 4db48d3cc0a8b3fafdc5080d4aa25b7e55c364f1..0000000000000000000000000000000000000000
--- a/bitpacking/tests/test-telemetry.cpp
+++ /dev/null
@@ -1,185 +0,0 @@
-#define CATCH_CONFIG_MAIN
-#include "include/catch.hpp"
-
-//#include <stdio.h>
-//#include <unistd.h>
-#include "hermes/HermesPackets.h"
-
-uint8_t buf[HighRateTMPacker::HR_TM_PACKET_SIZE];
-
-TEST_CASE("Test HR_TELEMETRY")
-{
- GIVEN("A HR telemetry packer") {
- HighRateTMPacker packer{buf};
- long long ts;
-
- WHEN("writing multiple values to the same field") {
- packer.packTimestamp(1111111, 0);
- packer.packTimestamp(123, 1);
- packer.packTimestamp(255, 1);
- packer.packTimestamp(1111111, 2);
- packer.packTimestamp(1, 2);
- packer.packTimestamp(12345678, 3);
-
- THEN("the last written value is read") {
- REQUIRE(packer.unpackTimestamp(&ts, 0));
- REQUIRE(ts == 1111111);
-
- REQUIRE(packer.unpackTimestamp(&ts, 1));
- REQUIRE(ts == 255);
-
- REQUIRE(packer.unpackTimestamp(&ts, 2));
- REQUIRE(ts == 1);
-
- REQUIRE(packer.unpackTimestamp(&ts, 3));
- REQUIRE(ts == 12345678);
- }
- }
-
- WHEN("writing an ivnalid position") {
- THEN("the operation fails") {
- REQUIRE_FALSE(packer.packTimestamp(123, 4));
- REQUIRE_FALSE(packer.packTimestamp(123, -1)); // CHE SUCCEDE SE PASSO -1 ??
- }
- }
-
- WHEN("filling an entire packet multiple times") {
- // write 4 times the 4 subpackets
- for(int i = 1; i < 5; i++) {
- for(int j = 0; j < 4; j++) {
- packer.packTimestamp(123+i*2, j);
-
- packer.packPressureAda(55000.79853+i*20, j);
- packer.packPressureDigi(55000.79853+i*20, j);
-
- packer.packMslAltitude(1234.5678+i*2, j);
- packer.packAglAltitude(1234.5678+i*2, j);
-
- packer.packVertSpeed(123.456+i*2, j);
- packer.packVertSpeed2(123.456+i*2, j);
-
- packer.packAccX(123.456+i*2, j);
- packer.packAccY(-123.456+i*2, j);
- packer.packAccZ(123.456+i*2, j);
-
- packer.packGyroX(5.4+i*2, j);
- packer.packGyroY(5.4+i*2, j);
- packer.packGyroZ(5.4+i*2, j);
-
- packer.packGpsLat(41.822766, j);
- packer.packGpsLon(14.034714, j);
- packer.packGpsAlt(123.456+i*2, j);
-
- packer.packFmmState(1+i, j);
- packer.packDplState(1+i, j);
- if (i % 2 == 0) {
- packer.packPinLaunch(0, j);
- packer.packPinNosecone(0, j);
- packer.packGpsFix(0, j);
- }
- else {
- packer.packPinLaunch(1, j);
- packer.packPinNosecone(1, j);
- packer.packGpsFix(1, j);
- }
- }
- }
- THEN("only the last written values are read") {
- long long ts;
- float f;
- uint8_t u;
- double d;
-
- for (int j = 0; j < 4; j++) {
- REQUIRE(packer.unpackTimestamp(&ts, j));
- REQUIRE(ts == 131);
-
- REQUIRE(packer.unpackPressureAda(&f, j));
- REQUIRE(Approx(f).margin(13.42773438) == 55080.79853);
- REQUIRE(packer.unpackPressureDigi(&f, j));
-
- REQUIRE(Approx(f).margin(6.713867188) == 55080.79853);
- REQUIRE(packer.unpackMslAltitude(&f, j));
- REQUIRE(Approx(f).margin(1) == 1234.5678+8);
- REQUIRE(packer.unpackAglAltitude(&f, j));
- REQUIRE(Approx(f).margin(6.0546875) == 1234.5678+8);
-
- REQUIRE(packer.unpackVertSpeed(&f, j));
- REQUIRE(Approx(f).margin(0.5859375) == 123.456+8);
- REQUIRE(packer.unpackVertSpeed2(&f, j));
- REQUIRE(Approx(f).margin(0.5) == 123.456+8);
-
- REQUIRE(packer.unpackAccX(&f, j));
- REQUIRE(Approx(f).margin(0.1533203125) == 123.456+8);
- REQUIRE(packer.unpackAccY(&f, j));
- REQUIRE(Approx(f).margin(0.1533203125) == -123.456+8);
- REQUIRE(packer.unpackAccZ(&f, j));
- REQUIRE(Approx(f).margin(0.1533203125) == 123.456+8);
-
- REQUIRE(packer.unpackGyroX(&f, j));
- REQUIRE(Approx(f).margin(1.953125) == 5.4+8);
- REQUIRE(packer.unpackGyroY(&f, j));
- REQUIRE(Approx(f).margin(1.953125) == 5.4+8);
- REQUIRE(packer.unpackGyroZ(&f, j));
- REQUIRE(Approx(f).margin(1.953125) == 5.4+8);
-
- REQUIRE(packer.unpackGpsLat(&d, j));
- REQUIRE(Approx(d).margin(0.00002799658203) == 41.822766);
- REQUIRE(packer.unpackGpsLon(&d, j));
- REQUIRE(Approx(d).margin(0.00002799658203) == 14.034714);
-
- REQUIRE(packer.unpackGpsAlt(&f, j));
- REQUIRE(Approx(f).margin(5) == 123.456+8);
-
- REQUIRE(packer.unpackFmmState(&u, j));
- REQUIRE(u == 5);
- REQUIRE(packer.unpackDplState(&u, j));
- REQUIRE(u == 5);
- REQUIRE(packer.unpackPinLaunch(&u, j));
- REQUIRE(u == 0);
- REQUIRE(packer.unpackPinNosecone(&u, j));
- REQUIRE(u == 0);
- REQUIRE(packer.unpackGpsFix(&u, j));
- REQUIRE(u == 0);
- }
- }
- }
- WHEN("writing timestamps in a loop") {
- long long ts;
- for(int i = 0; i < 100; i++) {
- REQUIRE(packer.packTimestamp(123+i, 0));
- REQUIRE(packer.unpackTimestamp(&ts, 0));
- REQUIRE(ts == 123+i);
- //printf("timestamp = %ld\n", ts);
- //usleep(200000);
- }
- }
- }
-}
-
-TEST_CASE("Test LR_TELEMETRY")
-{
- GIVEN("A LR telemetry packer") {
- LowRateTMPacker packer{buf};
- long long ts;
-
- WHEN("writing multiple values to the same field") {
- packer.packLiftoffTs(1111111, 0);
- packer.packLiftoffTs(12345678, 0);
- packer.packLiftoffTs(123, 0);
-
- THEN("the last written value is read") {
- REQUIRE(packer.unpackLiftoffTs(&ts, 0));
- REQUIRE(ts == 123);
- }
- }
-
- WHEN("writing an ivnalid position") {
- THEN("the operation fails") {
- REQUIRE_FALSE(packer.packLiftoffTs(123, 4));
- REQUIRE_FALSE(packer.packLiftoffTs(123, 1));
- REQUIRE_FALSE(packer.packLiftoffTs(123, -1));
- }
- }
- }
-}
\ No newline at end of file
diff --git a/generate.sh b/generate.sh
deleted file mode 100755
index 307092bdfd4d4b15a2284056fb0fe181be55c26e..0000000000000000000000000000000000000000
--- a/generate.sh
+++ /dev/null
@@ -1,3 +0,0 @@
-cd mavlink
-python3 -m pymavlink.tools.mavgen --lang=C --wire-protocol=1.0 --output=../mavlink_lib ../message_definitions/lyra.xml
-python3 -m pymavlink.tools.mavgen --lang=Python --wire-protocol=1.0 --output=../mavlink_lib ../message_definitions/lyra.xml
\ No newline at end of file
diff --git a/mavlink b/mavlink
deleted file mode 160000
index fdc5376c7251fb044a7cbf2f21f82ba5a8d1e6e9..0000000000000000000000000000000000000000
--- a/mavlink
+++ /dev/null
@@ -1 +0,0 @@
-Subproject commit fdc5376c7251fb044a7cbf2f21f82ba5a8d1e6e9
diff --git a/mavlink_lib.py b/mavlink_lib.py
deleted file mode 100644
index 88b070e5d3c619324a5a6946e43f5e95c7069f37..0000000000000000000000000000000000000000
--- a/mavlink_lib.py
+++ /dev/null
@@ -1,4748 +0,0 @@
-'''
-MAVLink protocol implementation (auto-generated by mavgen.py)
-
-Generated from: lyra.xml
-
-Note: this file has been auto-generated. DO NOT EDIT
-'''
-from __future__ import print_function
-from builtins import range
-from builtins import object
-import struct, array, time, json, os, sys, platform
-
-from pymavlink.generator.mavcrc import x25crc
-import hashlib
-
-WIRE_PROTOCOL_VERSION = '1.0'
-DIALECT = 'mavlink_lib'
-
-PROTOCOL_MARKER_V1 = 0xFE
-PROTOCOL_MARKER_V2 = 0xFD
-HEADER_LEN_V1 = 6
-HEADER_LEN_V2 = 10
-
-MAVLINK_SIGNATURE_BLOCK_LEN = 13
-
-MAVLINK_IFLAG_SIGNED = 0x01
-
-native_supported = platform.system() != 'Windows' # Not yet supported on other dialects
-native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants
-native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared
-
-if native_supported and float(WIRE_PROTOCOL_VERSION) <= 1:
- try:
- import mavnative
- except ImportError:
- print('ERROR LOADING MAVNATIVE - falling back to python implementation')
- native_supported = False
-else:
- # mavnative isn't supported for MAVLink2 yet
- native_supported = False
-
-# allow MAV_IGNORE_CRC=1 to ignore CRC, allowing some
-# corrupted msgs to be seen
-MAVLINK_IGNORE_CRC = os.environ.get("MAV_IGNORE_CRC",0)
-
-# some base types from mavlink_types.h
-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
-
-
-# swiped from DFReader.py
-def to_string(s):
- '''desperate attempt to convert a string regardless of what garbage we get'''
- try:
- return s.decode("utf-8")
- except Exception as e:
- pass
- try:
- s2 = s.encode('utf-8', 'ignore')
- x = u"%s" % s2
- return s2
- except Exception:
- pass
- # so it's a nasty one. Let's grab as many characters as we can
- r = ''
- try:
- for c in s:
- r2 = r + c
- r2 = r2.encode('ascii', 'ignore')
- x = u"%s" % r2
- r = r2
- except Exception:
- pass
- return r + '_XXX'
-
-
-class MAVLink_header(object):
- '''MAVLink message header'''
- def __init__(self, msgId, incompat_flags=0, compat_flags=0, mlen=0, seq=0, srcSystem=0, srcComponent=0):
- self.mlen = mlen
- self.seq = seq
- self.srcSystem = srcSystem
- self.srcComponent = srcComponent
- self.msgId = msgId
- self.incompat_flags = incompat_flags
- self.compat_flags = compat_flags
-
- def pack(self, force_mavlink1=False):
- if WIRE_PROTOCOL_VERSION == '2.0' and not force_mavlink1:
- return struct.pack('<BBBBBBBHB', 254, self.mlen,
- self.incompat_flags, self.compat_flags,
- self.seq, self.srcSystem, self.srcComponent,
- self.msgId&0xFFFF, self.msgId>>16)
- return struct.pack('<BBBBBB', PROTOCOL_MARKER_V1, self.mlen, self.seq,
- self.srcSystem, self.srcComponent, self.msgId)
-
-class MAVLink_message(object):
- '''base MAVLink message class'''
- def __init__(self, msgId, name):
- self._header = MAVLink_header(msgId)
- self._payload = None
- self._msgbuf = None
- self._crc = None
- self._fieldnames = []
- self._type = name
- self._signed = False
- self._link_id = None
- self._instances = None
- self._instance_field = None
-
- def format_attr(self, field):
- '''override field getter'''
- raw_attr = getattr(self,field)
- if isinstance(raw_attr, bytes):
- raw_attr = to_string(raw_attr).rstrip("\00")
- return raw_attr
-
- def get_msgbuf(self):
- if isinstance(self._msgbuf, bytearray):
- return self._msgbuf
- return bytearray(self._msgbuf)
-
- def get_header(self):
- return self._header
-
- def get_payload(self):
- return self._payload
-
- def get_crc(self):
- return self._crc
-
- def get_fieldnames(self):
- return self._fieldnames
-
- def get_type(self):
- return self._type
-
- def get_msgId(self):
- return self._header.msgId
-
- def get_srcSystem(self):
- return self._header.srcSystem
-
- def get_srcComponent(self):
- return self._header.srcComponent
-
- def get_seq(self):
- return self._header.seq
-
- def get_signed(self):
- return self._signed
-
- def get_link_id(self):
- return self._link_id
-
- def __str__(self):
- ret = '%s {' % self._type
- for a in self._fieldnames:
- v = self.format_attr(a)
- ret += '%s : %s, ' % (a, v)
- ret = ret[0:-2] + '}'
- return ret
-
- def __ne__(self, other):
- return not self.__eq__(other)
-
- def __eq__(self, other):
- if other is None:
- return False
-
- if self.get_type() != other.get_type():
- return False
-
- # We do not compare CRC because native code doesn't provide it
- #if self.get_crc() != other.get_crc():
- # return False
-
- if self.get_seq() != other.get_seq():
- return False
-
- if self.get_srcSystem() != other.get_srcSystem():
- return False
-
- if self.get_srcComponent() != other.get_srcComponent():
- return False
-
- for a in self._fieldnames:
- if self.format_attr(a) != other.format_attr(a):
- return False
-
- return True
-
- def to_dict(self):
- d = dict({})
- d['mavpackettype'] = self._type
- for a in self._fieldnames:
- d[a] = self.format_attr(a)
- return d
-
- def to_json(self):
- return json.dumps(self.to_dict())
-
- def sign_packet(self, mav):
- h = hashlib.new('sha256')
- self._msgbuf += struct.pack('<BQ', mav.signing.link_id, mav.signing.timestamp)[:7]
- h.update(mav.signing.secret_key)
- h.update(self._msgbuf)
- sig = h.digest()[:6]
- self._msgbuf += sig
- mav.signing.timestamp += 1
-
- def pack(self, mav, crc_extra, payload, force_mavlink1=False):
- plen = len(payload)
- if WIRE_PROTOCOL_VERSION != '1.0' and not force_mavlink1:
- # in MAVLink2 we can strip trailing zeros off payloads. This allows for simple
- # variable length arrays and smaller packets
- nullbyte = chr(0)
- # in Python2, type("fred') is str but also type("fred")==bytes
- if str(type(payload)) == "<class 'bytes'>":
- nullbyte = 0
- while plen > 1 and payload[plen-1] == nullbyte:
- plen -= 1
- self._payload = payload[:plen]
- incompat_flags = 0
- if mav.signing.sign_outgoing:
- incompat_flags |= MAVLINK_IFLAG_SIGNED
- self._header = MAVLink_header(self._header.msgId,
- incompat_flags=incompat_flags, compat_flags=0,
- mlen=len(self._payload), seq=mav.seq,
- srcSystem=mav.srcSystem, srcComponent=mav.srcComponent)
- self._msgbuf = self._header.pack(force_mavlink1=force_mavlink1) + self._payload
- crc = x25crc(self._msgbuf[1:])
- if True: # using CRC extra
- crc.accumulate_str(struct.pack('B', crc_extra))
- self._crc = crc.crc
- self._msgbuf += struct.pack('<H', self._crc)
- if mav.signing.sign_outgoing and not force_mavlink1:
- self.sign_packet(mav)
- return self._msgbuf
-
- def __getitem__(self, key):
- '''support indexing, allowing for multi-instance sensors in one message'''
- if self._instances is None:
- raise IndexError()
- if not key in self._instances:
- raise IndexError()
- return self._instances[key]
-
-
-# enums
-
-class EnumEntry(object):
- def __init__(self, name, description):
- self.name = name
- self.description = description
- self.param = {}
-
-enums = {}
-
-# SysIDs
-enums['SysIDs'] = {}
-MAV_SYSID_MAIN = 1 #
-enums['SysIDs'][1] = EnumEntry('MAV_SYSID_MAIN', '''''')
-MAV_SYSID_PAYLOAD = 2 #
-enums['SysIDs'][2] = EnumEntry('MAV_SYSID_PAYLOAD', '''''')
-MAV_SYSID_RIG = 3 #
-enums['SysIDs'][3] = EnumEntry('MAV_SYSID_RIG', '''''')
-MAV_SYSID_GS = 4 #
-enums['SysIDs'][4] = EnumEntry('MAV_SYSID_GS', '''''')
-SysIDs_ENUM_END = 5 #
-enums['SysIDs'][5] = EnumEntry('SysIDs_ENUM_END', '''''')
-
-# SystemTMList
-enums['SystemTMList'] = {}
-MAV_SYS_ID = 1 # State of init results about system hardware/software components
-enums['SystemTMList'][1] = EnumEntry('MAV_SYS_ID', '''State of init results about system hardware/software components''')
-MAV_FSM_ID = 2 # States of all On-Board FSMs
-enums['SystemTMList'][2] = EnumEntry('MAV_FSM_ID', '''States of all On-Board FSMs''')
-MAV_PIN_OBS_ID = 3 # Pin observer data
-enums['SystemTMList'][3] = EnumEntry('MAV_PIN_OBS_ID', '''Pin observer data''')
-MAV_LOGGER_ID = 4 # SD Logger stats
-enums['SystemTMList'][4] = EnumEntry('MAV_LOGGER_ID', '''SD Logger stats''')
-MAV_MAVLINK_STATS = 5 # Mavlink driver stats
-enums['SystemTMList'][5] = EnumEntry('MAV_MAVLINK_STATS', '''Mavlink driver stats''')
-MAV_TASK_STATS_ID = 6 # Task scheduler statistics answer: n mavlink messages where n is the
- # number of tasks
-enums['SystemTMList'][6] = EnumEntry('MAV_TASK_STATS_ID', '''Task scheduler statistics answer: n mavlink messages where n is the number of tasks''')
-MAV_ADA_ID = 7 # ADA Status
-enums['SystemTMList'][7] = EnumEntry('MAV_ADA_ID', '''ADA Status''')
-MAV_NAS_ID = 8 # NavigationSystem data
-enums['SystemTMList'][8] = EnumEntry('MAV_NAS_ID', '''NavigationSystem data''')
-MAV_MEA_ID = 9 # MEA Status
-enums['SystemTMList'][9] = EnumEntry('MAV_MEA_ID', '''MEA Status''')
-MAV_CAN_ID = 10 # Canbus stats
-enums['SystemTMList'][10] = EnumEntry('MAV_CAN_ID', '''Canbus stats''')
-MAV_FLIGHT_ID = 11 # Flight telemetry
-enums['SystemTMList'][11] = EnumEntry('MAV_FLIGHT_ID', '''Flight telemetry''')
-MAV_STATS_ID = 12 # Satistics telemetry
-enums['SystemTMList'][12] = EnumEntry('MAV_STATS_ID', '''Satistics telemetry''')
-MAV_SENSORS_STATE_ID = 13 # Sensors init state telemetry
-enums['SystemTMList'][13] = EnumEntry('MAV_SENSORS_STATE_ID', '''Sensors init state telemetry''')
-MAV_GSE_ID = 14 # Ground Segnement Equipment
-enums['SystemTMList'][14] = EnumEntry('MAV_GSE_ID', '''Ground Segnement Equipment''')
-MAV_MOTOR_ID = 15 # Rocket Motor data
-enums['SystemTMList'][15] = EnumEntry('MAV_MOTOR_ID', '''Rocket Motor data''')
-SystemTMList_ENUM_END = 16 #
-enums['SystemTMList'][16] = EnumEntry('SystemTMList_ENUM_END', '''''')
-
-# SensorsTMList
-enums['SensorsTMList'] = {}
-MAV_GPS_ID = 1 # GPS data
-enums['SensorsTMList'][1] = EnumEntry('MAV_GPS_ID', '''GPS data''')
-MAV_BMX160_ID = 2 # BMX160 IMU data
-enums['SensorsTMList'][2] = EnumEntry('MAV_BMX160_ID', '''BMX160 IMU data''')
-MAV_VN100_ID = 3 # VN100 IMU data
-enums['SensorsTMList'][3] = EnumEntry('MAV_VN100_ID', '''VN100 IMU data''')
-MAV_MPU9250_ID = 4 # MPU9250 IMU data
-enums['SensorsTMList'][4] = EnumEntry('MAV_MPU9250_ID', '''MPU9250 IMU data''')
-MAV_ADS_ID = 5 # ADS 8 channel ADC data
-enums['SensorsTMList'][5] = EnumEntry('MAV_ADS_ID', '''ADS 8 channel ADC data''')
-MAV_MS5803_ID = 6 # MS5803 barometer data
-enums['SensorsTMList'][6] = EnumEntry('MAV_MS5803_ID', '''MS5803 barometer data''')
-MAV_BME280_ID = 7 # BME280 barometer data
-enums['SensorsTMList'][7] = EnumEntry('MAV_BME280_ID', '''BME280 barometer data''')
-MAV_CURRENT_SENSE_ID = 8 # Electrical current sensors data
-enums['SensorsTMList'][8] = EnumEntry('MAV_CURRENT_SENSE_ID', '''Electrical current sensors data''')
-MAV_LIS3MDL_ID = 9 # LIS3MDL compass data
-enums['SensorsTMList'][9] = EnumEntry('MAV_LIS3MDL_ID', '''LIS3MDL compass data''')
-MAV_DPL_PRESS_ID = 10 # Deployment pressure data
-enums['SensorsTMList'][10] = EnumEntry('MAV_DPL_PRESS_ID', '''Deployment pressure data''')
-MAV_STATIC_PRESS_ID = 11 # Static pressure data
-enums['SensorsTMList'][11] = EnumEntry('MAV_STATIC_PRESS_ID', '''Static pressure data''')
-MAV_PITOT_PRESS_ID = 12 # Pitot pressure data
-enums['SensorsTMList'][12] = EnumEntry('MAV_PITOT_PRESS_ID', '''Pitot pressure data''')
-MAV_BATTERY_VOLTAGE_ID = 13 # Battery voltage data
-enums['SensorsTMList'][13] = EnumEntry('MAV_BATTERY_VOLTAGE_ID', '''Battery voltage data''')
-MAV_LOAD_CELL_ID = 14 # Load cell data
-enums['SensorsTMList'][14] = EnumEntry('MAV_LOAD_CELL_ID', '''Load cell data''')
-MAV_FILLING_PRESS_ID = 15 # Filling line pressure
-enums['SensorsTMList'][15] = EnumEntry('MAV_FILLING_PRESS_ID', '''Filling line pressure''')
-MAV_TANK_TOP_PRESS_ID = 16 # Top tank pressure
-enums['SensorsTMList'][16] = EnumEntry('MAV_TANK_TOP_PRESS_ID', '''Top tank pressure''')
-MAV_TANK_BOTTOM_PRESS_ID = 17 # Bottom tank pressure
-enums['SensorsTMList'][17] = EnumEntry('MAV_TANK_BOTTOM_PRESS_ID', '''Bottom tank pressure''')
-MAV_TANK_TEMP_ID = 18 # Tank temperature
-enums['SensorsTMList'][18] = EnumEntry('MAV_TANK_TEMP_ID', '''Tank temperature''')
-MAV_COMBUSTION_PRESS_ID = 19 # Combustion chamber pressure
-enums['SensorsTMList'][19] = EnumEntry('MAV_COMBUSTION_PRESS_ID', '''Combustion chamber pressure''')
-MAV_VESSEL_PRESS_ID = 20 # Vessel pressure
-enums['SensorsTMList'][20] = EnumEntry('MAV_VESSEL_PRESS_ID', '''Vessel pressure''')
-MAV_LOAD_CELL_VESSEL_ID = 21 # Vessel tank weight
-enums['SensorsTMList'][21] = EnumEntry('MAV_LOAD_CELL_VESSEL_ID', '''Vessel tank weight''')
-MAV_LOAD_CELL_TANK_ID = 22 # Tank weight
-enums['SensorsTMList'][22] = EnumEntry('MAV_LOAD_CELL_TANK_ID', '''Tank weight''')
-MAV_LIS2MDL_ID = 23 # Magnetometer data
-enums['SensorsTMList'][23] = EnumEntry('MAV_LIS2MDL_ID', '''Magnetometer data''')
-MAV_LPS28DFW_ID = 24 # Pressure sensor data
-enums['SensorsTMList'][24] = EnumEntry('MAV_LPS28DFW_ID', '''Pressure sensor data''')
-MAV_LSM6DSRX_ID = 25 # IMU data
-enums['SensorsTMList'][25] = EnumEntry('MAV_LSM6DSRX_ID', '''IMU data''')
-MAV_H3LIS331DL_ID = 26 # 400G accelerometer
-enums['SensorsTMList'][26] = EnumEntry('MAV_H3LIS331DL_ID', '''400G accelerometer''')
-MAV_LPS22DF_ID = 27 # Pressure sensor data
-enums['SensorsTMList'][27] = EnumEntry('MAV_LPS22DF_ID', '''Pressure sensor data''')
-SensorsTMList_ENUM_END = 28 #
-enums['SensorsTMList'][28] = EnumEntry('SensorsTMList_ENUM_END', '''''')
-
-# MavCommandList
-enums['MavCommandList'] = {}
-MAV_CMD_ARM = 1 # Command to arm the rocket
-enums['MavCommandList'][1] = EnumEntry('MAV_CMD_ARM', '''Command to arm the rocket''')
-MAV_CMD_DISARM = 2 # Command to disarm the rocket
-enums['MavCommandList'][2] = EnumEntry('MAV_CMD_DISARM', '''Command to disarm the rocket''')
-MAV_CMD_CALIBRATE = 3 # Command to trigger the calibration
-enums['MavCommandList'][3] = EnumEntry('MAV_CMD_CALIBRATE', '''Command to trigger the calibration''')
-MAV_CMD_SAVE_CALIBRATION = 4 # Command to save the current calibration into a file
-enums['MavCommandList'][4] = EnumEntry('MAV_CMD_SAVE_CALIBRATION', '''Command to save the current calibration into a file''')
-MAV_CMD_FORCE_INIT = 5 # Command to init the rocket
-enums['MavCommandList'][5] = EnumEntry('MAV_CMD_FORCE_INIT', '''Command to init the rocket''')
-MAV_CMD_FORCE_LAUNCH = 6 # Command to force the launch state on the rocket
-enums['MavCommandList'][6] = EnumEntry('MAV_CMD_FORCE_LAUNCH', '''Command to force the launch state on the rocket''')
-MAV_CMD_FORCE_LANDING = 7 # Command to communicate the end of the mission and close the file
- # descriptors in the SD card
-enums['MavCommandList'][7] = EnumEntry('MAV_CMD_FORCE_LANDING', '''Command to communicate the end of the mission and close the file descriptors in the SD card''')
-MAV_CMD_FORCE_APOGEE = 8 # Command to trigger the apogee event
-enums['MavCommandList'][8] = EnumEntry('MAV_CMD_FORCE_APOGEE', '''Command to trigger the apogee event''')
-MAV_CMD_FORCE_EXPULSION = 9 # Command to open the nosecone
-enums['MavCommandList'][9] = EnumEntry('MAV_CMD_FORCE_EXPULSION', '''Command to open the nosecone''')
-MAV_CMD_FORCE_DEPLOYMENT = 10 # Command to activate the thermal cutters and cut the drogue, activating
- # both thermal cutters sequentially
-enums['MavCommandList'][10] = EnumEntry('MAV_CMD_FORCE_DEPLOYMENT', '''Command to activate the thermal cutters and cut the drogue, activating both thermal cutters sequentially''')
-MAV_CMD_START_LOGGING = 11 # Command to enable sensor logging
-enums['MavCommandList'][11] = EnumEntry('MAV_CMD_START_LOGGING', '''Command to enable sensor logging''')
-MAV_CMD_STOP_LOGGING = 12 # Command to permanently close the log file
-enums['MavCommandList'][12] = EnumEntry('MAV_CMD_STOP_LOGGING', '''Command to permanently close the log file''')
-MAV_CMD_FORCE_REBOOT = 13 # Command to reset the board from test status
-enums['MavCommandList'][13] = EnumEntry('MAV_CMD_FORCE_REBOOT', '''Command to reset the board from test status''')
-MAV_CMD_ENTER_TEST_MODE = 14 # Command to enter the test mode
-enums['MavCommandList'][14] = EnumEntry('MAV_CMD_ENTER_TEST_MODE', '''Command to enter the test mode''')
-MAV_CMD_EXIT_TEST_MODE = 15 # Command to exit the test mode
-enums['MavCommandList'][15] = EnumEntry('MAV_CMD_EXIT_TEST_MODE', '''Command to exit the test mode''')
-MAV_CMD_START_RECORDING = 16 # Command to start the internal cameras recordings
-enums['MavCommandList'][16] = EnumEntry('MAV_CMD_START_RECORDING', '''Command to start the internal cameras recordings''')
-MAV_CMD_STOP_RECORDING = 17 # Command to stop the internal cameras recordings
-enums['MavCommandList'][17] = EnumEntry('MAV_CMD_STOP_RECORDING', '''Command to stop the internal cameras recordings''')
-MavCommandList_ENUM_END = 18 #
-enums['MavCommandList'][18] = EnumEntry('MavCommandList_ENUM_END', '''''')
-
-# ServosList
-enums['ServosList'] = {}
-AIR_BRAKES_SERVO = 1 #
-enums['ServosList'][1] = EnumEntry('AIR_BRAKES_SERVO', '''''')
-EXPULSION_SERVO = 2 #
-enums['ServosList'][2] = EnumEntry('EXPULSION_SERVO', '''''')
-PARAFOIL_LEFT_SERVO = 3 #
-enums['ServosList'][3] = EnumEntry('PARAFOIL_LEFT_SERVO', '''''')
-PARAFOIL_RIGHT_SERVO = 4 #
-enums['ServosList'][4] = EnumEntry('PARAFOIL_RIGHT_SERVO', '''''')
-MAIN_VALVE = 5 #
-enums['ServosList'][5] = EnumEntry('MAIN_VALVE', '''''')
-VENTING_VALVE = 6 #
-enums['ServosList'][6] = EnumEntry('VENTING_VALVE', '''''')
-RELEASE_VALVE = 7 #
-enums['ServosList'][7] = EnumEntry('RELEASE_VALVE', '''''')
-FILLING_VALVE = 8 #
-enums['ServosList'][8] = EnumEntry('FILLING_VALVE', '''''')
-DISCONNECT_SERVO = 9 #
-enums['ServosList'][9] = EnumEntry('DISCONNECT_SERVO', '''''')
-ServosList_ENUM_END = 10 #
-enums['ServosList'][10] = EnumEntry('ServosList_ENUM_END', '''''')
-
-# StepperList
-enums['StepperList'] = {}
-STEPPER_X = 1 #
-enums['StepperList'][1] = EnumEntry('STEPPER_X', '''''')
-STEPPER_Y = 2 #
-enums['StepperList'][2] = EnumEntry('STEPPER_Y', '''''')
-StepperList_ENUM_END = 3 #
-enums['StepperList'][3] = EnumEntry('StepperList_ENUM_END', '''''')
-
-# PinsList
-enums['PinsList'] = {}
-LAUNCH_PIN = 1 #
-enums['PinsList'][1] = EnumEntry('LAUNCH_PIN', '''''')
-NOSECONE_PIN = 2 #
-enums['PinsList'][2] = EnumEntry('NOSECONE_PIN', '''''')
-DEPLOYMENT_PIN = 3 #
-enums['PinsList'][3] = EnumEntry('DEPLOYMENT_PIN', '''''')
-QUICK_CONNECTOR_PIN = 4 #
-enums['PinsList'][4] = EnumEntry('QUICK_CONNECTOR_PIN', '''''')
-PinsList_ENUM_END = 5 #
-enums['PinsList'][5] = EnumEntry('PinsList_ENUM_END', '''''')
-
-# message IDs
-MAVLINK_MSG_ID_BAD_DATA = -1
-MAVLINK_MSG_ID_UNKNOWN = -2
-MAVLINK_MSG_ID_PING_TC = 1
-MAVLINK_MSG_ID_COMMAND_TC = 2
-MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC = 3
-MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC = 4
-MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC = 5
-MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC = 6
-MAVLINK_MSG_ID_WIGGLE_SERVO_TC = 7
-MAVLINK_MSG_ID_RESET_SERVO_TC = 8
-MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC = 9
-MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC = 10
-MAVLINK_MSG_ID_SET_ORIENTATION_TC = 11
-MAVLINK_MSG_ID_SET_COORDINATES_TC = 12
-MAVLINK_MSG_ID_RAW_EVENT_TC = 13
-MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC = 14
-MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC = 15
-MAVLINK_MSG_ID_SET_ALGORITHM_TC = 16
-MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC = 17
-MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC = 18
-MAVLINK_MSG_ID_CONRIG_STATE_TC = 19
-MAVLINK_MSG_ID_SET_IGNITION_TIME_TC = 20
-MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC = 21
-MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC = 22
-MAVLINK_MSG_ID_ACK_TM = 100
-MAVLINK_MSG_ID_NACK_TM = 101
-MAVLINK_MSG_ID_GPS_TM = 102
-MAVLINK_MSG_ID_IMU_TM = 103
-MAVLINK_MSG_ID_PRESSURE_TM = 104
-MAVLINK_MSG_ID_ADC_TM = 105
-MAVLINK_MSG_ID_VOLTAGE_TM = 106
-MAVLINK_MSG_ID_CURRENT_TM = 107
-MAVLINK_MSG_ID_TEMP_TM = 108
-MAVLINK_MSG_ID_LOAD_TM = 109
-MAVLINK_MSG_ID_ATTITUDE_TM = 110
-MAVLINK_MSG_ID_SENSOR_STATE_TM = 111
-MAVLINK_MSG_ID_SERVO_TM = 112
-MAVLINK_MSG_ID_PIN_TM = 113
-MAVLINK_MSG_ID_RECEIVER_TM = 150
-MAVLINK_MSG_ID_ARP_TM = 169
-MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC = 170
-MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC = 171
-MAVLINK_MSG_ID_SYS_TM = 200
-MAVLINK_MSG_ID_FSM_TM = 201
-MAVLINK_MSG_ID_LOGGER_TM = 202
-MAVLINK_MSG_ID_MAVLINK_STATS_TM = 203
-MAVLINK_MSG_ID_TASK_STATS_TM = 204
-MAVLINK_MSG_ID_ADA_TM = 205
-MAVLINK_MSG_ID_NAS_TM = 206
-MAVLINK_MSG_ID_MEA_TM = 207
-MAVLINK_MSG_ID_ROCKET_FLIGHT_TM = 208
-MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM = 209
-MAVLINK_MSG_ID_ROCKET_STATS_TM = 210
-MAVLINK_MSG_ID_PAYLOAD_STATS_TM = 211
-MAVLINK_MSG_ID_GSE_TM = 212
-MAVLINK_MSG_ID_MOTOR_TM = 213
-
-class MAVLink_ping_tc_message(MAVLink_message):
- '''
- TC to ping the rocket (expects an ACK message as a response)
- '''
- id = MAVLINK_MSG_ID_PING_TC
- name = 'PING_TC'
- fieldnames = ['timestamp']
- ordered_fieldnames = ['timestamp']
- fieldtypes = ['uint64_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {}
- format = '<Q'
- native_format = bytearray('<Q', 'ascii')
- orders = [0]
- lengths = [1]
- array_lengths = [0]
- crc_extra = 136
- unpacker = struct.Struct('<Q')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp):
- MAVLink_message.__init__(self, MAVLink_ping_tc_message.id, MAVLink_ping_tc_message.name)
- self._fieldnames = MAVLink_ping_tc_message.fieldnames
- self._instance_field = MAVLink_ping_tc_message.instance_field
- self._instance_offset = MAVLink_ping_tc_message.instance_offset
- self.timestamp = timestamp
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 136, struct.pack('<Q', self.timestamp), force_mavlink1=force_mavlink1)
-
-class MAVLink_command_tc_message(MAVLink_message):
- '''
- TC containing a command with no parameters that trigger some
- action
- '''
- id = MAVLINK_MSG_ID_COMMAND_TC
- name = 'COMMAND_TC'
- fieldnames = ['command_id']
- ordered_fieldnames = ['command_id']
- fieldtypes = ['uint8_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {}
- format = '<B'
- native_format = bytearray('<B', 'ascii')
- orders = [0]
- lengths = [1]
- array_lengths = [0]
- crc_extra = 198
- unpacker = struct.Struct('<B')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, command_id):
- MAVLink_message.__init__(self, MAVLink_command_tc_message.id, MAVLink_command_tc_message.name)
- self._fieldnames = MAVLink_command_tc_message.fieldnames
- self._instance_field = MAVLink_command_tc_message.instance_field
- self._instance_offset = MAVLink_command_tc_message.instance_offset
- self.command_id = command_id
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 198, struct.pack('<B', self.command_id), force_mavlink1=force_mavlink1)
-
-class MAVLink_system_tm_request_tc_message(MAVLink_message):
- '''
- TC containing a request for the status of a board
- '''
- id = MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC
- name = 'SYSTEM_TM_REQUEST_TC'
- fieldnames = ['tm_id']
- ordered_fieldnames = ['tm_id']
- fieldtypes = ['uint8_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {}
- format = '<B'
- native_format = bytearray('<B', 'ascii')
- orders = [0]
- lengths = [1]
- array_lengths = [0]
- crc_extra = 165
- unpacker = struct.Struct('<B')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, tm_id):
- MAVLink_message.__init__(self, MAVLink_system_tm_request_tc_message.id, MAVLink_system_tm_request_tc_message.name)
- self._fieldnames = MAVLink_system_tm_request_tc_message.fieldnames
- self._instance_field = MAVLink_system_tm_request_tc_message.instance_field
- self._instance_offset = MAVLink_system_tm_request_tc_message.instance_offset
- self.tm_id = tm_id
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 165, struct.pack('<B', self.tm_id), force_mavlink1=force_mavlink1)
-
-class MAVLink_sensor_tm_request_tc_message(MAVLink_message):
- '''
- TC containing a request for sensors telemetry
- '''
- id = MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC
- name = 'SENSOR_TM_REQUEST_TC'
- fieldnames = ['sensor_name']
- ordered_fieldnames = ['sensor_name']
- fieldtypes = ['uint8_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {}
- format = '<B'
- native_format = bytearray('<B', 'ascii')
- orders = [0]
- lengths = [1]
- array_lengths = [0]
- crc_extra = 248
- unpacker = struct.Struct('<B')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, sensor_name):
- MAVLink_message.__init__(self, MAVLink_sensor_tm_request_tc_message.id, MAVLink_sensor_tm_request_tc_message.name)
- self._fieldnames = MAVLink_sensor_tm_request_tc_message.fieldnames
- self._instance_field = MAVLink_sensor_tm_request_tc_message.instance_field
- self._instance_offset = MAVLink_sensor_tm_request_tc_message.instance_offset
- self.sensor_name = sensor_name
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 248, struct.pack('<B', self.sensor_name), force_mavlink1=force_mavlink1)
-
-class MAVLink_servo_tm_request_tc_message(MAVLink_message):
- '''
- TC containing a request for servo telemetry
- '''
- id = MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC
- name = 'SERVO_TM_REQUEST_TC'
- fieldnames = ['servo_id']
- ordered_fieldnames = ['servo_id']
- fieldtypes = ['uint8_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {}
- format = '<B'
- native_format = bytearray('<B', 'ascii')
- orders = [0]
- lengths = [1]
- array_lengths = [0]
- crc_extra = 184
- unpacker = struct.Struct('<B')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, servo_id):
- MAVLink_message.__init__(self, MAVLink_servo_tm_request_tc_message.id, MAVLink_servo_tm_request_tc_message.name)
- self._fieldnames = MAVLink_servo_tm_request_tc_message.fieldnames
- self._instance_field = MAVLink_servo_tm_request_tc_message.instance_field
- self._instance_offset = MAVLink_servo_tm_request_tc_message.instance_offset
- self.servo_id = servo_id
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 184, struct.pack('<B', self.servo_id), force_mavlink1=force_mavlink1)
-
-class MAVLink_set_servo_angle_tc_message(MAVLink_message):
- '''
- Sets the angle of a certain servo
- '''
- id = MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC
- name = 'SET_SERVO_ANGLE_TC'
- fieldnames = ['servo_id', 'angle']
- ordered_fieldnames = ['angle', 'servo_id']
- fieldtypes = ['uint8_t', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {}
- format = '<fB'
- native_format = bytearray('<fB', 'ascii')
- orders = [1, 0]
- lengths = [1, 1]
- array_lengths = [0, 0]
- crc_extra = 215
- unpacker = struct.Struct('<fB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, servo_id, angle):
- MAVLink_message.__init__(self, MAVLink_set_servo_angle_tc_message.id, MAVLink_set_servo_angle_tc_message.name)
- self._fieldnames = MAVLink_set_servo_angle_tc_message.fieldnames
- self._instance_field = MAVLink_set_servo_angle_tc_message.instance_field
- self._instance_offset = MAVLink_set_servo_angle_tc_message.instance_offset
- self.servo_id = servo_id
- self.angle = angle
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 215, struct.pack('<fB', self.angle, self.servo_id), force_mavlink1=force_mavlink1)
-
-class MAVLink_wiggle_servo_tc_message(MAVLink_message):
- '''
- Wiggles the specified servo
- '''
- id = MAVLINK_MSG_ID_WIGGLE_SERVO_TC
- name = 'WIGGLE_SERVO_TC'
- fieldnames = ['servo_id']
- ordered_fieldnames = ['servo_id']
- fieldtypes = ['uint8_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {}
- format = '<B'
- native_format = bytearray('<B', 'ascii')
- orders = [0]
- lengths = [1]
- array_lengths = [0]
- crc_extra = 160
- unpacker = struct.Struct('<B')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, servo_id):
- MAVLink_message.__init__(self, MAVLink_wiggle_servo_tc_message.id, MAVLink_wiggle_servo_tc_message.name)
- self._fieldnames = MAVLink_wiggle_servo_tc_message.fieldnames
- self._instance_field = MAVLink_wiggle_servo_tc_message.instance_field
- self._instance_offset = MAVLink_wiggle_servo_tc_message.instance_offset
- self.servo_id = servo_id
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 160, struct.pack('<B', self.servo_id), force_mavlink1=force_mavlink1)
-
-class MAVLink_reset_servo_tc_message(MAVLink_message):
- '''
- Resets the specified servo
- '''
- id = MAVLINK_MSG_ID_RESET_SERVO_TC
- name = 'RESET_SERVO_TC'
- fieldnames = ['servo_id']
- ordered_fieldnames = ['servo_id']
- fieldtypes = ['uint8_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {}
- format = '<B'
- native_format = bytearray('<B', 'ascii')
- orders = [0]
- lengths = [1]
- array_lengths = [0]
- crc_extra = 226
- unpacker = struct.Struct('<B')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, servo_id):
- MAVLink_message.__init__(self, MAVLink_reset_servo_tc_message.id, MAVLink_reset_servo_tc_message.name)
- self._fieldnames = MAVLink_reset_servo_tc_message.fieldnames
- self._instance_field = MAVLink_reset_servo_tc_message.instance_field
- self._instance_offset = MAVLink_reset_servo_tc_message.instance_offset
- self.servo_id = servo_id
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 226, struct.pack('<B', self.servo_id), force_mavlink1=force_mavlink1)
-
-class MAVLink_set_reference_altitude_tc_message(MAVLink_message):
- '''
- Sets the reference altitude for the altimeter
- '''
- id = MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC
- name = 'SET_REFERENCE_ALTITUDE_TC'
- fieldnames = ['ref_altitude']
- ordered_fieldnames = ['ref_altitude']
- fieldtypes = ['float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"ref_altitude": "m"}
- format = '<f'
- native_format = bytearray('<f', 'ascii')
- orders = [0]
- lengths = [1]
- array_lengths = [0]
- crc_extra = 113
- unpacker = struct.Struct('<f')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, ref_altitude):
- MAVLink_message.__init__(self, MAVLink_set_reference_altitude_tc_message.id, MAVLink_set_reference_altitude_tc_message.name)
- self._fieldnames = MAVLink_set_reference_altitude_tc_message.fieldnames
- self._instance_field = MAVLink_set_reference_altitude_tc_message.instance_field
- self._instance_offset = MAVLink_set_reference_altitude_tc_message.instance_offset
- self.ref_altitude = ref_altitude
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 113, struct.pack('<f', self.ref_altitude), force_mavlink1=force_mavlink1)
-
-class MAVLink_set_reference_temperature_tc_message(MAVLink_message):
- '''
- Sets the reference temperature for the altimeter
- '''
- id = MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC
- name = 'SET_REFERENCE_TEMPERATURE_TC'
- fieldnames = ['ref_temp']
- ordered_fieldnames = ['ref_temp']
- fieldtypes = ['float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"ref_temp": "degC"}
- format = '<f'
- native_format = bytearray('<f', 'ascii')
- orders = [0]
- lengths = [1]
- array_lengths = [0]
- crc_extra = 38
- unpacker = struct.Struct('<f')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, ref_temp):
- MAVLink_message.__init__(self, MAVLink_set_reference_temperature_tc_message.id, MAVLink_set_reference_temperature_tc_message.name)
- self._fieldnames = MAVLink_set_reference_temperature_tc_message.fieldnames
- self._instance_field = MAVLink_set_reference_temperature_tc_message.instance_field
- self._instance_offset = MAVLink_set_reference_temperature_tc_message.instance_offset
- self.ref_temp = ref_temp
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 38, struct.pack('<f', self.ref_temp), force_mavlink1=force_mavlink1)
-
-class MAVLink_set_orientation_tc_message(MAVLink_message):
- '''
- Sets current orientation for the navigation system
- '''
- id = MAVLINK_MSG_ID_SET_ORIENTATION_TC
- name = 'SET_ORIENTATION_TC'
- fieldnames = ['yaw', 'pitch', 'roll']
- ordered_fieldnames = ['yaw', 'pitch', 'roll']
- fieldtypes = ['float', 'float', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"yaw": "deg", "pitch": "deg", "roll": "deg"}
- format = '<fff'
- native_format = bytearray('<fff', 'ascii')
- orders = [0, 1, 2]
- lengths = [1, 1, 1]
- array_lengths = [0, 0, 0]
- crc_extra = 71
- unpacker = struct.Struct('<fff')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, yaw, pitch, roll):
- MAVLink_message.__init__(self, MAVLink_set_orientation_tc_message.id, MAVLink_set_orientation_tc_message.name)
- self._fieldnames = MAVLink_set_orientation_tc_message.fieldnames
- self._instance_field = MAVLink_set_orientation_tc_message.instance_field
- self._instance_offset = MAVLink_set_orientation_tc_message.instance_offset
- self.yaw = yaw
- self.pitch = pitch
- self.roll = roll
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 71, struct.pack('<fff', self.yaw, self.pitch, self.roll), force_mavlink1=force_mavlink1)
-
-class MAVLink_set_coordinates_tc_message(MAVLink_message):
- '''
- Sets current coordinates
- '''
- id = MAVLINK_MSG_ID_SET_COORDINATES_TC
- name = 'SET_COORDINATES_TC'
- fieldnames = ['latitude', 'longitude']
- ordered_fieldnames = ['latitude', 'longitude']
- fieldtypes = ['float', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"latitude": "deg", "longitude": "deg"}
- format = '<ff'
- native_format = bytearray('<ff', 'ascii')
- orders = [0, 1]
- lengths = [1, 1]
- array_lengths = [0, 0]
- crc_extra = 67
- unpacker = struct.Struct('<ff')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, latitude, longitude):
- MAVLink_message.__init__(self, MAVLink_set_coordinates_tc_message.id, MAVLink_set_coordinates_tc_message.name)
- self._fieldnames = MAVLink_set_coordinates_tc_message.fieldnames
- self._instance_field = MAVLink_set_coordinates_tc_message.instance_field
- self._instance_offset = MAVLink_set_coordinates_tc_message.instance_offset
- self.latitude = latitude
- self.longitude = longitude
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 67, struct.pack('<ff', self.latitude, self.longitude), force_mavlink1=force_mavlink1)
-
-class MAVLink_raw_event_tc_message(MAVLink_message):
- '''
- TC containing a raw event to be posted directly in the
- EventBroker
- '''
- id = MAVLINK_MSG_ID_RAW_EVENT_TC
- name = 'RAW_EVENT_TC'
- fieldnames = ['topic_id', 'event_id']
- ordered_fieldnames = ['topic_id', 'event_id']
- fieldtypes = ['uint8_t', 'uint8_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {}
- format = '<BB'
- native_format = bytearray('<BB', 'ascii')
- orders = [0, 1]
- lengths = [1, 1]
- array_lengths = [0, 0]
- crc_extra = 218
- unpacker = struct.Struct('<BB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, topic_id, event_id):
- MAVLink_message.__init__(self, MAVLink_raw_event_tc_message.id, MAVLink_raw_event_tc_message.name)
- self._fieldnames = MAVLink_raw_event_tc_message.fieldnames
- self._instance_field = MAVLink_raw_event_tc_message.instance_field
- self._instance_offset = MAVLink_raw_event_tc_message.instance_offset
- self.topic_id = topic_id
- self.event_id = event_id
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 218, struct.pack('<BB', self.topic_id, self.event_id), force_mavlink1=force_mavlink1)
-
-class MAVLink_set_deployment_altitude_tc_message(MAVLink_message):
- '''
- Sets the deployment altitude for the main parachute
- '''
- id = MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC
- name = 'SET_DEPLOYMENT_ALTITUDE_TC'
- fieldnames = ['dpl_altitude']
- ordered_fieldnames = ['dpl_altitude']
- fieldtypes = ['float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"dpl_altitude": "m"}
- format = '<f'
- native_format = bytearray('<f', 'ascii')
- orders = [0]
- lengths = [1]
- array_lengths = [0]
- crc_extra = 44
- unpacker = struct.Struct('<f')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, dpl_altitude):
- MAVLink_message.__init__(self, MAVLink_set_deployment_altitude_tc_message.id, MAVLink_set_deployment_altitude_tc_message.name)
- self._fieldnames = MAVLink_set_deployment_altitude_tc_message.fieldnames
- self._instance_field = MAVLink_set_deployment_altitude_tc_message.instance_field
- self._instance_offset = MAVLink_set_deployment_altitude_tc_message.instance_offset
- self.dpl_altitude = dpl_altitude
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 44, struct.pack('<f', self.dpl_altitude), force_mavlink1=force_mavlink1)
-
-class MAVLink_set_target_coordinates_tc_message(MAVLink_message):
- '''
- Sets the target coordinates
- '''
- id = MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC
- name = 'SET_TARGET_COORDINATES_TC'
- fieldnames = ['latitude', 'longitude']
- ordered_fieldnames = ['latitude', 'longitude']
- fieldtypes = ['float', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"latitude": "deg", "longitude": "deg"}
- format = '<ff'
- native_format = bytearray('<ff', 'ascii')
- orders = [0, 1]
- lengths = [1, 1]
- array_lengths = [0, 0]
- crc_extra = 81
- unpacker = struct.Struct('<ff')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, latitude, longitude):
- MAVLink_message.__init__(self, MAVLink_set_target_coordinates_tc_message.id, MAVLink_set_target_coordinates_tc_message.name)
- self._fieldnames = MAVLink_set_target_coordinates_tc_message.fieldnames
- self._instance_field = MAVLink_set_target_coordinates_tc_message.instance_field
- self._instance_offset = MAVLink_set_target_coordinates_tc_message.instance_offset
- self.latitude = latitude
- self.longitude = longitude
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 81, struct.pack('<ff', self.latitude, self.longitude), force_mavlink1=force_mavlink1)
-
-class MAVLink_set_algorithm_tc_message(MAVLink_message):
- '''
- Sets the algorithm number (for parafoil guidance and GSE tars)
- '''
- id = MAVLINK_MSG_ID_SET_ALGORITHM_TC
- name = 'SET_ALGORITHM_TC'
- fieldnames = ['algorithm_number']
- ordered_fieldnames = ['algorithm_number']
- fieldtypes = ['uint8_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {}
- format = '<B'
- native_format = bytearray('<B', 'ascii')
- orders = [0]
- lengths = [1]
- array_lengths = [0]
- crc_extra = 181
- unpacker = struct.Struct('<B')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, algorithm_number):
- MAVLink_message.__init__(self, MAVLink_set_algorithm_tc_message.id, MAVLink_set_algorithm_tc_message.name)
- self._fieldnames = MAVLink_set_algorithm_tc_message.fieldnames
- self._instance_field = MAVLink_set_algorithm_tc_message.instance_field
- self._instance_offset = MAVLink_set_algorithm_tc_message.instance_offset
- self.algorithm_number = algorithm_number
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 181, struct.pack('<B', self.algorithm_number), force_mavlink1=force_mavlink1)
-
-class MAVLink_set_atomic_valve_timing_tc_message(MAVLink_message):
- '''
- Sets the maximum time that the valves can be open atomically
- '''
- id = MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC
- name = 'SET_ATOMIC_VALVE_TIMING_TC'
- fieldnames = ['servo_id', 'maximum_timing']
- ordered_fieldnames = ['maximum_timing', 'servo_id']
- fieldtypes = ['uint8_t', 'uint32_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"maximum_timing": "ms"}
- format = '<IB'
- native_format = bytearray('<IB', 'ascii')
- orders = [1, 0]
- lengths = [1, 1]
- array_lengths = [0, 0]
- crc_extra = 110
- unpacker = struct.Struct('<IB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, servo_id, maximum_timing):
- MAVLink_message.__init__(self, MAVLink_set_atomic_valve_timing_tc_message.id, MAVLink_set_atomic_valve_timing_tc_message.name)
- self._fieldnames = MAVLink_set_atomic_valve_timing_tc_message.fieldnames
- self._instance_field = MAVLink_set_atomic_valve_timing_tc_message.instance_field
- self._instance_offset = MAVLink_set_atomic_valve_timing_tc_message.instance_offset
- self.servo_id = servo_id
- self.maximum_timing = maximum_timing
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 110, struct.pack('<IB', self.maximum_timing, self.servo_id), force_mavlink1=force_mavlink1)
-
-class MAVLink_set_valve_maximum_aperture_tc_message(MAVLink_message):
- '''
- Sets the maximum aperture of the specified valve. Set as value
- from 0 to 1
- '''
- id = MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC
- name = 'SET_VALVE_MAXIMUM_APERTURE_TC'
- fieldnames = ['servo_id', 'maximum_aperture']
- ordered_fieldnames = ['maximum_aperture', 'servo_id']
- fieldtypes = ['uint8_t', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {}
- format = '<fB'
- native_format = bytearray('<fB', 'ascii')
- orders = [1, 0]
- lengths = [1, 1]
- array_lengths = [0, 0]
- crc_extra = 22
- unpacker = struct.Struct('<fB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, servo_id, maximum_aperture):
- MAVLink_message.__init__(self, MAVLink_set_valve_maximum_aperture_tc_message.id, MAVLink_set_valve_maximum_aperture_tc_message.name)
- self._fieldnames = MAVLink_set_valve_maximum_aperture_tc_message.fieldnames
- self._instance_field = MAVLink_set_valve_maximum_aperture_tc_message.instance_field
- self._instance_offset = MAVLink_set_valve_maximum_aperture_tc_message.instance_offset
- self.servo_id = servo_id
- self.maximum_aperture = maximum_aperture
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 22, struct.pack('<fB', self.maximum_aperture, self.servo_id), force_mavlink1=force_mavlink1)
-
-class MAVLink_conrig_state_tc_message(MAVLink_message):
- '''
- Send the state of the conrig buttons
- '''
- id = MAVLINK_MSG_ID_CONRIG_STATE_TC
- name = 'CONRIG_STATE_TC'
- fieldnames = ['ignition_btn', 'filling_valve_btn', 'venting_valve_btn', 'release_pressure_btn', 'quick_connector_btn', 'start_tars_btn', 'arm_switch']
- ordered_fieldnames = ['ignition_btn', 'filling_valve_btn', 'venting_valve_btn', 'release_pressure_btn', 'quick_connector_btn', 'start_tars_btn', 'arm_switch']
- fieldtypes = ['uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {}
- format = '<BBBBBBB'
- native_format = bytearray('<BBBBBBB', 'ascii')
- orders = [0, 1, 2, 3, 4, 5, 6]
- lengths = [1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0]
- crc_extra = 65
- unpacker = struct.Struct('<BBBBBBB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, ignition_btn, filling_valve_btn, venting_valve_btn, release_pressure_btn, quick_connector_btn, start_tars_btn, arm_switch):
- MAVLink_message.__init__(self, MAVLink_conrig_state_tc_message.id, MAVLink_conrig_state_tc_message.name)
- self._fieldnames = MAVLink_conrig_state_tc_message.fieldnames
- self._instance_field = MAVLink_conrig_state_tc_message.instance_field
- self._instance_offset = MAVLink_conrig_state_tc_message.instance_offset
- self.ignition_btn = ignition_btn
- self.filling_valve_btn = filling_valve_btn
- self.venting_valve_btn = venting_valve_btn
- self.release_pressure_btn = release_pressure_btn
- self.quick_connector_btn = quick_connector_btn
- self.start_tars_btn = start_tars_btn
- self.arm_switch = arm_switch
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 65, struct.pack('<BBBBBBB', self.ignition_btn, self.filling_valve_btn, self.venting_valve_btn, self.release_pressure_btn, self.quick_connector_btn, self.start_tars_btn, self.arm_switch), force_mavlink1=force_mavlink1)
-
-class MAVLink_set_ignition_time_tc_message(MAVLink_message):
- '''
- Sets the time in ms that the igniter stays on before the
- oxidant valve is opened
- '''
- id = MAVLINK_MSG_ID_SET_IGNITION_TIME_TC
- name = 'SET_IGNITION_TIME_TC'
- fieldnames = ['timing']
- ordered_fieldnames = ['timing']
- fieldtypes = ['uint32_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timing": "ms"}
- format = '<I'
- native_format = bytearray('<I', 'ascii')
- orders = [0]
- lengths = [1]
- array_lengths = [0]
- crc_extra = 79
- unpacker = struct.Struct('<I')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timing):
- MAVLink_message.__init__(self, MAVLink_set_ignition_time_tc_message.id, MAVLink_set_ignition_time_tc_message.name)
- self._fieldnames = MAVLink_set_ignition_time_tc_message.fieldnames
- self._instance_field = MAVLink_set_ignition_time_tc_message.instance_field
- self._instance_offset = MAVLink_set_ignition_time_tc_message.instance_offset
- self.timing = timing
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 79, struct.pack('<I', self.timing), force_mavlink1=force_mavlink1)
-
-class MAVLink_set_stepper_angle_tc_message(MAVLink_message):
- '''
- Move the stepper of a certain angle
- '''
- id = MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC
- name = 'SET_STEPPER_ANGLE_TC'
- fieldnames = ['stepper_id', 'angle']
- ordered_fieldnames = ['angle', 'stepper_id']
- fieldtypes = ['uint8_t', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {}
- format = '<fB'
- native_format = bytearray('<fB', 'ascii')
- orders = [1, 0]
- lengths = [1, 1]
- array_lengths = [0, 0]
- crc_extra = 180
- unpacker = struct.Struct('<fB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, stepper_id, angle):
- MAVLink_message.__init__(self, MAVLink_set_stepper_angle_tc_message.id, MAVLink_set_stepper_angle_tc_message.name)
- self._fieldnames = MAVLink_set_stepper_angle_tc_message.fieldnames
- self._instance_field = MAVLink_set_stepper_angle_tc_message.instance_field
- self._instance_offset = MAVLink_set_stepper_angle_tc_message.instance_offset
- self.stepper_id = stepper_id
- self.angle = angle
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 180, struct.pack('<fB', self.angle, self.stepper_id), force_mavlink1=force_mavlink1)
-
-class MAVLink_set_stepper_steps_tc_message(MAVLink_message):
- '''
- Move the stepper of a certain amount of steps
- '''
- id = MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC
- name = 'SET_STEPPER_STEPS_TC'
- fieldnames = ['stepper_id', 'steps']
- ordered_fieldnames = ['steps', 'stepper_id']
- fieldtypes = ['uint8_t', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {}
- format = '<fB'
- native_format = bytearray('<fB', 'ascii')
- orders = [1, 0]
- lengths = [1, 1]
- array_lengths = [0, 0]
- crc_extra = 246
- unpacker = struct.Struct('<fB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, stepper_id, steps):
- MAVLink_message.__init__(self, MAVLink_set_stepper_steps_tc_message.id, MAVLink_set_stepper_steps_tc_message.name)
- self._fieldnames = MAVLink_set_stepper_steps_tc_message.fieldnames
- self._instance_field = MAVLink_set_stepper_steps_tc_message.instance_field
- self._instance_offset = MAVLink_set_stepper_steps_tc_message.instance_offset
- self.stepper_id = stepper_id
- self.steps = steps
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 246, struct.pack('<fB', self.steps, self.stepper_id), force_mavlink1=force_mavlink1)
-
-class MAVLink_ack_tm_message(MAVLink_message):
- '''
- TM containing an ACK message to notify that the message has
- been received
- '''
- id = MAVLINK_MSG_ID_ACK_TM
- name = 'ACK_TM'
- fieldnames = ['recv_msgid', 'seq_ack']
- ordered_fieldnames = ['recv_msgid', 'seq_ack']
- fieldtypes = ['uint8_t', 'uint8_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {}
- format = '<BB'
- native_format = bytearray('<BB', 'ascii')
- orders = [0, 1]
- lengths = [1, 1]
- array_lengths = [0, 0]
- crc_extra = 50
- unpacker = struct.Struct('<BB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, recv_msgid, seq_ack):
- MAVLink_message.__init__(self, MAVLink_ack_tm_message.id, MAVLink_ack_tm_message.name)
- self._fieldnames = MAVLink_ack_tm_message.fieldnames
- self._instance_field = MAVLink_ack_tm_message.instance_field
- self._instance_offset = MAVLink_ack_tm_message.instance_offset
- self.recv_msgid = recv_msgid
- self.seq_ack = seq_ack
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 50, struct.pack('<BB', self.recv_msgid, self.seq_ack), force_mavlink1=force_mavlink1)
-
-class MAVLink_nack_tm_message(MAVLink_message):
- '''
- TM containing a NACK message to notify that the received
- message was invalid
- '''
- id = MAVLINK_MSG_ID_NACK_TM
- name = 'NACK_TM'
- fieldnames = ['recv_msgid', 'seq_ack']
- ordered_fieldnames = ['recv_msgid', 'seq_ack']
- fieldtypes = ['uint8_t', 'uint8_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {}
- format = '<BB'
- native_format = bytearray('<BB', 'ascii')
- orders = [0, 1]
- lengths = [1, 1]
- array_lengths = [0, 0]
- crc_extra = 146
- unpacker = struct.Struct('<BB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, recv_msgid, seq_ack):
- MAVLink_message.__init__(self, MAVLink_nack_tm_message.id, MAVLink_nack_tm_message.name)
- self._fieldnames = MAVLink_nack_tm_message.fieldnames
- self._instance_field = MAVLink_nack_tm_message.instance_field
- self._instance_offset = MAVLink_nack_tm_message.instance_offset
- self.recv_msgid = recv_msgid
- self.seq_ack = seq_ack
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 146, struct.pack('<BB', self.recv_msgid, self.seq_ack), force_mavlink1=force_mavlink1)
-
-class MAVLink_gps_tm_message(MAVLink_message):
- '''
-
- '''
- id = MAVLINK_MSG_ID_GPS_TM
- name = 'GPS_TM'
- fieldnames = ['timestamp', 'sensor_name', 'fix', 'latitude', 'longitude', 'height', 'vel_north', 'vel_east', 'vel_down', 'speed', 'track', 'n_satellites']
- ordered_fieldnames = ['timestamp', 'latitude', 'longitude', 'height', 'vel_north', 'vel_east', 'vel_down', 'speed', 'track', 'sensor_name', 'fix', 'n_satellites']
- fieldtypes = ['uint64_t', 'char', 'uint8_t', 'double', 'double', 'double', 'float', 'float', 'float', 'float', 'float', 'uint8_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us", "latitude": "deg", "longitude": "deg", "height": "m", "vel_north": "m/s", "vel_east": "m/s", "vel_down": "m/s", "speed": "m/s", "track": "deg"}
- format = '<Qdddfffff20sBB'
- native_format = bytearray('<QdddfffffcBB', 'ascii')
- orders = [0, 9, 10, 1, 2, 3, 4, 5, 6, 7, 8, 11]
- lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 20, 0, 0]
- crc_extra = 57
- unpacker = struct.Struct('<Qdddfffff20sBB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, sensor_name, fix, latitude, longitude, height, vel_north, vel_east, vel_down, speed, track, n_satellites):
- MAVLink_message.__init__(self, MAVLink_gps_tm_message.id, MAVLink_gps_tm_message.name)
- self._fieldnames = MAVLink_gps_tm_message.fieldnames
- self._instance_field = MAVLink_gps_tm_message.instance_field
- self._instance_offset = MAVLink_gps_tm_message.instance_offset
- self.timestamp = timestamp
- self.sensor_name = sensor_name
- self.fix = fix
- self.latitude = latitude
- self.longitude = longitude
- self.height = height
- self.vel_north = vel_north
- self.vel_east = vel_east
- self.vel_down = vel_down
- self.speed = speed
- self.track = track
- self.n_satellites = n_satellites
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 57, struct.pack('<Qdddfffff20sBB', self.timestamp, self.latitude, self.longitude, self.height, self.vel_north, self.vel_east, self.vel_down, self.speed, self.track, self.sensor_name, self.fix, self.n_satellites), force_mavlink1=force_mavlink1)
-
-class MAVLink_imu_tm_message(MAVLink_message):
- '''
-
- '''
- id = MAVLINK_MSG_ID_IMU_TM
- name = 'IMU_TM'
- fieldnames = ['timestamp', 'sensor_name', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z']
- ordered_fieldnames = ['timestamp', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'sensor_name']
- fieldtypes = ['uint64_t', 'char', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us", "acc_x": "m/s2", "acc_y": "m/s2", "acc_z": "m/s2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT"}
- format = '<Qfffffffff20s'
- native_format = bytearray('<Qfffffffffc', 'ascii')
- orders = [0, 10, 1, 2, 3, 4, 5, 6, 7, 8, 9]
- lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 20]
- crc_extra = 72
- unpacker = struct.Struct('<Qfffffffff20s')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, sensor_name, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z):
- MAVLink_message.__init__(self, MAVLink_imu_tm_message.id, MAVLink_imu_tm_message.name)
- self._fieldnames = MAVLink_imu_tm_message.fieldnames
- self._instance_field = MAVLink_imu_tm_message.instance_field
- self._instance_offset = MAVLink_imu_tm_message.instance_offset
- self.timestamp = timestamp
- self.sensor_name = sensor_name
- self.acc_x = acc_x
- self.acc_y = acc_y
- self.acc_z = acc_z
- self.gyro_x = gyro_x
- self.gyro_y = gyro_y
- self.gyro_z = gyro_z
- self.mag_x = mag_x
- self.mag_y = mag_y
- self.mag_z = mag_z
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 72, struct.pack('<Qfffffffff20s', self.timestamp, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.sensor_name), force_mavlink1=force_mavlink1)
-
-class MAVLink_pressure_tm_message(MAVLink_message):
- '''
-
- '''
- id = MAVLINK_MSG_ID_PRESSURE_TM
- name = 'PRESSURE_TM'
- fieldnames = ['timestamp', 'sensor_name', 'pressure']
- ordered_fieldnames = ['timestamp', 'pressure', 'sensor_name']
- fieldtypes = ['uint64_t', 'char', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us", "pressure": "Pa"}
- format = '<Qf20s'
- native_format = bytearray('<Qfc', 'ascii')
- orders = [0, 2, 1]
- lengths = [1, 1, 1]
- array_lengths = [0, 0, 20]
- crc_extra = 87
- unpacker = struct.Struct('<Qf20s')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, sensor_name, pressure):
- MAVLink_message.__init__(self, MAVLink_pressure_tm_message.id, MAVLink_pressure_tm_message.name)
- self._fieldnames = MAVLink_pressure_tm_message.fieldnames
- self._instance_field = MAVLink_pressure_tm_message.instance_field
- self._instance_offset = MAVLink_pressure_tm_message.instance_offset
- self.timestamp = timestamp
- self.sensor_name = sensor_name
- self.pressure = pressure
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 87, struct.pack('<Qf20s', self.timestamp, self.pressure, self.sensor_name), force_mavlink1=force_mavlink1)
-
-class MAVLink_adc_tm_message(MAVLink_message):
- '''
-
- '''
- id = MAVLINK_MSG_ID_ADC_TM
- name = 'ADC_TM'
- fieldnames = ['timestamp', 'sensor_name', 'channel_0', 'channel_1', 'channel_2', 'channel_3', 'channel_4', 'channel_5', 'channel_6', 'channel_7']
- ordered_fieldnames = ['timestamp', 'channel_0', 'channel_1', 'channel_2', 'channel_3', 'channel_4', 'channel_5', 'channel_6', 'channel_7', 'sensor_name']
- fieldtypes = ['uint64_t', 'char', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us", "channel_0": "V", "channel_1": "V", "channel_2": "V", "channel_3": "V", "channel_4": "V", "channel_5": "V", "channel_6": "V", "channel_7": "V"}
- format = '<Qffffffff20s'
- native_format = bytearray('<Qffffffffc', 'ascii')
- orders = [0, 9, 1, 2, 3, 4, 5, 6, 7, 8]
- lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 20]
- crc_extra = 229
- unpacker = struct.Struct('<Qffffffff20s')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3, channel_4, channel_5, channel_6, channel_7):
- MAVLink_message.__init__(self, MAVLink_adc_tm_message.id, MAVLink_adc_tm_message.name)
- self._fieldnames = MAVLink_adc_tm_message.fieldnames
- self._instance_field = MAVLink_adc_tm_message.instance_field
- self._instance_offset = MAVLink_adc_tm_message.instance_offset
- self.timestamp = timestamp
- self.sensor_name = sensor_name
- self.channel_0 = channel_0
- self.channel_1 = channel_1
- self.channel_2 = channel_2
- self.channel_3 = channel_3
- self.channel_4 = channel_4
- self.channel_5 = channel_5
- self.channel_6 = channel_6
- self.channel_7 = channel_7
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 229, struct.pack('<Qffffffff20s', self.timestamp, self.channel_0, self.channel_1, self.channel_2, self.channel_3, self.channel_4, self.channel_5, self.channel_6, self.channel_7, self.sensor_name), force_mavlink1=force_mavlink1)
-
-class MAVLink_voltage_tm_message(MAVLink_message):
- '''
-
- '''
- id = MAVLINK_MSG_ID_VOLTAGE_TM
- name = 'VOLTAGE_TM'
- fieldnames = ['timestamp', 'sensor_name', 'voltage']
- ordered_fieldnames = ['timestamp', 'voltage', 'sensor_name']
- fieldtypes = ['uint64_t', 'char', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us", "voltage": "V"}
- format = '<Qf20s'
- native_format = bytearray('<Qfc', 'ascii')
- orders = [0, 2, 1]
- lengths = [1, 1, 1]
- array_lengths = [0, 0, 20]
- crc_extra = 245
- unpacker = struct.Struct('<Qf20s')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, sensor_name, voltage):
- MAVLink_message.__init__(self, MAVLink_voltage_tm_message.id, MAVLink_voltage_tm_message.name)
- self._fieldnames = MAVLink_voltage_tm_message.fieldnames
- self._instance_field = MAVLink_voltage_tm_message.instance_field
- self._instance_offset = MAVLink_voltage_tm_message.instance_offset
- self.timestamp = timestamp
- self.sensor_name = sensor_name
- self.voltage = voltage
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 245, struct.pack('<Qf20s', self.timestamp, self.voltage, self.sensor_name), force_mavlink1=force_mavlink1)
-
-class MAVLink_current_tm_message(MAVLink_message):
- '''
-
- '''
- id = MAVLINK_MSG_ID_CURRENT_TM
- name = 'CURRENT_TM'
- fieldnames = ['timestamp', 'sensor_name', 'current']
- ordered_fieldnames = ['timestamp', 'current', 'sensor_name']
- fieldtypes = ['uint64_t', 'char', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us", "current": "A"}
- format = '<Qf20s'
- native_format = bytearray('<Qfc', 'ascii')
- orders = [0, 2, 1]
- lengths = [1, 1, 1]
- array_lengths = [0, 0, 20]
- crc_extra = 212
- unpacker = struct.Struct('<Qf20s')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, sensor_name, current):
- MAVLink_message.__init__(self, MAVLink_current_tm_message.id, MAVLink_current_tm_message.name)
- self._fieldnames = MAVLink_current_tm_message.fieldnames
- self._instance_field = MAVLink_current_tm_message.instance_field
- self._instance_offset = MAVLink_current_tm_message.instance_offset
- self.timestamp = timestamp
- self.sensor_name = sensor_name
- self.current = current
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 212, struct.pack('<Qf20s', self.timestamp, self.current, self.sensor_name), force_mavlink1=force_mavlink1)
-
-class MAVLink_temp_tm_message(MAVLink_message):
- '''
-
- '''
- id = MAVLINK_MSG_ID_TEMP_TM
- name = 'TEMP_TM'
- fieldnames = ['timestamp', 'sensor_name', 'temperature']
- ordered_fieldnames = ['timestamp', 'temperature', 'sensor_name']
- fieldtypes = ['uint64_t', 'char', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us", "temperature": "deg"}
- format = '<Qf20s'
- native_format = bytearray('<Qfc', 'ascii')
- orders = [0, 2, 1]
- lengths = [1, 1, 1]
- array_lengths = [0, 0, 20]
- crc_extra = 140
- unpacker = struct.Struct('<Qf20s')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, sensor_name, temperature):
- MAVLink_message.__init__(self, MAVLink_temp_tm_message.id, MAVLink_temp_tm_message.name)
- self._fieldnames = MAVLink_temp_tm_message.fieldnames
- self._instance_field = MAVLink_temp_tm_message.instance_field
- self._instance_offset = MAVLink_temp_tm_message.instance_offset
- self.timestamp = timestamp
- self.sensor_name = sensor_name
- self.temperature = temperature
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 140, struct.pack('<Qf20s', self.timestamp, self.temperature, self.sensor_name), force_mavlink1=force_mavlink1)
-
-class MAVLink_load_tm_message(MAVLink_message):
- '''
-
- '''
- id = MAVLINK_MSG_ID_LOAD_TM
- name = 'LOAD_TM'
- fieldnames = ['timestamp', 'sensor_name', 'load']
- ordered_fieldnames = ['timestamp', 'load', 'sensor_name']
- fieldtypes = ['uint64_t', 'char', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us", "load": "kg"}
- format = '<Qf20s'
- native_format = bytearray('<Qfc', 'ascii')
- orders = [0, 2, 1]
- lengths = [1, 1, 1]
- array_lengths = [0, 0, 20]
- crc_extra = 148
- unpacker = struct.Struct('<Qf20s')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, sensor_name, load):
- MAVLink_message.__init__(self, MAVLink_load_tm_message.id, MAVLink_load_tm_message.name)
- self._fieldnames = MAVLink_load_tm_message.fieldnames
- self._instance_field = MAVLink_load_tm_message.instance_field
- self._instance_offset = MAVLink_load_tm_message.instance_offset
- self.timestamp = timestamp
- self.sensor_name = sensor_name
- self.load = load
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 148, struct.pack('<Qf20s', self.timestamp, self.load, self.sensor_name), force_mavlink1=force_mavlink1)
-
-class MAVLink_attitude_tm_message(MAVLink_message):
- '''
-
- '''
- id = MAVLINK_MSG_ID_ATTITUDE_TM
- name = 'ATTITUDE_TM'
- fieldnames = ['timestamp', 'sensor_name', 'roll', 'pitch', 'yaw', 'quat_x', 'quat_y', 'quat_z', 'quat_w']
- ordered_fieldnames = ['timestamp', 'roll', 'pitch', 'yaw', 'quat_x', 'quat_y', 'quat_z', 'quat_w', 'sensor_name']
- fieldtypes = ['uint64_t', 'char', 'float', 'float', 'float', 'float', 'float', 'float', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us", "roll": "deg", "pitch": "deg", "yaw": "deg"}
- format = '<Qfffffff20s'
- native_format = bytearray('<Qfffffffc', 'ascii')
- orders = [0, 8, 1, 2, 3, 4, 5, 6, 7]
- lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 20]
- crc_extra = 6
- unpacker = struct.Struct('<Qfffffff20s')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, sensor_name, roll, pitch, yaw, quat_x, quat_y, quat_z, quat_w):
- MAVLink_message.__init__(self, MAVLink_attitude_tm_message.id, MAVLink_attitude_tm_message.name)
- self._fieldnames = MAVLink_attitude_tm_message.fieldnames
- self._instance_field = MAVLink_attitude_tm_message.instance_field
- self._instance_offset = MAVLink_attitude_tm_message.instance_offset
- self.timestamp = timestamp
- self.sensor_name = sensor_name
- self.roll = roll
- self.pitch = pitch
- self.yaw = yaw
- self.quat_x = quat_x
- self.quat_y = quat_y
- self.quat_z = quat_z
- self.quat_w = quat_w
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 6, struct.pack('<Qfffffff20s', self.timestamp, self.roll, self.pitch, self.yaw, self.quat_x, self.quat_y, self.quat_z, self.quat_w, self.sensor_name), force_mavlink1=force_mavlink1)
-
-class MAVLink_sensor_state_tm_message(MAVLink_message):
- '''
-
- '''
- id = MAVLINK_MSG_ID_SENSOR_STATE_TM
- name = 'SENSOR_STATE_TM'
- fieldnames = ['sensor_name', 'state']
- ordered_fieldnames = ['sensor_name', 'state']
- fieldtypes = ['char', 'uint8_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {}
- format = '<20sB'
- native_format = bytearray('<cB', 'ascii')
- orders = [0, 1]
- lengths = [1, 1]
- array_lengths = [20, 0]
- crc_extra = 155
- unpacker = struct.Struct('<20sB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, sensor_name, state):
- MAVLink_message.__init__(self, MAVLink_sensor_state_tm_message.id, MAVLink_sensor_state_tm_message.name)
- self._fieldnames = MAVLink_sensor_state_tm_message.fieldnames
- self._instance_field = MAVLink_sensor_state_tm_message.instance_field
- self._instance_offset = MAVLink_sensor_state_tm_message.instance_offset
- self.sensor_name = sensor_name
- self.state = state
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 155, struct.pack('<20sB', self.sensor_name, self.state), force_mavlink1=force_mavlink1)
-
-class MAVLink_servo_tm_message(MAVLink_message):
- '''
-
- '''
- id = MAVLINK_MSG_ID_SERVO_TM
- name = 'SERVO_TM'
- fieldnames = ['servo_id', 'servo_position']
- ordered_fieldnames = ['servo_position', 'servo_id']
- fieldtypes = ['uint8_t', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {}
- format = '<fB'
- native_format = bytearray('<fB', 'ascii')
- orders = [1, 0]
- lengths = [1, 1]
- array_lengths = [0, 0]
- crc_extra = 87
- unpacker = struct.Struct('<fB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, servo_id, servo_position):
- MAVLink_message.__init__(self, MAVLink_servo_tm_message.id, MAVLink_servo_tm_message.name)
- self._fieldnames = MAVLink_servo_tm_message.fieldnames
- self._instance_field = MAVLink_servo_tm_message.instance_field
- self._instance_offset = MAVLink_servo_tm_message.instance_offset
- self.servo_id = servo_id
- self.servo_position = servo_position
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 87, struct.pack('<fB', self.servo_position, self.servo_id), force_mavlink1=force_mavlink1)
-
-class MAVLink_pin_tm_message(MAVLink_message):
- '''
-
- '''
- id = MAVLINK_MSG_ID_PIN_TM
- name = 'PIN_TM'
- fieldnames = ['timestamp', 'pin_id', 'last_change_timestamp', 'changes_counter', 'current_state']
- ordered_fieldnames = ['timestamp', 'last_change_timestamp', 'pin_id', 'changes_counter', 'current_state']
- fieldtypes = ['uint64_t', 'uint8_t', 'uint64_t', 'uint8_t', 'uint8_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us"}
- format = '<QQBBB'
- native_format = bytearray('<QQBBB', 'ascii')
- orders = [0, 2, 1, 3, 4]
- lengths = [1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0]
- crc_extra = 255
- unpacker = struct.Struct('<QQBBB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, pin_id, last_change_timestamp, changes_counter, current_state):
- MAVLink_message.__init__(self, MAVLink_pin_tm_message.id, MAVLink_pin_tm_message.name)
- self._fieldnames = MAVLink_pin_tm_message.fieldnames
- self._instance_field = MAVLink_pin_tm_message.instance_field
- self._instance_offset = MAVLink_pin_tm_message.instance_offset
- self.timestamp = timestamp
- self.pin_id = pin_id
- self.last_change_timestamp = last_change_timestamp
- self.changes_counter = changes_counter
- self.current_state = current_state
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 255, struct.pack('<QQBBB', self.timestamp, self.last_change_timestamp, self.pin_id, self.changes_counter, self.current_state), force_mavlink1=force_mavlink1)
-
-class MAVLink_receiver_tm_message(MAVLink_message):
- '''
-
- '''
- id = MAVLINK_MSG_ID_RECEIVER_TM
- name = 'RECEIVER_TM'
- fieldnames = ['timestamp', 'main_radio_present', 'main_packet_tx_error_count', 'main_tx_bitrate', 'main_packet_rx_success_count', 'main_packet_rx_drop_count', 'main_rx_bitrate', 'main_rx_rssi', 'main_rx_fei', 'payload_radio_present', 'payload_packet_tx_error_count', 'payload_tx_bitrate', 'payload_packet_rx_success_count', 'payload_packet_rx_drop_count', 'payload_rx_bitrate', 'payload_rx_rssi', 'payload_rx_fei', 'ethernet_present', 'ethernet_status', 'battery_voltage']
- ordered_fieldnames = ['timestamp', 'main_rx_rssi', 'main_rx_fei', 'payload_rx_rssi', 'payload_rx_fei', 'battery_voltage', 'main_packet_tx_error_count', 'main_tx_bitrate', 'main_packet_rx_success_count', 'main_packet_rx_drop_count', 'main_rx_bitrate', 'payload_packet_tx_error_count', 'payload_tx_bitrate', 'payload_packet_rx_success_count', 'payload_packet_rx_drop_count', 'payload_rx_bitrate', 'main_radio_present', 'payload_radio_present', 'ethernet_present', 'ethernet_status']
- fieldtypes = ['uint64_t', 'uint8_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'float', 'float', 'uint8_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'float', 'float', 'uint8_t', 'uint8_t', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us", "main_tx_bitrate": "b/s", "main_rx_bitrate": "b/s", "main_rx_rssi": "dBm", "main_rx_fei": "Hz", "payload_tx_bitrate": "b/s", "payload_rx_bitrate": "b/s", "payload_rx_rssi": "dBm", "payload_rx_fei": "Hz", "battery_voltage": "V"}
- format = '<QfffffHHHHHHHHHHBBBB'
- native_format = bytearray('<QfffffHHHHHHHHHHBBBB', 'ascii')
- orders = [0, 16, 6, 7, 8, 9, 10, 1, 2, 17, 11, 12, 13, 14, 15, 3, 4, 18, 19, 5]
- lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
- crc_extra = 117
- unpacker = struct.Struct('<QfffffHHHHHHHHHHBBBB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei, ethernet_present, ethernet_status, battery_voltage):
- MAVLink_message.__init__(self, MAVLink_receiver_tm_message.id, MAVLink_receiver_tm_message.name)
- self._fieldnames = MAVLink_receiver_tm_message.fieldnames
- self._instance_field = MAVLink_receiver_tm_message.instance_field
- self._instance_offset = MAVLink_receiver_tm_message.instance_offset
- self.timestamp = timestamp
- self.main_radio_present = main_radio_present
- self.main_packet_tx_error_count = main_packet_tx_error_count
- self.main_tx_bitrate = main_tx_bitrate
- self.main_packet_rx_success_count = main_packet_rx_success_count
- self.main_packet_rx_drop_count = main_packet_rx_drop_count
- self.main_rx_bitrate = main_rx_bitrate
- self.main_rx_rssi = main_rx_rssi
- self.main_rx_fei = main_rx_fei
- self.payload_radio_present = payload_radio_present
- self.payload_packet_tx_error_count = payload_packet_tx_error_count
- self.payload_tx_bitrate = payload_tx_bitrate
- self.payload_packet_rx_success_count = payload_packet_rx_success_count
- self.payload_packet_rx_drop_count = payload_packet_rx_drop_count
- self.payload_rx_bitrate = payload_rx_bitrate
- self.payload_rx_rssi = payload_rx_rssi
- self.payload_rx_fei = payload_rx_fei
- self.ethernet_present = ethernet_present
- self.ethernet_status = ethernet_status
- self.battery_voltage = battery_voltage
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 117, struct.pack('<QfffffHHHHHHHHHHBBBB', self.timestamp, self.main_rx_rssi, self.main_rx_fei, self.payload_rx_rssi, self.payload_rx_fei, self.battery_voltage, self.main_packet_tx_error_count, self.main_tx_bitrate, self.main_packet_rx_success_count, self.main_packet_rx_drop_count, self.main_rx_bitrate, self.payload_packet_tx_error_count, self.payload_tx_bitrate, self.payload_packet_rx_success_count, self.payload_packet_rx_drop_count, self.payload_rx_bitrate, self.main_radio_present, self.payload_radio_present, self.ethernet_present, self.ethernet_status), force_mavlink1=force_mavlink1)
-
-class MAVLink_arp_tm_message(MAVLink_message):
- '''
-
- '''
- id = MAVLINK_MSG_ID_ARP_TM
- name = 'ARP_TM'
- fieldnames = ['timestamp', 'yaw', 'pitch', 'roll', 'target_yaw', 'target_pitch', 'stepperX_pos', 'stepperX_delta', 'stepperX_speed', 'stepperY_pos', 'stepperY_delta', 'stepperY_speed', 'gps_latitude', 'gps_longitude', 'gps_height', 'gps_fix', 'main_radio_present', 'main_packet_tx_error_count', 'main_tx_bitrate', 'main_packet_rx_success_count', 'main_packet_rx_drop_count', 'main_rx_bitrate', 'main_rx_rssi', 'ethernet_present', 'ethernet_status', 'battery_voltage']
- ordered_fieldnames = ['timestamp', 'yaw', 'pitch', 'roll', 'target_yaw', 'target_pitch', 'stepperX_pos', 'stepperX_delta', 'stepperX_speed', 'stepperY_pos', 'stepperY_delta', 'stepperY_speed', 'gps_latitude', 'gps_longitude', 'gps_height', 'main_rx_rssi', 'battery_voltage', 'main_packet_tx_error_count', 'main_tx_bitrate', 'main_packet_rx_success_count', 'main_packet_rx_drop_count', 'main_rx_bitrate', 'gps_fix', 'main_radio_present', 'ethernet_present', 'ethernet_status']
- fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint16_t', 'float', 'uint8_t', 'uint8_t', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us", "yaw": "deg", "pitch": "deg", "roll": "deg", "target_yaw": "deg", "target_pitch": "deg", "stepperX_pos": "deg", "stepperX_delta": "deg", "stepperX_speed": "rps", "stepperY_pos": "deg", "stepperY_delta": "deg", "stepperY_speed": "rps", "gps_latitude": "deg", "gps_longitude": "deg", "gps_height": "m", "main_tx_bitrate": "b/s", "main_rx_bitrate": "b/s", "main_rx_rssi": "dBm", "battery_voltage": "V"}
- format = '<QffffffffffffffffHHHHHBBBB'
- native_format = bytearray('<QffffffffffffffffHHHHHBBBB', 'ascii')
- orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 22, 23, 17, 18, 19, 20, 21, 15, 24, 25, 16]
- lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
- crc_extra = 2
- unpacker = struct.Struct('<QffffffffffffffffHHHHHBBBB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, ethernet_present, ethernet_status, battery_voltage):
- MAVLink_message.__init__(self, MAVLink_arp_tm_message.id, MAVLink_arp_tm_message.name)
- self._fieldnames = MAVLink_arp_tm_message.fieldnames
- self._instance_field = MAVLink_arp_tm_message.instance_field
- self._instance_offset = MAVLink_arp_tm_message.instance_offset
- self.timestamp = timestamp
- self.yaw = yaw
- self.pitch = pitch
- self.roll = roll
- self.target_yaw = target_yaw
- self.target_pitch = target_pitch
- self.stepperX_pos = stepperX_pos
- self.stepperX_delta = stepperX_delta
- self.stepperX_speed = stepperX_speed
- self.stepperY_pos = stepperY_pos
- self.stepperY_delta = stepperY_delta
- self.stepperY_speed = stepperY_speed
- self.gps_latitude = gps_latitude
- self.gps_longitude = gps_longitude
- self.gps_height = gps_height
- self.gps_fix = gps_fix
- self.main_radio_present = main_radio_present
- self.main_packet_tx_error_count = main_packet_tx_error_count
- self.main_tx_bitrate = main_tx_bitrate
- self.main_packet_rx_success_count = main_packet_rx_success_count
- self.main_packet_rx_drop_count = main_packet_rx_drop_count
- self.main_rx_bitrate = main_rx_bitrate
- self.main_rx_rssi = main_rx_rssi
- self.ethernet_present = ethernet_present
- self.ethernet_status = ethernet_status
- self.battery_voltage = battery_voltage
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 2, struct.pack('<QffffffffffffffffHHHHHBBBB', self.timestamp, self.yaw, self.pitch, self.roll, self.target_yaw, self.target_pitch, self.stepperX_pos, self.stepperX_delta, self.stepperX_speed, self.stepperY_pos, self.stepperY_delta, self.stepperY_speed, self.gps_latitude, self.gps_longitude, self.gps_height, self.main_rx_rssi, self.battery_voltage, self.main_packet_tx_error_count, self.main_tx_bitrate, self.main_packet_rx_success_count, self.main_packet_rx_drop_count, self.main_rx_bitrate, self.gps_fix, self.main_radio_present, self.ethernet_present, self.ethernet_status), force_mavlink1=force_mavlink1)
-
-class MAVLink_set_antenna_coordinates_arp_tc_message(MAVLink_message):
- '''
- Sets current antennas coordinates
- '''
- id = MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC
- name = 'SET_ANTENNA_COORDINATES_ARP_TC'
- fieldnames = ['latitude', 'longitude']
- ordered_fieldnames = ['latitude', 'longitude']
- fieldtypes = ['float', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"latitude": "deg", "longitude": "deg"}
- format = '<ff'
- native_format = bytearray('<ff', 'ascii')
- orders = [0, 1]
- lengths = [1, 1]
- array_lengths = [0, 0]
- crc_extra = 202
- unpacker = struct.Struct('<ff')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, latitude, longitude):
- MAVLink_message.__init__(self, MAVLink_set_antenna_coordinates_arp_tc_message.id, MAVLink_set_antenna_coordinates_arp_tc_message.name)
- self._fieldnames = MAVLink_set_antenna_coordinates_arp_tc_message.fieldnames
- self._instance_field = MAVLink_set_antenna_coordinates_arp_tc_message.instance_field
- self._instance_offset = MAVLink_set_antenna_coordinates_arp_tc_message.instance_offset
- self.latitude = latitude
- self.longitude = longitude
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 202, struct.pack('<ff', self.latitude, self.longitude), force_mavlink1=force_mavlink1)
-
-class MAVLink_set_rocket_coordinates_arp_tc_message(MAVLink_message):
- '''
- Sets current rocket coordinates
- '''
- id = MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC
- name = 'SET_ROCKET_COORDINATES_ARP_TC'
- fieldnames = ['latitude', 'longitude']
- ordered_fieldnames = ['latitude', 'longitude']
- fieldtypes = ['float', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"latitude": "deg", "longitude": "deg"}
- format = '<ff'
- native_format = bytearray('<ff', 'ascii')
- orders = [0, 1]
- lengths = [1, 1]
- array_lengths = [0, 0]
- crc_extra = 164
- unpacker = struct.Struct('<ff')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, latitude, longitude):
- MAVLink_message.__init__(self, MAVLink_set_rocket_coordinates_arp_tc_message.id, MAVLink_set_rocket_coordinates_arp_tc_message.name)
- self._fieldnames = MAVLink_set_rocket_coordinates_arp_tc_message.fieldnames
- self._instance_field = MAVLink_set_rocket_coordinates_arp_tc_message.instance_field
- self._instance_offset = MAVLink_set_rocket_coordinates_arp_tc_message.instance_offset
- self.latitude = latitude
- self.longitude = longitude
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 164, struct.pack('<ff', self.latitude, self.longitude), force_mavlink1=force_mavlink1)
-
-class MAVLink_sys_tm_message(MAVLink_message):
- '''
- System status telemetry
- '''
- id = MAVLINK_MSG_ID_SYS_TM
- name = 'SYS_TM'
- fieldnames = ['timestamp', 'logger', 'event_broker', 'radio', 'pin_observer', 'sensors', 'board_scheduler']
- ordered_fieldnames = ['timestamp', 'logger', 'event_broker', 'radio', 'pin_observer', 'sensors', 'board_scheduler']
- fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us"}
- format = '<QBBBBBB'
- native_format = bytearray('<QBBBBBB', 'ascii')
- orders = [0, 1, 2, 3, 4, 5, 6]
- lengths = [1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0]
- crc_extra = 183
- unpacker = struct.Struct('<QBBBBBB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, logger, event_broker, radio, pin_observer, sensors, board_scheduler):
- MAVLink_message.__init__(self, MAVLink_sys_tm_message.id, MAVLink_sys_tm_message.name)
- self._fieldnames = MAVLink_sys_tm_message.fieldnames
- self._instance_field = MAVLink_sys_tm_message.instance_field
- self._instance_offset = MAVLink_sys_tm_message.instance_offset
- self.timestamp = timestamp
- self.logger = logger
- self.event_broker = event_broker
- self.radio = radio
- self.pin_observer = pin_observer
- self.sensors = sensors
- self.board_scheduler = board_scheduler
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 183, struct.pack('<QBBBBBB', self.timestamp, self.logger, self.event_broker, self.radio, self.pin_observer, self.sensors, self.board_scheduler), force_mavlink1=force_mavlink1)
-
-class MAVLink_fsm_tm_message(MAVLink_message):
- '''
- Flight State Machine status telemetry
- '''
- id = MAVLINK_MSG_ID_FSM_TM
- name = 'FSM_TM'
- fieldnames = ['timestamp', 'ada_state', 'abk_state', 'dpl_state', 'fmm_state', 'nas_state', 'wes_state']
- ordered_fieldnames = ['timestamp', 'ada_state', 'abk_state', 'dpl_state', 'fmm_state', 'nas_state', 'wes_state']
- fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us"}
- format = '<QBBBBBB'
- native_format = bytearray('<QBBBBBB', 'ascii')
- orders = [0, 1, 2, 3, 4, 5, 6]
- lengths = [1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0]
- crc_extra = 242
- unpacker = struct.Struct('<QBBBBBB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, ada_state, abk_state, dpl_state, fmm_state, nas_state, wes_state):
- MAVLink_message.__init__(self, MAVLink_fsm_tm_message.id, MAVLink_fsm_tm_message.name)
- self._fieldnames = MAVLink_fsm_tm_message.fieldnames
- self._instance_field = MAVLink_fsm_tm_message.instance_field
- self._instance_offset = MAVLink_fsm_tm_message.instance_offset
- self.timestamp = timestamp
- self.ada_state = ada_state
- self.abk_state = abk_state
- self.dpl_state = dpl_state
- self.fmm_state = fmm_state
- self.nas_state = nas_state
- self.wes_state = wes_state
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 242, struct.pack('<QBBBBBB', self.timestamp, self.ada_state, self.abk_state, self.dpl_state, self.fmm_state, self.nas_state, self.wes_state), force_mavlink1=force_mavlink1)
-
-class MAVLink_logger_tm_message(MAVLink_message):
- '''
- Logger status telemetry
- '''
- id = MAVLINK_MSG_ID_LOGGER_TM
- name = 'LOGGER_TM'
- fieldnames = ['timestamp', 'log_number', 'too_large_samples', 'dropped_samples', 'queued_samples', 'buffers_filled', 'buffers_written', 'writes_failed', 'last_write_error', 'average_write_time', 'max_write_time']
- ordered_fieldnames = ['timestamp', 'too_large_samples', 'dropped_samples', 'queued_samples', 'buffers_filled', 'buffers_written', 'writes_failed', 'last_write_error', 'average_write_time', 'max_write_time', 'log_number']
- fieldtypes = ['uint64_t', 'int16_t', 'int32_t', 'int32_t', 'int32_t', 'int32_t', 'int32_t', 'int32_t', 'int32_t', 'int32_t', 'int32_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us"}
- format = '<Qiiiiiiiiih'
- native_format = bytearray('<Qiiiiiiiiih', 'ascii')
- orders = [0, 10, 1, 2, 3, 4, 5, 6, 7, 8, 9]
- lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
- crc_extra = 142
- unpacker = struct.Struct('<Qiiiiiiiiih')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, log_number, too_large_samples, dropped_samples, queued_samples, buffers_filled, buffers_written, writes_failed, last_write_error, average_write_time, max_write_time):
- MAVLink_message.__init__(self, MAVLink_logger_tm_message.id, MAVLink_logger_tm_message.name)
- self._fieldnames = MAVLink_logger_tm_message.fieldnames
- self._instance_field = MAVLink_logger_tm_message.instance_field
- self._instance_offset = MAVLink_logger_tm_message.instance_offset
- self.timestamp = timestamp
- self.log_number = log_number
- self.too_large_samples = too_large_samples
- self.dropped_samples = dropped_samples
- self.queued_samples = queued_samples
- self.buffers_filled = buffers_filled
- self.buffers_written = buffers_written
- self.writes_failed = writes_failed
- self.last_write_error = last_write_error
- self.average_write_time = average_write_time
- self.max_write_time = max_write_time
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 142, struct.pack('<Qiiiiiiiiih', self.timestamp, self.too_large_samples, self.dropped_samples, self.queued_samples, self.buffers_filled, self.buffers_written, self.writes_failed, self.last_write_error, self.average_write_time, self.max_write_time, self.log_number), force_mavlink1=force_mavlink1)
-
-class MAVLink_mavlink_stats_tm_message(MAVLink_message):
- '''
- Status of the TMTCManager telemetry
- '''
- id = MAVLINK_MSG_ID_MAVLINK_STATS_TM
- name = 'MAVLINK_STATS_TM'
- fieldnames = ['timestamp', 'n_send_queue', 'max_send_queue', 'n_send_errors', 'msg_received', 'buffer_overrun', 'parse_error', 'parse_state', 'packet_idx', 'current_rx_seq', 'current_tx_seq', 'packet_rx_success_count', 'packet_rx_drop_count']
- ordered_fieldnames = ['timestamp', 'parse_state', 'n_send_queue', 'max_send_queue', 'n_send_errors', 'packet_rx_success_count', 'packet_rx_drop_count', 'msg_received', 'buffer_overrun', 'parse_error', 'packet_idx', 'current_rx_seq', 'current_tx_seq']
- fieldtypes = ['uint64_t', 'uint16_t', 'uint16_t', 'uint16_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint32_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint16_t', 'uint16_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us"}
- format = '<QIHHHHHBBBBBB'
- native_format = bytearray('<QIHHHHHBBBBBB', 'ascii')
- orders = [0, 2, 3, 4, 7, 8, 9, 1, 10, 11, 12, 5, 6]
- lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
- crc_extra = 108
- unpacker = struct.Struct('<QIHHHHHBBBBBB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, n_send_queue, max_send_queue, n_send_errors, msg_received, buffer_overrun, parse_error, parse_state, packet_idx, current_rx_seq, current_tx_seq, packet_rx_success_count, packet_rx_drop_count):
- MAVLink_message.__init__(self, MAVLink_mavlink_stats_tm_message.id, MAVLink_mavlink_stats_tm_message.name)
- self._fieldnames = MAVLink_mavlink_stats_tm_message.fieldnames
- self._instance_field = MAVLink_mavlink_stats_tm_message.instance_field
- self._instance_offset = MAVLink_mavlink_stats_tm_message.instance_offset
- self.timestamp = timestamp
- self.n_send_queue = n_send_queue
- self.max_send_queue = max_send_queue
- self.n_send_errors = n_send_errors
- self.msg_received = msg_received
- self.buffer_overrun = buffer_overrun
- self.parse_error = parse_error
- self.parse_state = parse_state
- self.packet_idx = packet_idx
- self.current_rx_seq = current_rx_seq
- self.current_tx_seq = current_tx_seq
- self.packet_rx_success_count = packet_rx_success_count
- self.packet_rx_drop_count = packet_rx_drop_count
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 108, struct.pack('<QIHHHHHBBBBBB', self.timestamp, self.parse_state, self.n_send_queue, self.max_send_queue, self.n_send_errors, self.packet_rx_success_count, self.packet_rx_drop_count, self.msg_received, self.buffer_overrun, self.parse_error, self.packet_idx, self.current_rx_seq, self.current_tx_seq), force_mavlink1=force_mavlink1)
-
-class MAVLink_task_stats_tm_message(MAVLink_message):
- '''
- Statistics of the Task Scheduler
- '''
- id = MAVLINK_MSG_ID_TASK_STATS_TM
- name = 'TASK_STATS_TM'
- fieldnames = ['timestamp', 'task_id', 'task_period', 'task_min', 'task_max', 'task_mean', 'task_stddev']
- ordered_fieldnames = ['timestamp', 'task_min', 'task_max', 'task_mean', 'task_stddev', 'task_period', 'task_id']
- fieldtypes = ['uint64_t', 'uint8_t', 'uint16_t', 'float', 'float', 'float', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us", "task_period": "ms"}
- format = '<QffffHB'
- native_format = bytearray('<QffffHB', 'ascii')
- orders = [0, 6, 5, 1, 2, 3, 4]
- lengths = [1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0]
- crc_extra = 133
- unpacker = struct.Struct('<QffffHB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, task_id, task_period, task_min, task_max, task_mean, task_stddev):
- MAVLink_message.__init__(self, MAVLink_task_stats_tm_message.id, MAVLink_task_stats_tm_message.name)
- self._fieldnames = MAVLink_task_stats_tm_message.fieldnames
- self._instance_field = MAVLink_task_stats_tm_message.instance_field
- self._instance_offset = MAVLink_task_stats_tm_message.instance_offset
- self.timestamp = timestamp
- self.task_id = task_id
- self.task_period = task_period
- self.task_min = task_min
- self.task_max = task_max
- self.task_mean = task_mean
- self.task_stddev = task_stddev
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 133, struct.pack('<QffffHB', self.timestamp, self.task_min, self.task_max, self.task_mean, self.task_stddev, self.task_period, self.task_id), force_mavlink1=force_mavlink1)
-
-class MAVLink_ada_tm_message(MAVLink_message):
- '''
- Apogee Detection Algorithm status telemetry
- '''
- id = MAVLINK_MSG_ID_ADA_TM
- name = 'ADA_TM'
- fieldnames = ['timestamp', 'state', 'kalman_x0', 'kalman_x1', 'kalman_x2', 'vertical_speed', 'msl_altitude', 'ref_pressure', 'ref_altitude', 'ref_temperature', 'msl_pressure', 'msl_temperature', 'dpl_altitude']
- ordered_fieldnames = ['timestamp', 'kalman_x0', 'kalman_x1', 'kalman_x2', 'vertical_speed', 'msl_altitude', 'ref_pressure', 'ref_altitude', 'ref_temperature', 'msl_pressure', 'msl_temperature', 'dpl_altitude', 'state']
- fieldtypes = ['uint64_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us", "vertical_speed": "m/s", "msl_altitude": "m", "ref_pressure": "Pa", "ref_altitude": "m", "ref_temperature": "degC", "msl_pressure": "Pa", "msl_temperature": "degC", "dpl_altitude": "m"}
- format = '<QfffffffffffB'
- native_format = bytearray('<QfffffffffffB', 'ascii')
- orders = [0, 12, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11]
- lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
- crc_extra = 234
- unpacker = struct.Struct('<QfffffffffffB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, state, kalman_x0, kalman_x1, kalman_x2, vertical_speed, msl_altitude, ref_pressure, ref_altitude, ref_temperature, msl_pressure, msl_temperature, dpl_altitude):
- MAVLink_message.__init__(self, MAVLink_ada_tm_message.id, MAVLink_ada_tm_message.name)
- self._fieldnames = MAVLink_ada_tm_message.fieldnames
- self._instance_field = MAVLink_ada_tm_message.instance_field
- self._instance_offset = MAVLink_ada_tm_message.instance_offset
- self.timestamp = timestamp
- self.state = state
- self.kalman_x0 = kalman_x0
- self.kalman_x1 = kalman_x1
- self.kalman_x2 = kalman_x2
- self.vertical_speed = vertical_speed
- self.msl_altitude = msl_altitude
- self.ref_pressure = ref_pressure
- self.ref_altitude = ref_altitude
- self.ref_temperature = ref_temperature
- self.msl_pressure = msl_pressure
- self.msl_temperature = msl_temperature
- self.dpl_altitude = dpl_altitude
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 234, struct.pack('<QfffffffffffB', self.timestamp, self.kalman_x0, self.kalman_x1, self.kalman_x2, self.vertical_speed, self.msl_altitude, self.ref_pressure, self.ref_altitude, self.ref_temperature, self.msl_pressure, self.msl_temperature, self.dpl_altitude, self.state), force_mavlink1=force_mavlink1)
-
-class MAVLink_nas_tm_message(MAVLink_message):
- '''
- Navigation System status telemetry
- '''
- id = MAVLINK_MSG_ID_NAS_TM
- name = 'NAS_TM'
- fieldnames = ['timestamp', 'state', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'ref_pressure', 'ref_temperature', 'ref_latitude', 'ref_longitude']
- ordered_fieldnames = ['timestamp', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'ref_pressure', 'ref_temperature', 'ref_latitude', 'ref_longitude', 'state']
- fieldtypes = ['uint64_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "nas_qx": "deg", "nas_qy": "deg", "nas_qz": "deg", "nas_qw": "deg", "ref_pressure": "Pa", "ref_temperature": "degC", "ref_latitude": "deg", "ref_longitude": "deg"}
- format = '<QfffffffffffffffffB'
- native_format = bytearray('<QfffffffffffffffffB', 'ascii')
- orders = [0, 18, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17]
- lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
- crc_extra = 66
- unpacker = struct.Struct('<QfffffffffffffffffB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, state, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, ref_pressure, ref_temperature, ref_latitude, ref_longitude):
- MAVLink_message.__init__(self, MAVLink_nas_tm_message.id, MAVLink_nas_tm_message.name)
- self._fieldnames = MAVLink_nas_tm_message.fieldnames
- self._instance_field = MAVLink_nas_tm_message.instance_field
- self._instance_offset = MAVLink_nas_tm_message.instance_offset
- self.timestamp = timestamp
- self.state = state
- self.nas_n = nas_n
- self.nas_e = nas_e
- self.nas_d = nas_d
- self.nas_vn = nas_vn
- self.nas_ve = nas_ve
- self.nas_vd = nas_vd
- self.nas_qx = nas_qx
- self.nas_qy = nas_qy
- self.nas_qz = nas_qz
- self.nas_qw = nas_qw
- self.nas_bias_x = nas_bias_x
- self.nas_bias_y = nas_bias_y
- self.nas_bias_z = nas_bias_z
- self.ref_pressure = ref_pressure
- self.ref_temperature = ref_temperature
- self.ref_latitude = ref_latitude
- self.ref_longitude = ref_longitude
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 66, struct.pack('<QfffffffffffffffffB', self.timestamp, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.ref_pressure, self.ref_temperature, self.ref_latitude, self.ref_longitude, self.state), force_mavlink1=force_mavlink1)
-
-class MAVLink_mea_tm_message(MAVLink_message):
- '''
- Mass Estimation Algorithm status telemetry
- '''
- id = MAVLINK_MSG_ID_MEA_TM
- name = 'MEA_TM'
- fieldnames = ['timestamp', 'state', 'kalman_x0', 'kalman_x1', 'kalman_x2', 'mass', 'corrected_pressure']
- ordered_fieldnames = ['timestamp', 'kalman_x0', 'kalman_x1', 'kalman_x2', 'mass', 'corrected_pressure', 'state']
- fieldtypes = ['uint64_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us", "mass": "kg", "corrected_pressure": "kg"}
- format = '<QfffffB'
- native_format = bytearray('<QfffffB', 'ascii')
- orders = [0, 6, 1, 2, 3, 4, 5]
- lengths = [1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0]
- crc_extra = 11
- unpacker = struct.Struct('<QfffffB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, state, kalman_x0, kalman_x1, kalman_x2, mass, corrected_pressure):
- MAVLink_message.__init__(self, MAVLink_mea_tm_message.id, MAVLink_mea_tm_message.name)
- self._fieldnames = MAVLink_mea_tm_message.fieldnames
- self._instance_field = MAVLink_mea_tm_message.instance_field
- self._instance_offset = MAVLink_mea_tm_message.instance_offset
- self.timestamp = timestamp
- self.state = state
- self.kalman_x0 = kalman_x0
- self.kalman_x1 = kalman_x1
- self.kalman_x2 = kalman_x2
- self.mass = mass
- self.corrected_pressure = corrected_pressure
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 11, struct.pack('<QfffffB', self.timestamp, self.kalman_x0, self.kalman_x1, self.kalman_x2, self.mass, self.corrected_pressure, self.state), force_mavlink1=force_mavlink1)
-
-class MAVLink_rocket_flight_tm_message(MAVLink_message):
- '''
- High Rate Telemetry
- '''
- id = MAVLINK_MSG_ID_ROCKET_FLIGHT_TM
- name = 'ROCKET_FLIGHT_TM'
- fieldnames = ['timestamp', 'ada_state', 'fmm_state', 'dpl_state', 'abk_state', 'nas_state', 'mea_state', 'pressure_ada', 'pressure_digi', 'pressure_static', 'pressure_dpl', 'airspeed_pitot', 'altitude_agl', 'ada_vert_speed', 'mea_mass', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_fix', 'gps_lat', 'gps_lon', 'gps_alt', 'abk_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'pin_quick_connector', 'pin_launch', 'pin_nosecone', 'pin_expulsion', 'cutter_presence', 'battery_voltage', 'cam_battery_voltage', 'current_consumption', 'temperature', 'logger_error']
- ordered_fieldnames = ['timestamp', 'pressure_ada', 'pressure_digi', 'pressure_static', 'pressure_dpl', 'airspeed_pitot', 'altitude_agl', 'ada_vert_speed', 'mea_mass', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_lat', 'gps_lon', 'gps_alt', 'abk_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'pin_quick_connector', 'battery_voltage', 'cam_battery_voltage', 'current_consumption', 'temperature', 'ada_state', 'fmm_state', 'dpl_state', 'abk_state', 'nas_state', 'mea_state', 'gps_fix', 'pin_launch', 'pin_nosecone', 'pin_expulsion', 'cutter_presence', 'logger_error']
- fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'float', 'int8_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us", "pressure_ada": "Pa", "pressure_digi": "Pa", "pressure_static": "Pa", "pressure_dpl": "Pa", "airspeed_pitot": "m/s", "altitude_agl": "m", "ada_vert_speed": "m/s", "mea_mass": "kg", "acc_x": "m/s^2", "acc_y": "m/s^2", "acc_z": "m/s^2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT", "gps_lat": "deg", "gps_lon": "deg", "gps_alt": "m", "abk_angle": "deg", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "nas_qx": "deg", "nas_qy": "deg", "nas_qz": "deg", "nas_qw": "deg", "battery_voltage": "V", "cam_battery_voltage": "V", "current_consumption": "A", "temperature": "degC"}
- format = '<QfffffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb'
- native_format = bytearray('<QfffffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb', 'ascii')
- orders = [0, 40, 41, 42, 43, 44, 45, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 46, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 47, 48, 49, 50, 36, 37, 38, 39, 51]
- lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
- crc_extra = 214
- unpacker = struct.Struct('<QfffffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_quick_connector, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, current_consumption, temperature, logger_error):
- MAVLink_message.__init__(self, MAVLink_rocket_flight_tm_message.id, MAVLink_rocket_flight_tm_message.name)
- self._fieldnames = MAVLink_rocket_flight_tm_message.fieldnames
- self._instance_field = MAVLink_rocket_flight_tm_message.instance_field
- self._instance_offset = MAVLink_rocket_flight_tm_message.instance_offset
- self.timestamp = timestamp
- self.ada_state = ada_state
- self.fmm_state = fmm_state
- self.dpl_state = dpl_state
- self.abk_state = abk_state
- self.nas_state = nas_state
- self.mea_state = mea_state
- self.pressure_ada = pressure_ada
- self.pressure_digi = pressure_digi
- self.pressure_static = pressure_static
- self.pressure_dpl = pressure_dpl
- self.airspeed_pitot = airspeed_pitot
- self.altitude_agl = altitude_agl
- self.ada_vert_speed = ada_vert_speed
- self.mea_mass = mea_mass
- self.acc_x = acc_x
- self.acc_y = acc_y
- self.acc_z = acc_z
- self.gyro_x = gyro_x
- self.gyro_y = gyro_y
- self.gyro_z = gyro_z
- self.mag_x = mag_x
- self.mag_y = mag_y
- self.mag_z = mag_z
- self.gps_fix = gps_fix
- self.gps_lat = gps_lat
- self.gps_lon = gps_lon
- self.gps_alt = gps_alt
- self.abk_angle = abk_angle
- self.nas_n = nas_n
- self.nas_e = nas_e
- self.nas_d = nas_d
- self.nas_vn = nas_vn
- self.nas_ve = nas_ve
- self.nas_vd = nas_vd
- self.nas_qx = nas_qx
- self.nas_qy = nas_qy
- self.nas_qz = nas_qz
- self.nas_qw = nas_qw
- self.nas_bias_x = nas_bias_x
- self.nas_bias_y = nas_bias_y
- self.nas_bias_z = nas_bias_z
- self.pin_quick_connector = pin_quick_connector
- self.pin_launch = pin_launch
- self.pin_nosecone = pin_nosecone
- self.pin_expulsion = pin_expulsion
- self.cutter_presence = cutter_presence
- self.battery_voltage = battery_voltage
- self.cam_battery_voltage = cam_battery_voltage
- self.current_consumption = current_consumption
- self.temperature = temperature
- self.logger_error = logger_error
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 214, struct.pack('<QfffffffffffffffffffffffffffffffffffffffBBBBBBBBBBBb', self.timestamp, self.pressure_ada, self.pressure_digi, self.pressure_static, self.pressure_dpl, self.airspeed_pitot, self.altitude_agl, self.ada_vert_speed, self.mea_mass, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.gps_lat, self.gps_lon, self.gps_alt, self.abk_angle, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.pin_quick_connector, self.battery_voltage, self.cam_battery_voltage, self.current_consumption, self.temperature, self.ada_state, self.fmm_state, self.dpl_state, self.abk_state, self.nas_state, self.mea_state, self.gps_fix, self.pin_launch, self.pin_nosecone, self.pin_expulsion, self.cutter_presence, self.logger_error), force_mavlink1=force_mavlink1)
-
-class MAVLink_payload_flight_tm_message(MAVLink_message):
- '''
- High Rate Telemetry
- '''
- id = MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM
- name = 'PAYLOAD_FLIGHT_TM'
- fieldnames = ['timestamp', 'fmm_state', 'nas_state', 'wes_state', 'pressure_digi', 'pressure_static', 'airspeed_pitot', 'altitude_agl', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_fix', 'gps_lat', 'gps_lon', 'gps_alt', 'left_servo_angle', 'right_servo_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'wes_n', 'wes_e', 'pin_nosecone', 'battery_voltage', 'cam_battery_voltage', 'current_consumption', 'cutter_presence', 'temperature', 'logger_error']
- ordered_fieldnames = ['timestamp', 'pressure_digi', 'pressure_static', 'airspeed_pitot', 'altitude_agl', 'acc_x', 'acc_y', 'acc_z', 'gyro_x', 'gyro_y', 'gyro_z', 'mag_x', 'mag_y', 'mag_z', 'gps_lat', 'gps_lon', 'gps_alt', 'left_servo_angle', 'right_servo_angle', 'nas_n', 'nas_e', 'nas_d', 'nas_vn', 'nas_ve', 'nas_vd', 'nas_qx', 'nas_qy', 'nas_qz', 'nas_qw', 'nas_bias_x', 'nas_bias_y', 'nas_bias_z', 'wes_n', 'wes_e', 'battery_voltage', 'cam_battery_voltage', 'current_consumption', 'temperature', 'fmm_state', 'nas_state', 'wes_state', 'gps_fix', 'pin_nosecone', 'cutter_presence', 'logger_error']
- fieldtypes = ['uint64_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint8_t', 'float', 'float', 'float', 'uint8_t', 'float', 'int8_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us", "pressure_digi": "Pa", "pressure_static": "Pa", "airspeed_pitot": "m/s", "altitude_agl": "m", "acc_x": "m/s^2", "acc_y": "m/s^2", "acc_z": "m/s^2", "gyro_x": "rad/s", "gyro_y": "rad/s", "gyro_z": "rad/s", "mag_x": "uT", "mag_y": "uT", "mag_z": "uT", "gps_lat": "deg", "gps_lon": "deg", "gps_alt": "m", "left_servo_angle": "deg", "right_servo_angle": "deg", "nas_n": "deg", "nas_e": "deg", "nas_d": "m", "nas_vn": "m/s", "nas_ve": "m/s", "nas_vd": "m/s", "nas_qx": "deg", "nas_qy": "deg", "nas_qz": "deg", "nas_qw": "deg", "wes_n": "m/s", "wes_e": "m/s", "battery_voltage": "V", "cam_battery_voltage": "V", "current_consumption": "A", "temperature": "degC"}
- format = '<QfffffffffffffffffffffffffffffffffffffBBBBBBb'
- native_format = bytearray('<QfffffffffffffffffffffffffffffffffffffBBBBBBb', 'ascii')
- orders = [0, 38, 39, 40, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 41, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 42, 34, 35, 36, 43, 37, 44]
- lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
- crc_extra = 84
- unpacker = struct.Struct('<QfffffffffffffffffffffffffffffffffffffBBBBBBb')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, current_consumption, cutter_presence, temperature, logger_error):
- MAVLink_message.__init__(self, MAVLink_payload_flight_tm_message.id, MAVLink_payload_flight_tm_message.name)
- self._fieldnames = MAVLink_payload_flight_tm_message.fieldnames
- self._instance_field = MAVLink_payload_flight_tm_message.instance_field
- self._instance_offset = MAVLink_payload_flight_tm_message.instance_offset
- self.timestamp = timestamp
- self.fmm_state = fmm_state
- self.nas_state = nas_state
- self.wes_state = wes_state
- self.pressure_digi = pressure_digi
- self.pressure_static = pressure_static
- self.airspeed_pitot = airspeed_pitot
- self.altitude_agl = altitude_agl
- self.acc_x = acc_x
- self.acc_y = acc_y
- self.acc_z = acc_z
- self.gyro_x = gyro_x
- self.gyro_y = gyro_y
- self.gyro_z = gyro_z
- self.mag_x = mag_x
- self.mag_y = mag_y
- self.mag_z = mag_z
- self.gps_fix = gps_fix
- self.gps_lat = gps_lat
- self.gps_lon = gps_lon
- self.gps_alt = gps_alt
- self.left_servo_angle = left_servo_angle
- self.right_servo_angle = right_servo_angle
- self.nas_n = nas_n
- self.nas_e = nas_e
- self.nas_d = nas_d
- self.nas_vn = nas_vn
- self.nas_ve = nas_ve
- self.nas_vd = nas_vd
- self.nas_qx = nas_qx
- self.nas_qy = nas_qy
- self.nas_qz = nas_qz
- self.nas_qw = nas_qw
- self.nas_bias_x = nas_bias_x
- self.nas_bias_y = nas_bias_y
- self.nas_bias_z = nas_bias_z
- self.wes_n = wes_n
- self.wes_e = wes_e
- self.pin_nosecone = pin_nosecone
- self.battery_voltage = battery_voltage
- self.cam_battery_voltage = cam_battery_voltage
- self.current_consumption = current_consumption
- self.cutter_presence = cutter_presence
- self.temperature = temperature
- self.logger_error = logger_error
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 84, struct.pack('<QfffffffffffffffffffffffffffffffffffffBBBBBBb', self.timestamp, self.pressure_digi, self.pressure_static, self.airspeed_pitot, self.altitude_agl, self.acc_x, self.acc_y, self.acc_z, self.gyro_x, self.gyro_y, self.gyro_z, self.mag_x, self.mag_y, self.mag_z, self.gps_lat, self.gps_lon, self.gps_alt, self.left_servo_angle, self.right_servo_angle, self.nas_n, self.nas_e, self.nas_d, self.nas_vn, self.nas_ve, self.nas_vd, self.nas_qx, self.nas_qy, self.nas_qz, self.nas_qw, self.nas_bias_x, self.nas_bias_y, self.nas_bias_z, self.wes_n, self.wes_e, self.battery_voltage, self.cam_battery_voltage, self.current_consumption, self.temperature, self.fmm_state, self.nas_state, self.wes_state, self.gps_fix, self.pin_nosecone, self.cutter_presence, self.logger_error), force_mavlink1=force_mavlink1)
-
-class MAVLink_rocket_stats_tm_message(MAVLink_message):
- '''
- Low Rate Telemetry
- '''
- id = MAVLINK_MSG_ID_ROCKET_STATS_TM
- name = 'ROCKET_STATS_TM'
- fieldnames = ['liftoff_ts', 'liftoff_max_acc_ts', 'liftoff_max_acc', 'dpl_ts', 'dpl_max_acc', 'max_z_speed_ts', 'max_z_speed', 'max_airspeed_pitot', 'max_speed_altitude', 'apogee_ts', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'min_pressure', 'ada_min_pressure', 'dpl_vane_max_pressure', 'cpu_load', 'free_heap']
- ordered_fieldnames = ['liftoff_ts', 'liftoff_max_acc_ts', 'dpl_ts', 'max_z_speed_ts', 'apogee_ts', 'liftoff_max_acc', 'dpl_max_acc', 'max_z_speed', 'max_airspeed_pitot', 'max_speed_altitude', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'min_pressure', 'ada_min_pressure', 'dpl_vane_max_pressure', 'cpu_load', 'free_heap']
- fieldtypes = ['uint64_t', 'uint64_t', 'float', 'uint64_t', 'float', 'uint64_t', 'float', 'float', 'float', 'uint64_t', 'float', 'float', 'float', 'float', 'float', 'float', 'float', 'uint32_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"liftoff_ts": "us", "liftoff_max_acc_ts": "us", "liftoff_max_acc": "m/s2", "dpl_ts": "us", "dpl_max_acc": "m/s2", "max_z_speed_ts": "us", "max_z_speed": "m/s", "max_airspeed_pitot": "m/s", "max_speed_altitude": "m", "apogee_ts": "us", "apogee_lat": "deg", "apogee_lon": "deg", "apogee_alt": "m", "min_pressure": "Pa", "ada_min_pressure": "Pa", "dpl_vane_max_pressure": "Pa"}
- format = '<QQQQQffffffffffffI'
- native_format = bytearray('<QQQQQffffffffffffI', 'ascii')
- orders = [0, 1, 5, 2, 6, 3, 7, 8, 9, 4, 10, 11, 12, 13, 14, 15, 16, 17]
- lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
- crc_extra = 245
- unpacker = struct.Struct('<QQQQQffffffffffffI')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, ada_min_pressure, dpl_vane_max_pressure, cpu_load, free_heap):
- MAVLink_message.__init__(self, MAVLink_rocket_stats_tm_message.id, MAVLink_rocket_stats_tm_message.name)
- self._fieldnames = MAVLink_rocket_stats_tm_message.fieldnames
- self._instance_field = MAVLink_rocket_stats_tm_message.instance_field
- self._instance_offset = MAVLink_rocket_stats_tm_message.instance_offset
- self.liftoff_ts = liftoff_ts
- self.liftoff_max_acc_ts = liftoff_max_acc_ts
- self.liftoff_max_acc = liftoff_max_acc
- self.dpl_ts = dpl_ts
- self.dpl_max_acc = dpl_max_acc
- self.max_z_speed_ts = max_z_speed_ts
- self.max_z_speed = max_z_speed
- self.max_airspeed_pitot = max_airspeed_pitot
- self.max_speed_altitude = max_speed_altitude
- self.apogee_ts = apogee_ts
- self.apogee_lat = apogee_lat
- self.apogee_lon = apogee_lon
- self.apogee_alt = apogee_alt
- self.min_pressure = min_pressure
- self.ada_min_pressure = ada_min_pressure
- self.dpl_vane_max_pressure = dpl_vane_max_pressure
- self.cpu_load = cpu_load
- self.free_heap = free_heap
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 245, struct.pack('<QQQQQffffffffffffI', self.liftoff_ts, self.liftoff_max_acc_ts, self.dpl_ts, self.max_z_speed_ts, self.apogee_ts, self.liftoff_max_acc, self.dpl_max_acc, self.max_z_speed, self.max_airspeed_pitot, self.max_speed_altitude, self.apogee_lat, self.apogee_lon, self.apogee_alt, self.min_pressure, self.ada_min_pressure, self.dpl_vane_max_pressure, self.cpu_load, self.free_heap), force_mavlink1=force_mavlink1)
-
-class MAVLink_payload_stats_tm_message(MAVLink_message):
- '''
- Low Rate Telemetry
- '''
- id = MAVLINK_MSG_ID_PAYLOAD_STATS_TM
- name = 'PAYLOAD_STATS_TM'
- fieldnames = ['liftoff_max_acc_ts', 'liftoff_max_acc', 'dpl_ts', 'dpl_max_acc', 'max_z_speed_ts', 'max_z_speed', 'max_airspeed_pitot', 'max_speed_altitude', 'apogee_ts', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'min_pressure', 'cpu_load', 'free_heap']
- ordered_fieldnames = ['liftoff_max_acc_ts', 'dpl_ts', 'max_z_speed_ts', 'apogee_ts', 'liftoff_max_acc', 'dpl_max_acc', 'max_z_speed', 'max_airspeed_pitot', 'max_speed_altitude', 'apogee_lat', 'apogee_lon', 'apogee_alt', 'min_pressure', 'cpu_load', 'free_heap']
- fieldtypes = ['uint64_t', 'float', 'uint64_t', 'float', 'uint64_t', 'float', 'float', 'float', 'uint64_t', 'float', 'float', 'float', 'float', 'float', 'uint32_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"liftoff_max_acc_ts": "us", "liftoff_max_acc": "m/s2", "dpl_ts": "us", "dpl_max_acc": "m/s2", "max_z_speed_ts": "us", "max_z_speed": "m/s", "max_airspeed_pitot": "m/s", "max_speed_altitude": "m", "apogee_ts": "us", "apogee_lat": "deg", "apogee_lon": "deg", "apogee_alt": "m", "min_pressure": "Pa"}
- format = '<QQQQffffffffffI'
- native_format = bytearray('<QQQQffffffffffI', 'ascii')
- orders = [0, 4, 1, 5, 2, 6, 7, 8, 3, 9, 10, 11, 12, 13, 14]
- lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
- crc_extra = 115
- unpacker = struct.Struct('<QQQQffffffffffI')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap):
- MAVLink_message.__init__(self, MAVLink_payload_stats_tm_message.id, MAVLink_payload_stats_tm_message.name)
- self._fieldnames = MAVLink_payload_stats_tm_message.fieldnames
- self._instance_field = MAVLink_payload_stats_tm_message.instance_field
- self._instance_offset = MAVLink_payload_stats_tm_message.instance_offset
- self.liftoff_max_acc_ts = liftoff_max_acc_ts
- self.liftoff_max_acc = liftoff_max_acc
- self.dpl_ts = dpl_ts
- self.dpl_max_acc = dpl_max_acc
- self.max_z_speed_ts = max_z_speed_ts
- self.max_z_speed = max_z_speed
- self.max_airspeed_pitot = max_airspeed_pitot
- self.max_speed_altitude = max_speed_altitude
- self.apogee_ts = apogee_ts
- self.apogee_lat = apogee_lat
- self.apogee_lon = apogee_lon
- self.apogee_alt = apogee_alt
- self.min_pressure = min_pressure
- self.cpu_load = cpu_load
- self.free_heap = free_heap
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 115, struct.pack('<QQQQffffffffffI', self.liftoff_max_acc_ts, self.dpl_ts, self.max_z_speed_ts, self.apogee_ts, self.liftoff_max_acc, self.dpl_max_acc, self.max_z_speed, self.max_airspeed_pitot, self.max_speed_altitude, self.apogee_lat, self.apogee_lon, self.apogee_alt, self.min_pressure, self.cpu_load, self.free_heap), force_mavlink1=force_mavlink1)
-
-class MAVLink_gse_tm_message(MAVLink_message):
- '''
- Ground Segment Equipment telemetry
- '''
- id = MAVLINK_MSG_ID_GSE_TM
- name = 'GSE_TM'
- fieldnames = ['timestamp', 'loadcell_rocket', 'loadcell_vessel', 'filling_pressure', 'vessel_pressure', 'arming_state', 'filling_valve_state', 'venting_valve_state', 'release_valve_state', 'main_valve_state', 'ignition_state', 'tars_state', 'battery_voltage', 'current_consumption', 'main_board_status', 'payload_board_status', 'motor_board_status']
- ordered_fieldnames = ['timestamp', 'loadcell_rocket', 'loadcell_vessel', 'filling_pressure', 'vessel_pressure', 'battery_voltage', 'current_consumption', 'arming_state', 'filling_valve_state', 'venting_valve_state', 'release_valve_state', 'main_valve_state', 'ignition_state', 'tars_state', 'main_board_status', 'payload_board_status', 'motor_board_status']
- fieldtypes = ['uint64_t', 'float', 'float', 'float', 'float', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'uint8_t', 'float', 'float', 'uint8_t', 'uint8_t', 'uint8_t']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us", "loadcell_rocket": "kg", "loadcell_vessel": "kg", "filling_pressure": "Bar", "vessel_pressure": "Bar"}
- format = '<QffffffBBBBBBBBBB'
- native_format = bytearray('<QffffffBBBBBBBBBB', 'ascii')
- orders = [0, 1, 2, 3, 4, 7, 8, 9, 10, 11, 12, 13, 5, 6, 14, 15, 16]
- lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
- crc_extra = 63
- unpacker = struct.Struct('<QffffffBBBBBBBBBB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, ignition_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status):
- MAVLink_message.__init__(self, MAVLink_gse_tm_message.id, MAVLink_gse_tm_message.name)
- self._fieldnames = MAVLink_gse_tm_message.fieldnames
- self._instance_field = MAVLink_gse_tm_message.instance_field
- self._instance_offset = MAVLink_gse_tm_message.instance_offset
- self.timestamp = timestamp
- self.loadcell_rocket = loadcell_rocket
- self.loadcell_vessel = loadcell_vessel
- self.filling_pressure = filling_pressure
- self.vessel_pressure = vessel_pressure
- self.arming_state = arming_state
- self.filling_valve_state = filling_valve_state
- self.venting_valve_state = venting_valve_state
- self.release_valve_state = release_valve_state
- self.main_valve_state = main_valve_state
- self.ignition_state = ignition_state
- self.tars_state = tars_state
- self.battery_voltage = battery_voltage
- self.current_consumption = current_consumption
- self.main_board_status = main_board_status
- self.payload_board_status = payload_board_status
- self.motor_board_status = motor_board_status
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 63, struct.pack('<QffffffBBBBBBBBBB', self.timestamp, self.loadcell_rocket, self.loadcell_vessel, self.filling_pressure, self.vessel_pressure, self.battery_voltage, self.current_consumption, self.arming_state, self.filling_valve_state, self.venting_valve_state, self.release_valve_state, self.main_valve_state, self.ignition_state, self.tars_state, self.main_board_status, self.payload_board_status, self.motor_board_status), force_mavlink1=force_mavlink1)
-
-class MAVLink_motor_tm_message(MAVLink_message):
- '''
- Motor rocket telemetry
- '''
- id = MAVLINK_MSG_ID_MOTOR_TM
- name = 'MOTOR_TM'
- fieldnames = ['timestamp', 'top_tank_pressure', 'bottom_tank_pressure', 'combustion_chamber_pressure', 'floating_level', 'tank_temperature', 'main_valve_state', 'venting_valve_state', 'battery_voltage', 'current_consumption']
- ordered_fieldnames = ['timestamp', 'top_tank_pressure', 'bottom_tank_pressure', 'combustion_chamber_pressure', 'tank_temperature', 'battery_voltage', 'current_consumption', 'floating_level', 'main_valve_state', 'venting_valve_state']
- fieldtypes = ['uint64_t', 'float', 'float', 'float', 'uint8_t', 'float', 'uint8_t', 'uint8_t', 'float', 'float']
- fielddisplays_by_name = {}
- fieldenums_by_name = {}
- fieldunits_by_name = {"timestamp": "us", "top_tank_pressure": "Bar", "bottom_tank_pressure": "Bar", "combustion_chamber_pressure": "Bar", "battery_voltage": "V", "current_consumption": "A"}
- format = '<QffffffBBB'
- native_format = bytearray('<QffffffBBB', 'ascii')
- orders = [0, 1, 2, 3, 7, 4, 8, 9, 5, 6]
- lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1]
- array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
- crc_extra = 79
- unpacker = struct.Struct('<QffffffBBB')
- instance_field = None
- instance_offset = -1
-
- def __init__(self, timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, floating_level, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, current_consumption):
- MAVLink_message.__init__(self, MAVLink_motor_tm_message.id, MAVLink_motor_tm_message.name)
- self._fieldnames = MAVLink_motor_tm_message.fieldnames
- self._instance_field = MAVLink_motor_tm_message.instance_field
- self._instance_offset = MAVLink_motor_tm_message.instance_offset
- self.timestamp = timestamp
- self.top_tank_pressure = top_tank_pressure
- self.bottom_tank_pressure = bottom_tank_pressure
- self.combustion_chamber_pressure = combustion_chamber_pressure
- self.floating_level = floating_level
- self.tank_temperature = tank_temperature
- self.main_valve_state = main_valve_state
- self.venting_valve_state = venting_valve_state
- self.battery_voltage = battery_voltage
- self.current_consumption = current_consumption
-
- def pack(self, mav, force_mavlink1=False):
- return MAVLink_message.pack(self, mav, 79, struct.pack('<QffffffBBB', self.timestamp, self.top_tank_pressure, self.bottom_tank_pressure, self.combustion_chamber_pressure, self.tank_temperature, self.battery_voltage, self.current_consumption, self.floating_level, self.main_valve_state, self.venting_valve_state), force_mavlink1=force_mavlink1)
-
-
-mavlink_map = {
- MAVLINK_MSG_ID_PING_TC : MAVLink_ping_tc_message,
- MAVLINK_MSG_ID_COMMAND_TC : MAVLink_command_tc_message,
- MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC : MAVLink_system_tm_request_tc_message,
- MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC : MAVLink_sensor_tm_request_tc_message,
- MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC : MAVLink_servo_tm_request_tc_message,
- MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC : MAVLink_set_servo_angle_tc_message,
- MAVLINK_MSG_ID_WIGGLE_SERVO_TC : MAVLink_wiggle_servo_tc_message,
- MAVLINK_MSG_ID_RESET_SERVO_TC : MAVLink_reset_servo_tc_message,
- MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC : MAVLink_set_reference_altitude_tc_message,
- MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC : MAVLink_set_reference_temperature_tc_message,
- MAVLINK_MSG_ID_SET_ORIENTATION_TC : MAVLink_set_orientation_tc_message,
- MAVLINK_MSG_ID_SET_COORDINATES_TC : MAVLink_set_coordinates_tc_message,
- MAVLINK_MSG_ID_RAW_EVENT_TC : MAVLink_raw_event_tc_message,
- MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC : MAVLink_set_deployment_altitude_tc_message,
- MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC : MAVLink_set_target_coordinates_tc_message,
- MAVLINK_MSG_ID_SET_ALGORITHM_TC : MAVLink_set_algorithm_tc_message,
- MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC : MAVLink_set_atomic_valve_timing_tc_message,
- MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC : MAVLink_set_valve_maximum_aperture_tc_message,
- MAVLINK_MSG_ID_CONRIG_STATE_TC : MAVLink_conrig_state_tc_message,
- MAVLINK_MSG_ID_SET_IGNITION_TIME_TC : MAVLink_set_ignition_time_tc_message,
- MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC : MAVLink_set_stepper_angle_tc_message,
- MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC : MAVLink_set_stepper_steps_tc_message,
- MAVLINK_MSG_ID_ACK_TM : MAVLink_ack_tm_message,
- MAVLINK_MSG_ID_NACK_TM : MAVLink_nack_tm_message,
- MAVLINK_MSG_ID_GPS_TM : MAVLink_gps_tm_message,
- MAVLINK_MSG_ID_IMU_TM : MAVLink_imu_tm_message,
- MAVLINK_MSG_ID_PRESSURE_TM : MAVLink_pressure_tm_message,
- MAVLINK_MSG_ID_ADC_TM : MAVLink_adc_tm_message,
- MAVLINK_MSG_ID_VOLTAGE_TM : MAVLink_voltage_tm_message,
- MAVLINK_MSG_ID_CURRENT_TM : MAVLink_current_tm_message,
- MAVLINK_MSG_ID_TEMP_TM : MAVLink_temp_tm_message,
- MAVLINK_MSG_ID_LOAD_TM : MAVLink_load_tm_message,
- MAVLINK_MSG_ID_ATTITUDE_TM : MAVLink_attitude_tm_message,
- MAVLINK_MSG_ID_SENSOR_STATE_TM : MAVLink_sensor_state_tm_message,
- MAVLINK_MSG_ID_SERVO_TM : MAVLink_servo_tm_message,
- MAVLINK_MSG_ID_PIN_TM : MAVLink_pin_tm_message,
- MAVLINK_MSG_ID_RECEIVER_TM : MAVLink_receiver_tm_message,
- MAVLINK_MSG_ID_ARP_TM : MAVLink_arp_tm_message,
- MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC : MAVLink_set_antenna_coordinates_arp_tc_message,
- MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC : MAVLink_set_rocket_coordinates_arp_tc_message,
- MAVLINK_MSG_ID_SYS_TM : MAVLink_sys_tm_message,
- MAVLINK_MSG_ID_FSM_TM : MAVLink_fsm_tm_message,
- MAVLINK_MSG_ID_LOGGER_TM : MAVLink_logger_tm_message,
- MAVLINK_MSG_ID_MAVLINK_STATS_TM : MAVLink_mavlink_stats_tm_message,
- MAVLINK_MSG_ID_TASK_STATS_TM : MAVLink_task_stats_tm_message,
- MAVLINK_MSG_ID_ADA_TM : MAVLink_ada_tm_message,
- MAVLINK_MSG_ID_NAS_TM : MAVLink_nas_tm_message,
- MAVLINK_MSG_ID_MEA_TM : MAVLink_mea_tm_message,
- MAVLINK_MSG_ID_ROCKET_FLIGHT_TM : MAVLink_rocket_flight_tm_message,
- MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM : MAVLink_payload_flight_tm_message,
- MAVLINK_MSG_ID_ROCKET_STATS_TM : MAVLink_rocket_stats_tm_message,
- MAVLINK_MSG_ID_PAYLOAD_STATS_TM : MAVLink_payload_stats_tm_message,
- MAVLINK_MSG_ID_GSE_TM : MAVLink_gse_tm_message,
- MAVLINK_MSG_ID_MOTOR_TM : MAVLink_motor_tm_message,
-}
-
-class MAVError(Exception):
- '''MAVLink error class'''
- def __init__(self, msg):
- Exception.__init__(self, msg)
- self.message = msg
-
-class MAVString(str):
- '''NUL terminated string'''
- def __init__(self, s):
- str.__init__(self)
- def __str__(self):
- i = self.find(chr(0))
- if i == -1:
- return self[:]
- return self[0:i]
-
-class MAVLink_bad_data(MAVLink_message):
- '''
- a piece of bad data in a mavlink stream
- '''
- def __init__(self, data, reason):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_BAD_DATA, 'BAD_DATA')
- self._fieldnames = ['data', 'reason']
- self.data = data
- self.reason = reason
- self._msgbuf = data
- self._instance_field = None
-
- def __str__(self):
- '''Override the __str__ function from MAVLink_messages because non-printable characters are common in to be the reason for this message to exist.'''
- return '%s {%s, data:%s}' % (self._type, self.reason, [('%x' % ord(i) if isinstance(i, str) else '%x' % i) for i in self.data])
-
-class MAVLink_unknown(MAVLink_message):
- '''
- a message that we don't have in the XML used when built
- '''
- def __init__(self, msgid, data):
- MAVLink_message.__init__(self, MAVLINK_MSG_ID_UNKNOWN, 'UNKNOWN_%u' % msgid)
- self._fieldnames = ['data']
- self.data = data
- self._msgbuf = data
- self._instance_field = None
-
- def __str__(self):
- '''Override the __str__ function from MAVLink_messages because non-printable characters are common.'''
- return '%s {data:%s}' % (self._type, [('%x' % ord(i) if isinstance(i, str) else '%x' % i) for i in self.data])
-
-class MAVLinkSigning(object):
- '''MAVLink signing state class'''
- def __init__(self):
- self.secret_key = None
- self.timestamp = 0
- self.link_id = 0
- self.sign_outgoing = False
- self.allow_unsigned_callback = None
- self.stream_timestamps = {}
- self.sig_count = 0
- self.badsig_count = 0
- self.goodsig_count = 0
- self.unsigned_count = 0
- self.reject_count = 0
-
-class MAVLink(object):
- '''MAVLink protocol handling class'''
- def __init__(self, file, srcSystem=0, srcComponent=0, use_native=False):
- self.seq = 0
- self.file = file
- self.srcSystem = srcSystem
- self.srcComponent = srcComponent
- self.callback = None
- self.callback_args = None
- self.callback_kwargs = None
- self.send_callback = None
- self.send_callback_args = None
- self.send_callback_kwargs = None
- self.buf = bytearray()
- self.buf_index = 0
- self.expected_length = HEADER_LEN_V1+2
- self.have_prefix_error = False
- self.robust_parsing = False
- self.protocol_marker = 254
- self.little_endian = True
- self.crc_extra = True
- self.sort_fields = True
- self.total_packets_sent = 0
- self.total_bytes_sent = 0
- self.total_packets_received = 0
- self.total_bytes_received = 0
- self.total_receive_errors = 0
- self.startup_time = time.time()
- self.signing = MAVLinkSigning()
- if native_supported and (use_native or native_testing or native_force):
- print("NOTE: mavnative is currently beta-test code")
- self.native = mavnative.NativeConnection(MAVLink_message, mavlink_map)
- else:
- self.native = None
- if native_testing:
- self.test_buf = bytearray()
- self.mav20_unpacker = struct.Struct('<cBBBBBBHB')
- self.mav10_unpacker = struct.Struct('<cBBBBB')
- self.mav20_h3_unpacker = struct.Struct('BBB')
- self.mav_csum_unpacker = struct.Struct('<H')
- self.mav_sign_unpacker = struct.Struct('<IH')
-
- def set_callback(self, callback, *args, **kwargs):
- self.callback = callback
- self.callback_args = args
- self.callback_kwargs = kwargs
-
- def set_send_callback(self, callback, *args, **kwargs):
- self.send_callback = callback
- self.send_callback_args = args
- self.send_callback_kwargs = kwargs
-
- def send(self, mavmsg, force_mavlink1=False):
- '''send a MAVLink message'''
- buf = mavmsg.pack(self, force_mavlink1=force_mavlink1)
- self.file.write(buf)
- self.seq = (self.seq + 1) % 256
- self.total_packets_sent += 1
- self.total_bytes_sent += len(buf)
- if self.send_callback:
- self.send_callback(mavmsg, *self.send_callback_args, **self.send_callback_kwargs)
-
- def buf_len(self):
- return len(self.buf) - self.buf_index
-
- def bytes_needed(self):
- '''return number of bytes needed for next parsing stage'''
- if self.native:
- ret = self.native.expected_length - self.buf_len()
- else:
- ret = self.expected_length - self.buf_len()
-
- if ret <= 0:
- return 1
- return ret
-
- def __parse_char_native(self, c):
- '''this method exists only to see in profiling results'''
- m = self.native.parse_chars(c)
- return m
-
- def __callbacks(self, msg):
- '''this method exists only to make profiling results easier to read'''
- if self.callback:
- self.callback(msg, *self.callback_args, **self.callback_kwargs)
-
- def parse_char(self, c):
- '''input some data bytes, possibly returning a new message'''
- self.buf.extend(c)
-
- self.total_bytes_received += len(c)
-
- if self.native:
- if native_testing:
- self.test_buf.extend(c)
- m = self.__parse_char_native(self.test_buf)
- m2 = self.__parse_char_legacy()
- if m2 != m:
- print("Native: %s\nLegacy: %s\n" % (m, m2))
- raise Exception('Native vs. Legacy mismatch')
- else:
- m = self.__parse_char_native(self.buf)
- else:
- m = self.__parse_char_legacy()
-
- if m is not None:
- self.total_packets_received += 1
- self.__callbacks(m)
- else:
- # XXX The idea here is if we've read something and there's nothing left in
- # the buffer, reset it to 0 which frees the memory
- if self.buf_len() == 0 and self.buf_index != 0:
- self.buf = bytearray()
- self.buf_index = 0
-
- return m
-
- def __parse_char_legacy(self):
- '''input some data bytes, possibly returning a new message (uses no native code)'''
- header_len = HEADER_LEN_V1
- if self.buf_len() >= 1 and self.buf[self.buf_index] == PROTOCOL_MARKER_V2:
- header_len = HEADER_LEN_V2
-
- if self.buf_len() >= 1 and self.buf[self.buf_index] != PROTOCOL_MARKER_V1 and self.buf[self.buf_index] != PROTOCOL_MARKER_V2:
- magic = self.buf[self.buf_index]
- self.buf_index += 1
- if self.robust_parsing:
- m = MAVLink_bad_data(bytearray([magic]), 'Bad prefix')
- self.expected_length = header_len+2
- self.total_receive_errors += 1
- return m
- if self.have_prefix_error:
- return None
- self.have_prefix_error = True
- self.total_receive_errors += 1
- raise MAVError("invalid MAVLink prefix '%s'" % magic)
- self.have_prefix_error = False
- if self.buf_len() >= 3:
- sbuf = self.buf[self.buf_index:3+self.buf_index]
- if sys.version_info.major < 3:
- sbuf = str(sbuf)
- (magic, self.expected_length, incompat_flags) = self.mav20_h3_unpacker.unpack(sbuf)
- if magic == PROTOCOL_MARKER_V2 and (incompat_flags & MAVLINK_IFLAG_SIGNED):
- self.expected_length += MAVLINK_SIGNATURE_BLOCK_LEN
- self.expected_length += header_len + 2
- if self.expected_length >= (header_len+2) and self.buf_len() >= self.expected_length:
- mbuf = array.array('B', self.buf[self.buf_index:self.buf_index+self.expected_length])
- self.buf_index += self.expected_length
- self.expected_length = header_len+2
- if self.robust_parsing:
- try:
- if magic == PROTOCOL_MARKER_V2 and (incompat_flags & ~MAVLINK_IFLAG_SIGNED) != 0:
- raise MAVError('invalid incompat_flags 0x%x 0x%x %u' % (incompat_flags, magic, self.expected_length))
- m = self.decode(mbuf)
- except MAVError as reason:
- m = MAVLink_bad_data(mbuf, reason.message)
- self.total_receive_errors += 1
- else:
- if magic == PROTOCOL_MARKER_V2 and (incompat_flags & ~MAVLINK_IFLAG_SIGNED) != 0:
- raise MAVError('invalid incompat_flags 0x%x 0x%x %u' % (incompat_flags, magic, self.expected_length))
- m = self.decode(mbuf)
- return m
- return None
-
- def parse_buffer(self, s):
- '''input some data bytes, possibly returning a list of new messages'''
- m = self.parse_char(s)
- if m is None:
- return None
- ret = [m]
- while True:
- m = self.parse_char("")
- if m is None:
- return ret
- ret.append(m)
- return ret
-
- def check_signature(self, msgbuf, srcSystem, srcComponent):
- '''check signature on incoming message'''
- if isinstance(msgbuf, array.array):
- try:
- msgbuf = msgbuf.tostring()
- except:
- msgbuf = msgbuf.tobytes()
- timestamp_buf = msgbuf[-12:-6]
- link_id = msgbuf[-13]
- (tlow, thigh) = self.mav_sign_unpacker.unpack(timestamp_buf)
- timestamp = tlow + (thigh<<32)
-
- # see if the timestamp is acceptable
- stream_key = (link_id,srcSystem,srcComponent)
- if stream_key in self.signing.stream_timestamps:
- if timestamp <= self.signing.stream_timestamps[stream_key]:
- # reject old timestamp
- # print('old timestamp')
- return False
- else:
- # a new stream has appeared. Accept the timestamp if it is at most
- # one minute behind our current timestamp
- if timestamp + 6000*1000 < self.signing.timestamp:
- # print('bad new stream ', timestamp/(100.0*1000*60*60*24*365), self.signing.timestamp/(100.0*1000*60*60*24*365))
- return False
- self.signing.stream_timestamps[stream_key] = timestamp
- # print('new stream')
-
- h = hashlib.new('sha256')
- h.update(self.signing.secret_key)
- h.update(msgbuf[:-6])
- if str(type(msgbuf)) == "<class 'bytes'>" or str(type(msgbuf)) == "<class 'bytearray'>":
- # Python 3
- sig1 = h.digest()[:6]
- sig2 = msgbuf[-6:]
- else:
- sig1 = str(h.digest())[:6]
- sig2 = str(msgbuf)[-6:]
- if sig1 != sig2:
- # print('sig mismatch')
- return False
-
- # the timestamp we next send with is the max of the received timestamp and
- # our current timestamp
- self.signing.timestamp = max(self.signing.timestamp, timestamp)
- return True
-
- def decode(self, msgbuf):
- '''decode a buffer as a MAVLink message'''
- # decode the header
- if msgbuf[0] != PROTOCOL_MARKER_V1:
- headerlen = 10
- try:
- magic, mlen, incompat_flags, compat_flags, seq, srcSystem, srcComponent, msgIdlow, msgIdhigh = self.mav20_unpacker.unpack(msgbuf[:headerlen])
- except struct.error as emsg:
- raise MAVError('Unable to unpack MAVLink header: %s' % emsg)
- msgId = msgIdlow | (msgIdhigh<<16)
- mapkey = msgId
- else:
- headerlen = 6
- try:
- magic, mlen, seq, srcSystem, srcComponent, msgId = self.mav10_unpacker.unpack(msgbuf[:headerlen])
- incompat_flags = 0
- compat_flags = 0
- except struct.error as emsg:
- raise MAVError('Unable to unpack MAVLink header: %s' % emsg)
- mapkey = msgId
- if (incompat_flags & MAVLINK_IFLAG_SIGNED) != 0:
- signature_len = MAVLINK_SIGNATURE_BLOCK_LEN
- else:
- signature_len = 0
-
- if ord(magic) != PROTOCOL_MARKER_V1 and ord(magic) != PROTOCOL_MARKER_V2:
- raise MAVError("invalid MAVLink prefix '%s'" % magic)
- if mlen != len(msgbuf)-(headerlen+2+signature_len):
- raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u headerlen=%u' % (len(msgbuf)-(headerlen+2+signature_len), mlen, msgId, headerlen))
-
- if not mapkey in mavlink_map:
- return MAVLink_unknown(msgId, msgbuf)
-
- # decode the payload
- type = mavlink_map[mapkey]
- fmt = type.format
- order_map = type.orders
- len_map = type.lengths
- crc_extra = type.crc_extra
-
- # decode the checksum
- try:
- crc, = self.mav_csum_unpacker.unpack(msgbuf[-(2+signature_len):][:2])
- except struct.error as emsg:
- raise MAVError('Unable to unpack MAVLink CRC: %s' % emsg)
- crcbuf = msgbuf[1:-(2+signature_len)]
- if True: # using CRC extra
- crcbuf.append(crc_extra)
- crc2 = x25crc(crcbuf)
- if crc != crc2.crc and not MAVLINK_IGNORE_CRC:
- raise MAVError('invalid MAVLink CRC in msgID %u 0x%04x should be 0x%04x' % (msgId, crc, crc2.crc))
-
- sig_ok = False
- if signature_len == MAVLINK_SIGNATURE_BLOCK_LEN:
- self.signing.sig_count += 1
- if self.signing.secret_key is not None:
- accept_signature = False
- if signature_len == MAVLINK_SIGNATURE_BLOCK_LEN:
- sig_ok = self.check_signature(msgbuf, srcSystem, srcComponent)
- accept_signature = sig_ok
- if sig_ok:
- self.signing.goodsig_count += 1
- else:
- self.signing.badsig_count += 1
- if not accept_signature and self.signing.allow_unsigned_callback is not None:
- accept_signature = self.signing.allow_unsigned_callback(self, msgId)
- if accept_signature:
- self.signing.unsigned_count += 1
- else:
- self.signing.reject_count += 1
- elif self.signing.allow_unsigned_callback is not None:
- accept_signature = self.signing.allow_unsigned_callback(self, msgId)
- if accept_signature:
- self.signing.unsigned_count += 1
- else:
- self.signing.reject_count += 1
- if not accept_signature:
- raise MAVError('Invalid signature')
-
- csize = type.unpacker.size
- mbuf = msgbuf[headerlen:-(2+signature_len)]
- if len(mbuf) < csize:
- # zero pad to give right size
- mbuf.extend([0]*(csize - len(mbuf)))
- if len(mbuf) < csize:
- raise MAVError('Bad message of type %s length %u needs %s' % (
- type, len(mbuf), csize))
- mbuf = mbuf[:csize]
- try:
- t = type.unpacker.unpack(mbuf)
- except struct.error as emsg:
- raise MAVError('Unable to unpack MAVLink payload type=%s fmt=%s payloadLength=%u: %s' % (
- type, fmt, len(mbuf), emsg))
-
- tlist = list(t)
- # handle sorted fields
- if True:
- t = tlist[:]
- if sum(len_map) == len(len_map):
- # message has no arrays in it
- for i in range(0, len(tlist)):
- tlist[i] = t[order_map[i]]
- else:
- # message has some arrays
- tlist = []
- for i in range(0, len(order_map)):
- order = order_map[i]
- L = len_map[order]
- tip = sum(len_map[:order])
- field = t[tip]
- if L == 1 or isinstance(field, str):
- tlist.append(field)
- else:
- tlist.append(t[tip:(tip + L)])
-
- # terminate any strings
- for i in range(0, len(tlist)):
- if type.fieldtypes[i] == 'char':
- if sys.version_info.major >= 3:
- tlist[i] = to_string(tlist[i])
- tlist[i] = str(MAVString(tlist[i]))
- t = tuple(tlist)
- # construct the message object
- try:
- m = type(*t)
- except Exception as emsg:
- raise MAVError('Unable to instantiate MAVLink message of type %s : %s' % (type, emsg))
- m._signed = sig_ok
- if m._signed:
- m._link_id = msgbuf[-13]
- m._msgbuf = msgbuf
- m._payload = msgbuf[6:-(2+signature_len)]
- m._crc = crc
- m._header = MAVLink_header(msgId, incompat_flags, compat_flags, mlen, seq, srcSystem, srcComponent)
- return m
- def ping_tc_encode(self, timestamp):
- '''
- TC to ping the rocket (expects an ACK message as a response)
-
- timestamp : Timestamp to identify when it was sent (type:uint64_t)
-
- '''
- return MAVLink_ping_tc_message(timestamp)
-
- def ping_tc_send(self, timestamp, force_mavlink1=False):
- '''
- TC to ping the rocket (expects an ACK message as a response)
-
- timestamp : Timestamp to identify when it was sent (type:uint64_t)
-
- '''
- return self.send(self.ping_tc_encode(timestamp), force_mavlink1=force_mavlink1)
-
- def command_tc_encode(self, command_id):
- '''
- TC containing a command with no parameters that trigger some action
-
- command_id : A member of the MavCommandList enum (type:uint8_t)
-
- '''
- return MAVLink_command_tc_message(command_id)
-
- def command_tc_send(self, command_id, force_mavlink1=False):
- '''
- TC containing a command with no parameters that trigger some action
-
- command_id : A member of the MavCommandList enum (type:uint8_t)
-
- '''
- return self.send(self.command_tc_encode(command_id), force_mavlink1=force_mavlink1)
-
- def system_tm_request_tc_encode(self, tm_id):
- '''
- TC containing a request for the status of a board
-
- tm_id : A member of the SystemTMList enum (type:uint8_t)
-
- '''
- return MAVLink_system_tm_request_tc_message(tm_id)
-
- def system_tm_request_tc_send(self, tm_id, force_mavlink1=False):
- '''
- TC containing a request for the status of a board
-
- tm_id : A member of the SystemTMList enum (type:uint8_t)
-
- '''
- return self.send(self.system_tm_request_tc_encode(tm_id), force_mavlink1=force_mavlink1)
-
- def sensor_tm_request_tc_encode(self, sensor_name):
- '''
- TC containing a request for sensors telemetry
-
- sensor_name : A member of the SensorTMList enum (type:uint8_t)
-
- '''
- return MAVLink_sensor_tm_request_tc_message(sensor_name)
-
- def sensor_tm_request_tc_send(self, sensor_name, force_mavlink1=False):
- '''
- TC containing a request for sensors telemetry
-
- sensor_name : A member of the SensorTMList enum (type:uint8_t)
-
- '''
- return self.send(self.sensor_tm_request_tc_encode(sensor_name), force_mavlink1=force_mavlink1)
-
- def servo_tm_request_tc_encode(self, servo_id):
- '''
- TC containing a request for servo telemetry
-
- servo_id : A member of the ServosList enum (type:uint8_t)
-
- '''
- return MAVLink_servo_tm_request_tc_message(servo_id)
-
- def servo_tm_request_tc_send(self, servo_id, force_mavlink1=False):
- '''
- TC containing a request for servo telemetry
-
- servo_id : A member of the ServosList enum (type:uint8_t)
-
- '''
- return self.send(self.servo_tm_request_tc_encode(servo_id), force_mavlink1=force_mavlink1)
-
- def set_servo_angle_tc_encode(self, servo_id, angle):
- '''
- Sets the angle of a certain servo
-
- servo_id : A member of the ServosList enum (type:uint8_t)
- angle : Servo angle in normalized value [0-1] (type:float)
-
- '''
- return MAVLink_set_servo_angle_tc_message(servo_id, angle)
-
- def set_servo_angle_tc_send(self, servo_id, angle, force_mavlink1=False):
- '''
- Sets the angle of a certain servo
-
- servo_id : A member of the ServosList enum (type:uint8_t)
- angle : Servo angle in normalized value [0-1] (type:float)
-
- '''
- return self.send(self.set_servo_angle_tc_encode(servo_id, angle), force_mavlink1=force_mavlink1)
-
- def wiggle_servo_tc_encode(self, servo_id):
- '''
- Wiggles the specified servo
-
- servo_id : A member of the ServosList enum (type:uint8_t)
-
- '''
- return MAVLink_wiggle_servo_tc_message(servo_id)
-
- def wiggle_servo_tc_send(self, servo_id, force_mavlink1=False):
- '''
- Wiggles the specified servo
-
- servo_id : A member of the ServosList enum (type:uint8_t)
-
- '''
- return self.send(self.wiggle_servo_tc_encode(servo_id), force_mavlink1=force_mavlink1)
-
- def reset_servo_tc_encode(self, servo_id):
- '''
- Resets the specified servo
-
- servo_id : A member of the ServosList enum (type:uint8_t)
-
- '''
- return MAVLink_reset_servo_tc_message(servo_id)
-
- def reset_servo_tc_send(self, servo_id, force_mavlink1=False):
- '''
- Resets the specified servo
-
- servo_id : A member of the ServosList enum (type:uint8_t)
-
- '''
- return self.send(self.reset_servo_tc_encode(servo_id), force_mavlink1=force_mavlink1)
-
- def set_reference_altitude_tc_encode(self, ref_altitude):
- '''
- Sets the reference altitude for the altimeter
-
- ref_altitude : Reference altitude [m] (type:float)
-
- '''
- return MAVLink_set_reference_altitude_tc_message(ref_altitude)
-
- def set_reference_altitude_tc_send(self, ref_altitude, force_mavlink1=False):
- '''
- Sets the reference altitude for the altimeter
-
- ref_altitude : Reference altitude [m] (type:float)
-
- '''
- return self.send(self.set_reference_altitude_tc_encode(ref_altitude), force_mavlink1=force_mavlink1)
-
- def set_reference_temperature_tc_encode(self, ref_temp):
- '''
- Sets the reference temperature for the altimeter
-
- ref_temp : Reference temperature [degC] (type:float)
-
- '''
- return MAVLink_set_reference_temperature_tc_message(ref_temp)
-
- def set_reference_temperature_tc_send(self, ref_temp, force_mavlink1=False):
- '''
- Sets the reference temperature for the altimeter
-
- ref_temp : Reference temperature [degC] (type:float)
-
- '''
- return self.send(self.set_reference_temperature_tc_encode(ref_temp), force_mavlink1=force_mavlink1)
-
- def set_orientation_tc_encode(self, yaw, pitch, roll):
- '''
- Sets current orientation for the navigation system
-
- yaw : Yaw angle [deg] (type:float)
- pitch : Pitch angle [deg] (type:float)
- roll : Roll angle [deg] (type:float)
-
- '''
- return MAVLink_set_orientation_tc_message(yaw, pitch, roll)
-
- def set_orientation_tc_send(self, yaw, pitch, roll, force_mavlink1=False):
- '''
- Sets current orientation for the navigation system
-
- yaw : Yaw angle [deg] (type:float)
- pitch : Pitch angle [deg] (type:float)
- roll : Roll angle [deg] (type:float)
-
- '''
- return self.send(self.set_orientation_tc_encode(yaw, pitch, roll), force_mavlink1=force_mavlink1)
-
- def set_coordinates_tc_encode(self, latitude, longitude):
- '''
- Sets current coordinates
-
- latitude : Latitude [deg] (type:float)
- longitude : Longitude [deg] (type:float)
-
- '''
- return MAVLink_set_coordinates_tc_message(latitude, longitude)
-
- def set_coordinates_tc_send(self, latitude, longitude, force_mavlink1=False):
- '''
- Sets current coordinates
-
- latitude : Latitude [deg] (type:float)
- longitude : Longitude [deg] (type:float)
-
- '''
- return self.send(self.set_coordinates_tc_encode(latitude, longitude), force_mavlink1=force_mavlink1)
-
- def raw_event_tc_encode(self, topic_id, event_id):
- '''
- TC containing a raw event to be posted directly in the EventBroker
-
- topic_id : Id of the topic to which the event should be posted (type:uint8_t)
- event_id : Id of the event to be posted (type:uint8_t)
-
- '''
- return MAVLink_raw_event_tc_message(topic_id, event_id)
-
- def raw_event_tc_send(self, topic_id, event_id, force_mavlink1=False):
- '''
- TC containing a raw event to be posted directly in the EventBroker
-
- topic_id : Id of the topic to which the event should be posted (type:uint8_t)
- event_id : Id of the event to be posted (type:uint8_t)
-
- '''
- return self.send(self.raw_event_tc_encode(topic_id, event_id), force_mavlink1=force_mavlink1)
-
- def set_deployment_altitude_tc_encode(self, dpl_altitude):
- '''
- Sets the deployment altitude for the main parachute
-
- dpl_altitude : Deployment altitude [m] (type:float)
-
- '''
- return MAVLink_set_deployment_altitude_tc_message(dpl_altitude)
-
- def set_deployment_altitude_tc_send(self, dpl_altitude, force_mavlink1=False):
- '''
- Sets the deployment altitude for the main parachute
-
- dpl_altitude : Deployment altitude [m] (type:float)
-
- '''
- return self.send(self.set_deployment_altitude_tc_encode(dpl_altitude), force_mavlink1=force_mavlink1)
-
- def set_target_coordinates_tc_encode(self, latitude, longitude):
- '''
- Sets the target coordinates
-
- latitude : Latitude [deg] (type:float)
- longitude : Longitude [deg] (type:float)
-
- '''
- return MAVLink_set_target_coordinates_tc_message(latitude, longitude)
-
- def set_target_coordinates_tc_send(self, latitude, longitude, force_mavlink1=False):
- '''
- Sets the target coordinates
-
- latitude : Latitude [deg] (type:float)
- longitude : Longitude [deg] (type:float)
-
- '''
- return self.send(self.set_target_coordinates_tc_encode(latitude, longitude), force_mavlink1=force_mavlink1)
-
- def set_algorithm_tc_encode(self, algorithm_number):
- '''
- Sets the algorithm number (for parafoil guidance and GSE tars)
-
- algorithm_number : Algorithm number (type:uint8_t)
-
- '''
- return MAVLink_set_algorithm_tc_message(algorithm_number)
-
- def set_algorithm_tc_send(self, algorithm_number, force_mavlink1=False):
- '''
- Sets the algorithm number (for parafoil guidance and GSE tars)
-
- algorithm_number : Algorithm number (type:uint8_t)
-
- '''
- return self.send(self.set_algorithm_tc_encode(algorithm_number), force_mavlink1=force_mavlink1)
-
- def set_atomic_valve_timing_tc_encode(self, servo_id, maximum_timing):
- '''
- Sets the maximum time that the valves can be open atomically
-
- servo_id : A member of the ServosList enum (type:uint8_t)
- maximum_timing : Maximum timing in [ms] [ms] (type:uint32_t)
-
- '''
- return MAVLink_set_atomic_valve_timing_tc_message(servo_id, maximum_timing)
-
- def set_atomic_valve_timing_tc_send(self, servo_id, maximum_timing, force_mavlink1=False):
- '''
- Sets the maximum time that the valves can be open atomically
-
- servo_id : A member of the ServosList enum (type:uint8_t)
- maximum_timing : Maximum timing in [ms] [ms] (type:uint32_t)
-
- '''
- return self.send(self.set_atomic_valve_timing_tc_encode(servo_id, maximum_timing), force_mavlink1=force_mavlink1)
-
- def set_valve_maximum_aperture_tc_encode(self, servo_id, maximum_aperture):
- '''
- Sets the maximum aperture of the specified valve. Set as value from 0
- to 1
-
- servo_id : A member of the ServosList enum (type:uint8_t)
- maximum_aperture : Maximum aperture (type:float)
-
- '''
- return MAVLink_set_valve_maximum_aperture_tc_message(servo_id, maximum_aperture)
-
- def set_valve_maximum_aperture_tc_send(self, servo_id, maximum_aperture, force_mavlink1=False):
- '''
- Sets the maximum aperture of the specified valve. Set as value from 0
- to 1
-
- servo_id : A member of the ServosList enum (type:uint8_t)
- maximum_aperture : Maximum aperture (type:float)
-
- '''
- return self.send(self.set_valve_maximum_aperture_tc_encode(servo_id, maximum_aperture), force_mavlink1=force_mavlink1)
-
- def conrig_state_tc_encode(self, ignition_btn, filling_valve_btn, venting_valve_btn, release_pressure_btn, quick_connector_btn, start_tars_btn, arm_switch):
- '''
- Send the state of the conrig buttons
-
- ignition_btn : Ignition button pressed (type:uint8_t)
- filling_valve_btn : Open filling valve pressed (type:uint8_t)
- venting_valve_btn : Open venting valve pressed (type:uint8_t)
- release_pressure_btn : Release filling line pressure pressed (type:uint8_t)
- quick_connector_btn : Detach quick connector pressed (type:uint8_t)
- start_tars_btn : Startup TARS pressed (type:uint8_t)
- arm_switch : Arming switch state (type:uint8_t)
-
- '''
- return MAVLink_conrig_state_tc_message(ignition_btn, filling_valve_btn, venting_valve_btn, release_pressure_btn, quick_connector_btn, start_tars_btn, arm_switch)
-
- def conrig_state_tc_send(self, ignition_btn, filling_valve_btn, venting_valve_btn, release_pressure_btn, quick_connector_btn, start_tars_btn, arm_switch, force_mavlink1=False):
- '''
- Send the state of the conrig buttons
-
- ignition_btn : Ignition button pressed (type:uint8_t)
- filling_valve_btn : Open filling valve pressed (type:uint8_t)
- venting_valve_btn : Open venting valve pressed (type:uint8_t)
- release_pressure_btn : Release filling line pressure pressed (type:uint8_t)
- quick_connector_btn : Detach quick connector pressed (type:uint8_t)
- start_tars_btn : Startup TARS pressed (type:uint8_t)
- arm_switch : Arming switch state (type:uint8_t)
-
- '''
- return self.send(self.conrig_state_tc_encode(ignition_btn, filling_valve_btn, venting_valve_btn, release_pressure_btn, quick_connector_btn, start_tars_btn, arm_switch), force_mavlink1=force_mavlink1)
-
- def set_ignition_time_tc_encode(self, timing):
- '''
- Sets the time in ms that the igniter stays on before the oxidant valve
- is opened
-
- timing : Timing in [ms] [ms] (type:uint32_t)
-
- '''
- return MAVLink_set_ignition_time_tc_message(timing)
-
- def set_ignition_time_tc_send(self, timing, force_mavlink1=False):
- '''
- Sets the time in ms that the igniter stays on before the oxidant valve
- is opened
-
- timing : Timing in [ms] [ms] (type:uint32_t)
-
- '''
- return self.send(self.set_ignition_time_tc_encode(timing), force_mavlink1=force_mavlink1)
-
- def set_stepper_angle_tc_encode(self, stepper_id, angle):
- '''
- Move the stepper of a certain angle
-
- stepper_id : A member of the StepperList enum (type:uint8_t)
- angle : Stepper angle in degrees (type:float)
-
- '''
- return MAVLink_set_stepper_angle_tc_message(stepper_id, angle)
-
- def set_stepper_angle_tc_send(self, stepper_id, angle, force_mavlink1=False):
- '''
- Move the stepper of a certain angle
-
- stepper_id : A member of the StepperList enum (type:uint8_t)
- angle : Stepper angle in degrees (type:float)
-
- '''
- return self.send(self.set_stepper_angle_tc_encode(stepper_id, angle), force_mavlink1=force_mavlink1)
-
- def set_stepper_steps_tc_encode(self, stepper_id, steps):
- '''
- Move the stepper of a certain amount of steps
-
- stepper_id : A member of the StepperList enum (type:uint8_t)
- steps : Number of steps (type:float)
-
- '''
- return MAVLink_set_stepper_steps_tc_message(stepper_id, steps)
-
- def set_stepper_steps_tc_send(self, stepper_id, steps, force_mavlink1=False):
- '''
- Move the stepper of a certain amount of steps
-
- stepper_id : A member of the StepperList enum (type:uint8_t)
- steps : Number of steps (type:float)
-
- '''
- return self.send(self.set_stepper_steps_tc_encode(stepper_id, steps), force_mavlink1=force_mavlink1)
-
- def ack_tm_encode(self, recv_msgid, seq_ack):
- '''
- TM containing an ACK message to notify that the message has been
- received
-
- recv_msgid : Message id of the received message (type:uint8_t)
- seq_ack : Sequence number of the received message (type:uint8_t)
-
- '''
- return MAVLink_ack_tm_message(recv_msgid, seq_ack)
-
- def ack_tm_send(self, recv_msgid, seq_ack, force_mavlink1=False):
- '''
- TM containing an ACK message to notify that the message has been
- received
-
- recv_msgid : Message id of the received message (type:uint8_t)
- seq_ack : Sequence number of the received message (type:uint8_t)
-
- '''
- return self.send(self.ack_tm_encode(recv_msgid, seq_ack), force_mavlink1=force_mavlink1)
-
- def nack_tm_encode(self, recv_msgid, seq_ack):
- '''
- TM containing a NACK message to notify that the received message was
- invalid
-
- recv_msgid : Message id of the received message (type:uint8_t)
- seq_ack : Sequence number of the received message (type:uint8_t)
-
- '''
- return MAVLink_nack_tm_message(recv_msgid, seq_ack)
-
- def nack_tm_send(self, recv_msgid, seq_ack, force_mavlink1=False):
- '''
- TM containing a NACK message to notify that the received message was
- invalid
-
- recv_msgid : Message id of the received message (type:uint8_t)
- seq_ack : Sequence number of the received message (type:uint8_t)
-
- '''
- return self.send(self.nack_tm_encode(recv_msgid, seq_ack), force_mavlink1=force_mavlink1)
-
- def gps_tm_encode(self, timestamp, sensor_name, fix, latitude, longitude, height, vel_north, vel_east, vel_down, speed, track, n_satellites):
- '''
-
-
- timestamp : When was this logged [us] (type:uint64_t)
- sensor_name : Sensor name (type:char)
- fix : Wether the GPS has a FIX (type:uint8_t)
- latitude : Latitude [deg] (type:double)
- longitude : Longitude [deg] (type:double)
- height : Altitude [m] (type:double)
- vel_north : Velocity in NED frame (north) [m/s] (type:float)
- vel_east : Velocity in NED frame (east) [m/s] (type:float)
- vel_down : Velocity in NED frame (down) [m/s] (type:float)
- speed : Speed [m/s] (type:float)
- track : Track [deg] (type:float)
- n_satellites : Number of connected satellites (type:uint8_t)
-
- '''
- return MAVLink_gps_tm_message(timestamp, sensor_name, fix, latitude, longitude, height, vel_north, vel_east, vel_down, speed, track, n_satellites)
-
- def gps_tm_send(self, timestamp, sensor_name, fix, latitude, longitude, height, vel_north, vel_east, vel_down, speed, track, n_satellites, force_mavlink1=False):
- '''
-
-
- timestamp : When was this logged [us] (type:uint64_t)
- sensor_name : Sensor name (type:char)
- fix : Wether the GPS has a FIX (type:uint8_t)
- latitude : Latitude [deg] (type:double)
- longitude : Longitude [deg] (type:double)
- height : Altitude [m] (type:double)
- vel_north : Velocity in NED frame (north) [m/s] (type:float)
- vel_east : Velocity in NED frame (east) [m/s] (type:float)
- vel_down : Velocity in NED frame (down) [m/s] (type:float)
- speed : Speed [m/s] (type:float)
- track : Track [deg] (type:float)
- n_satellites : Number of connected satellites (type:uint8_t)
-
- '''
- return self.send(self.gps_tm_encode(timestamp, sensor_name, fix, latitude, longitude, height, vel_north, vel_east, vel_down, speed, track, n_satellites), force_mavlink1=force_mavlink1)
-
- def imu_tm_encode(self, timestamp, sensor_name, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z):
- '''
-
-
- timestamp : When was this logged [us] (type:uint64_t)
- sensor_name : Sensor name (type:char)
- acc_x : X axis acceleration [m/s2] (type:float)
- acc_y : Y axis acceleration [m/s2] (type:float)
- acc_z : Z axis acceleration [m/s2] (type:float)
- gyro_x : X axis gyro [rad/s] (type:float)
- gyro_y : Y axis gyro [rad/s] (type:float)
- gyro_z : Z axis gyro [rad/s] (type:float)
- mag_x : X axis compass [uT] (type:float)
- mag_y : Y axis compass [uT] (type:float)
- mag_z : Z axis compass [uT] (type:float)
-
- '''
- return MAVLink_imu_tm_message(timestamp, sensor_name, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z)
-
- def imu_tm_send(self, timestamp, sensor_name, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, force_mavlink1=False):
- '''
-
-
- timestamp : When was this logged [us] (type:uint64_t)
- sensor_name : Sensor name (type:char)
- acc_x : X axis acceleration [m/s2] (type:float)
- acc_y : Y axis acceleration [m/s2] (type:float)
- acc_z : Z axis acceleration [m/s2] (type:float)
- gyro_x : X axis gyro [rad/s] (type:float)
- gyro_y : Y axis gyro [rad/s] (type:float)
- gyro_z : Z axis gyro [rad/s] (type:float)
- mag_x : X axis compass [uT] (type:float)
- mag_y : Y axis compass [uT] (type:float)
- mag_z : Z axis compass [uT] (type:float)
-
- '''
- return self.send(self.imu_tm_encode(timestamp, sensor_name, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z), force_mavlink1=force_mavlink1)
-
- def pressure_tm_encode(self, timestamp, sensor_name, pressure):
- '''
-
-
- timestamp : When was this logged [us] (type:uint64_t)
- sensor_name : Sensor name (type:char)
- pressure : Pressure of the digital barometer [Pa] (type:float)
-
- '''
- return MAVLink_pressure_tm_message(timestamp, sensor_name, pressure)
-
- def pressure_tm_send(self, timestamp, sensor_name, pressure, force_mavlink1=False):
- '''
-
-
- timestamp : When was this logged [us] (type:uint64_t)
- sensor_name : Sensor name (type:char)
- pressure : Pressure of the digital barometer [Pa] (type:float)
-
- '''
- return self.send(self.pressure_tm_encode(timestamp, sensor_name, pressure), force_mavlink1=force_mavlink1)
-
- def adc_tm_encode(self, timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3, channel_4, channel_5, channel_6, channel_7):
- '''
-
-
- timestamp : When was this logged [us] (type:uint64_t)
- sensor_name : Sensor name (type:char)
- channel_0 : ADC voltage measured on channel 0 [V] (type:float)
- channel_1 : ADC voltage measured on channel 1 [V] (type:float)
- channel_2 : ADC voltage measured on channel 2 [V] (type:float)
- channel_3 : ADC voltage measured on channel 3 [V] (type:float)
- channel_4 : ADC voltage measured on channel 4 [V] (type:float)
- channel_5 : ADC voltage measured on channel 5 [V] (type:float)
- channel_6 : ADC voltage measured on channel 6 [V] (type:float)
- channel_7 : ADC voltage measured on channel 7 [V] (type:float)
-
- '''
- return MAVLink_adc_tm_message(timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3, channel_4, channel_5, channel_6, channel_7)
-
- def adc_tm_send(self, timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3, channel_4, channel_5, channel_6, channel_7, force_mavlink1=False):
- '''
-
-
- timestamp : When was this logged [us] (type:uint64_t)
- sensor_name : Sensor name (type:char)
- channel_0 : ADC voltage measured on channel 0 [V] (type:float)
- channel_1 : ADC voltage measured on channel 1 [V] (type:float)
- channel_2 : ADC voltage measured on channel 2 [V] (type:float)
- channel_3 : ADC voltage measured on channel 3 [V] (type:float)
- channel_4 : ADC voltage measured on channel 4 [V] (type:float)
- channel_5 : ADC voltage measured on channel 5 [V] (type:float)
- channel_6 : ADC voltage measured on channel 6 [V] (type:float)
- channel_7 : ADC voltage measured on channel 7 [V] (type:float)
-
- '''
- return self.send(self.adc_tm_encode(timestamp, sensor_name, channel_0, channel_1, channel_2, channel_3, channel_4, channel_5, channel_6, channel_7), force_mavlink1=force_mavlink1)
-
- def voltage_tm_encode(self, timestamp, sensor_name, voltage):
- '''
-
-
- timestamp : When was this logged [us] (type:uint64_t)
- sensor_name : Sensor name (type:char)
- voltage : Voltage [V] (type:float)
-
- '''
- return MAVLink_voltage_tm_message(timestamp, sensor_name, voltage)
-
- def voltage_tm_send(self, timestamp, sensor_name, voltage, force_mavlink1=False):
- '''
-
-
- timestamp : When was this logged [us] (type:uint64_t)
- sensor_name : Sensor name (type:char)
- voltage : Voltage [V] (type:float)
-
- '''
- return self.send(self.voltage_tm_encode(timestamp, sensor_name, voltage), force_mavlink1=force_mavlink1)
-
- def current_tm_encode(self, timestamp, sensor_name, current):
- '''
-
-
- timestamp : When was this logged [us] (type:uint64_t)
- sensor_name : Sensor name (type:char)
- current : Current [A] (type:float)
-
- '''
- return MAVLink_current_tm_message(timestamp, sensor_name, current)
-
- def current_tm_send(self, timestamp, sensor_name, current, force_mavlink1=False):
- '''
-
-
- timestamp : When was this logged [us] (type:uint64_t)
- sensor_name : Sensor name (type:char)
- current : Current [A] (type:float)
-
- '''
- return self.send(self.current_tm_encode(timestamp, sensor_name, current), force_mavlink1=force_mavlink1)
-
- def temp_tm_encode(self, timestamp, sensor_name, temperature):
- '''
-
-
- timestamp : When was this logged [us] (type:uint64_t)
- sensor_name : Sensor name (type:char)
- temperature : Temperature [deg] (type:float)
-
- '''
- return MAVLink_temp_tm_message(timestamp, sensor_name, temperature)
-
- def temp_tm_send(self, timestamp, sensor_name, temperature, force_mavlink1=False):
- '''
-
-
- timestamp : When was this logged [us] (type:uint64_t)
- sensor_name : Sensor name (type:char)
- temperature : Temperature [deg] (type:float)
-
- '''
- return self.send(self.temp_tm_encode(timestamp, sensor_name, temperature), force_mavlink1=force_mavlink1)
-
- def load_tm_encode(self, timestamp, sensor_name, load):
- '''
-
-
- timestamp : When was this logged [us] (type:uint64_t)
- sensor_name : Sensor name (type:char)
- load : Load force [kg] (type:float)
-
- '''
- return MAVLink_load_tm_message(timestamp, sensor_name, load)
-
- def load_tm_send(self, timestamp, sensor_name, load, force_mavlink1=False):
- '''
-
-
- timestamp : When was this logged [us] (type:uint64_t)
- sensor_name : Sensor name (type:char)
- load : Load force [kg] (type:float)
-
- '''
- return self.send(self.load_tm_encode(timestamp, sensor_name, load), force_mavlink1=force_mavlink1)
-
- def attitude_tm_encode(self, timestamp, sensor_name, roll, pitch, yaw, quat_x, quat_y, quat_z, quat_w):
- '''
-
-
- timestamp : When was this logged [us] (type:uint64_t)
- sensor_name : Sensor name (type:char)
- roll : Roll angle [deg] (type:float)
- pitch : Pitch angle [deg] (type:float)
- yaw : Yaw angle [deg] (type:float)
- quat_x : Quaternion x component (type:float)
- quat_y : Quaternion y component (type:float)
- quat_z : Quaternion z component (type:float)
- quat_w : Quaternion w component (type:float)
-
- '''
- return MAVLink_attitude_tm_message(timestamp, sensor_name, roll, pitch, yaw, quat_x, quat_y, quat_z, quat_w)
-
- def attitude_tm_send(self, timestamp, sensor_name, roll, pitch, yaw, quat_x, quat_y, quat_z, quat_w, force_mavlink1=False):
- '''
-
-
- timestamp : When was this logged [us] (type:uint64_t)
- sensor_name : Sensor name (type:char)
- roll : Roll angle [deg] (type:float)
- pitch : Pitch angle [deg] (type:float)
- yaw : Yaw angle [deg] (type:float)
- quat_x : Quaternion x component (type:float)
- quat_y : Quaternion y component (type:float)
- quat_z : Quaternion z component (type:float)
- quat_w : Quaternion w component (type:float)
-
- '''
- return self.send(self.attitude_tm_encode(timestamp, sensor_name, roll, pitch, yaw, quat_x, quat_y, quat_z, quat_w), force_mavlink1=force_mavlink1)
-
- def sensor_state_tm_encode(self, sensor_name, state):
- '''
-
-
- sensor_name : Sensor name (type:char)
- state : Boolean that represents the init state (type:uint8_t)
-
- '''
- return MAVLink_sensor_state_tm_message(sensor_name, state)
-
- def sensor_state_tm_send(self, sensor_name, state, force_mavlink1=False):
- '''
-
-
- sensor_name : Sensor name (type:char)
- state : Boolean that represents the init state (type:uint8_t)
-
- '''
- return self.send(self.sensor_state_tm_encode(sensor_name, state), force_mavlink1=force_mavlink1)
-
- def servo_tm_encode(self, servo_id, servo_position):
- '''
-
-
- servo_id : A member of the ServosList enum (type:uint8_t)
- servo_position : Position of the servo [0-1] (type:float)
-
- '''
- return MAVLink_servo_tm_message(servo_id, servo_position)
-
- def servo_tm_send(self, servo_id, servo_position, force_mavlink1=False):
- '''
-
-
- servo_id : A member of the ServosList enum (type:uint8_t)
- servo_position : Position of the servo [0-1] (type:float)
-
- '''
- return self.send(self.servo_tm_encode(servo_id, servo_position), force_mavlink1=force_mavlink1)
-
- def pin_tm_encode(self, timestamp, pin_id, last_change_timestamp, changes_counter, current_state):
- '''
-
-
- timestamp : Timestamp [us] (type:uint64_t)
- pin_id : A member of the PinsList enum (type:uint8_t)
- last_change_timestamp : Last change timestamp of pin (type:uint64_t)
- changes_counter : Number of changes of pin (type:uint8_t)
- current_state : Current state of pin (type:uint8_t)
-
- '''
- return MAVLink_pin_tm_message(timestamp, pin_id, last_change_timestamp, changes_counter, current_state)
-
- def pin_tm_send(self, timestamp, pin_id, last_change_timestamp, changes_counter, current_state, force_mavlink1=False):
- '''
-
-
- timestamp : Timestamp [us] (type:uint64_t)
- pin_id : A member of the PinsList enum (type:uint8_t)
- last_change_timestamp : Last change timestamp of pin (type:uint64_t)
- changes_counter : Number of changes of pin (type:uint8_t)
- current_state : Current state of pin (type:uint8_t)
-
- '''
- return self.send(self.pin_tm_encode(timestamp, pin_id, last_change_timestamp, changes_counter, current_state), force_mavlink1=force_mavlink1)
-
- def receiver_tm_encode(self, timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei, ethernet_present, ethernet_status, battery_voltage):
- '''
-
-
- timestamp : Timestamp [us] (type:uint64_t)
- main_radio_present : Boolean indicating the presence of the main radio (type:uint8_t)
- main_packet_tx_error_count : Number of errors during send (type:uint16_t)
- main_tx_bitrate : Send bitrate [b/s] (type:uint16_t)
- main_packet_rx_success_count : Number of succesfull received mavlink packets (type:uint16_t)
- main_packet_rx_drop_count : Number of dropped mavlink packets (type:uint16_t)
- main_rx_bitrate : Receive bitrate [b/s] (type:uint16_t)
- main_rx_rssi : Receive RSSI [dBm] (type:float)
- main_rx_fei : Receive frequency error index [Hz] (type:float)
- payload_radio_present : Boolean indicating the presence of the payload radio (type:uint8_t)
- payload_packet_tx_error_count : Number of errors during send (type:uint16_t)
- payload_tx_bitrate : Send bitrate [b/s] (type:uint16_t)
- payload_packet_rx_success_count : Number of succesfull received mavlink packets (type:uint16_t)
- payload_packet_rx_drop_count : Number of dropped mavlink packets (type:uint16_t)
- payload_rx_bitrate : Receive bitrate [b/s] (type:uint16_t)
- payload_rx_rssi : Receive RSSI [dBm] (type:float)
- payload_rx_fei : Receive frequency error index [Hz] (type:float)
- ethernet_present : Boolean indicating the presence of the ethernet module (type:uint8_t)
- ethernet_status : Status flag indicating the status of the ethernet PHY (type:uint8_t)
- battery_voltage : Battery voltage [V] (type:float)
-
- '''
- return MAVLink_receiver_tm_message(timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei, ethernet_present, ethernet_status, battery_voltage)
-
- def receiver_tm_send(self, timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei, ethernet_present, ethernet_status, battery_voltage, force_mavlink1=False):
- '''
-
-
- timestamp : Timestamp [us] (type:uint64_t)
- main_radio_present : Boolean indicating the presence of the main radio (type:uint8_t)
- main_packet_tx_error_count : Number of errors during send (type:uint16_t)
- main_tx_bitrate : Send bitrate [b/s] (type:uint16_t)
- main_packet_rx_success_count : Number of succesfull received mavlink packets (type:uint16_t)
- main_packet_rx_drop_count : Number of dropped mavlink packets (type:uint16_t)
- main_rx_bitrate : Receive bitrate [b/s] (type:uint16_t)
- main_rx_rssi : Receive RSSI [dBm] (type:float)
- main_rx_fei : Receive frequency error index [Hz] (type:float)
- payload_radio_present : Boolean indicating the presence of the payload radio (type:uint8_t)
- payload_packet_tx_error_count : Number of errors during send (type:uint16_t)
- payload_tx_bitrate : Send bitrate [b/s] (type:uint16_t)
- payload_packet_rx_success_count : Number of succesfull received mavlink packets (type:uint16_t)
- payload_packet_rx_drop_count : Number of dropped mavlink packets (type:uint16_t)
- payload_rx_bitrate : Receive bitrate [b/s] (type:uint16_t)
- payload_rx_rssi : Receive RSSI [dBm] (type:float)
- payload_rx_fei : Receive frequency error index [Hz] (type:float)
- ethernet_present : Boolean indicating the presence of the ethernet module (type:uint8_t)
- ethernet_status : Status flag indicating the status of the ethernet PHY (type:uint8_t)
- battery_voltage : Battery voltage [V] (type:float)
-
- '''
- return self.send(self.receiver_tm_encode(timestamp, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, main_rx_fei, payload_radio_present, payload_packet_tx_error_count, payload_tx_bitrate, payload_packet_rx_success_count, payload_packet_rx_drop_count, payload_rx_bitrate, payload_rx_rssi, payload_rx_fei, ethernet_present, ethernet_status, battery_voltage), force_mavlink1=force_mavlink1)
-
- def arp_tm_encode(self, timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, ethernet_present, ethernet_status, battery_voltage):
- '''
-
-
- timestamp : Timestamp [us] (type:uint64_t)
- yaw : Current Yaw [deg] (type:float)
- pitch : Current Pitch [deg] (type:float)
- roll : Current Roll [deg] (type:float)
- target_yaw : Target Yaw [deg] (type:float)
- target_pitch : Target Pitch [deg] (type:float)
- stepperX_pos : StepperX current position wrt the boot position [deg] (type:float)
- stepperX_delta : StepperX last actuated delta angle [deg] (type:float)
- stepperX_speed : StepperX current speed [rps] (type:float)
- stepperY_pos : StepperY current position wrt the boot position [deg] (type:float)
- stepperY_delta : StepperY last actuated delta angle [deg] (type:float)
- stepperY_speed : StepperY current Speed [rps] (type:float)
- gps_latitude : Latitude [deg] (type:float)
- gps_longitude : Longitude [deg] (type:float)
- gps_height : Altitude [m] (type:float)
- gps_fix : Wether the GPS has a FIX (type:uint8_t)
- main_radio_present : Boolean indicating the presence of the main radio (type:uint8_t)
- main_packet_tx_error_count : Number of errors during send (type:uint16_t)
- main_tx_bitrate : Send bitrate [b/s] (type:uint16_t)
- main_packet_rx_success_count : Number of succesfull received mavlink packets (type:uint16_t)
- main_packet_rx_drop_count : Number of dropped mavlink packets (type:uint16_t)
- main_rx_bitrate : Receive bitrate [b/s] (type:uint16_t)
- main_rx_rssi : Receive RSSI [dBm] (type:float)
- ethernet_present : Boolean indicating the presence of the ethernet module (type:uint8_t)
- ethernet_status : Status flag indicating the status of the ethernet PHY (type:uint8_t)
- battery_voltage : Battery voltage [V] (type:float)
-
- '''
- return MAVLink_arp_tm_message(timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, ethernet_present, ethernet_status, battery_voltage)
-
- def arp_tm_send(self, timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, ethernet_present, ethernet_status, battery_voltage, force_mavlink1=False):
- '''
-
-
- timestamp : Timestamp [us] (type:uint64_t)
- yaw : Current Yaw [deg] (type:float)
- pitch : Current Pitch [deg] (type:float)
- roll : Current Roll [deg] (type:float)
- target_yaw : Target Yaw [deg] (type:float)
- target_pitch : Target Pitch [deg] (type:float)
- stepperX_pos : StepperX current position wrt the boot position [deg] (type:float)
- stepperX_delta : StepperX last actuated delta angle [deg] (type:float)
- stepperX_speed : StepperX current speed [rps] (type:float)
- stepperY_pos : StepperY current position wrt the boot position [deg] (type:float)
- stepperY_delta : StepperY last actuated delta angle [deg] (type:float)
- stepperY_speed : StepperY current Speed [rps] (type:float)
- gps_latitude : Latitude [deg] (type:float)
- gps_longitude : Longitude [deg] (type:float)
- gps_height : Altitude [m] (type:float)
- gps_fix : Wether the GPS has a FIX (type:uint8_t)
- main_radio_present : Boolean indicating the presence of the main radio (type:uint8_t)
- main_packet_tx_error_count : Number of errors during send (type:uint16_t)
- main_tx_bitrate : Send bitrate [b/s] (type:uint16_t)
- main_packet_rx_success_count : Number of succesfull received mavlink packets (type:uint16_t)
- main_packet_rx_drop_count : Number of dropped mavlink packets (type:uint16_t)
- main_rx_bitrate : Receive bitrate [b/s] (type:uint16_t)
- main_rx_rssi : Receive RSSI [dBm] (type:float)
- ethernet_present : Boolean indicating the presence of the ethernet module (type:uint8_t)
- ethernet_status : Status flag indicating the status of the ethernet PHY (type:uint8_t)
- battery_voltage : Battery voltage [V] (type:float)
-
- '''
- return self.send(self.arp_tm_encode(timestamp, yaw, pitch, roll, target_yaw, target_pitch, stepperX_pos, stepperX_delta, stepperX_speed, stepperY_pos, stepperY_delta, stepperY_speed, gps_latitude, gps_longitude, gps_height, gps_fix, main_radio_present, main_packet_tx_error_count, main_tx_bitrate, main_packet_rx_success_count, main_packet_rx_drop_count, main_rx_bitrate, main_rx_rssi, ethernet_present, ethernet_status, battery_voltage), force_mavlink1=force_mavlink1)
-
- def set_antenna_coordinates_arp_tc_encode(self, latitude, longitude):
- '''
- Sets current antennas coordinates
-
- latitude : Latitude [deg] (type:float)
- longitude : Longitude [deg] (type:float)
-
- '''
- return MAVLink_set_antenna_coordinates_arp_tc_message(latitude, longitude)
-
- def set_antenna_coordinates_arp_tc_send(self, latitude, longitude, force_mavlink1=False):
- '''
- Sets current antennas coordinates
-
- latitude : Latitude [deg] (type:float)
- longitude : Longitude [deg] (type:float)
-
- '''
- return self.send(self.set_antenna_coordinates_arp_tc_encode(latitude, longitude), force_mavlink1=force_mavlink1)
-
- def set_rocket_coordinates_arp_tc_encode(self, latitude, longitude):
- '''
- Sets current rocket coordinates
-
- latitude : Latitude [deg] (type:float)
- longitude : Longitude [deg] (type:float)
-
- '''
- return MAVLink_set_rocket_coordinates_arp_tc_message(latitude, longitude)
-
- def set_rocket_coordinates_arp_tc_send(self, latitude, longitude, force_mavlink1=False):
- '''
- Sets current rocket coordinates
-
- latitude : Latitude [deg] (type:float)
- longitude : Longitude [deg] (type:float)
-
- '''
- return self.send(self.set_rocket_coordinates_arp_tc_encode(latitude, longitude), force_mavlink1=force_mavlink1)
-
- def sys_tm_encode(self, timestamp, logger, event_broker, radio, pin_observer, sensors, board_scheduler):
- '''
- System status telemetry
-
- timestamp : Timestamp [us] (type:uint64_t)
- logger : True if the logger started correctly (type:uint8_t)
- event_broker : True if the event broker started correctly (type:uint8_t)
- radio : True if the radio started correctly (type:uint8_t)
- pin_observer : True if the pin observer started correctly (type:uint8_t)
- sensors : True if the sensors started correctly (type:uint8_t)
- board_scheduler : True if the board scheduler is running (type:uint8_t)
-
- '''
- return MAVLink_sys_tm_message(timestamp, logger, event_broker, radio, pin_observer, sensors, board_scheduler)
-
- def sys_tm_send(self, timestamp, logger, event_broker, radio, pin_observer, sensors, board_scheduler, force_mavlink1=False):
- '''
- System status telemetry
-
- timestamp : Timestamp [us] (type:uint64_t)
- logger : True if the logger started correctly (type:uint8_t)
- event_broker : True if the event broker started correctly (type:uint8_t)
- radio : True if the radio started correctly (type:uint8_t)
- pin_observer : True if the pin observer started correctly (type:uint8_t)
- sensors : True if the sensors started correctly (type:uint8_t)
- board_scheduler : True if the board scheduler is running (type:uint8_t)
-
- '''
- return self.send(self.sys_tm_encode(timestamp, logger, event_broker, radio, pin_observer, sensors, board_scheduler), force_mavlink1=force_mavlink1)
-
- def fsm_tm_encode(self, timestamp, ada_state, abk_state, dpl_state, fmm_state, nas_state, wes_state):
- '''
- Flight State Machine status telemetry
-
- timestamp : Timestamp [us] (type:uint64_t)
- ada_state : Apogee Detection Algorithm state (type:uint8_t)
- abk_state : Air Brakes state (type:uint8_t)
- dpl_state : Deployment state (type:uint8_t)
- fmm_state : Flight Mode Manager state (type:uint8_t)
- nas_state : Navigation and Attitude System state (type:uint8_t)
- wes_state : Wind Estimation System state (type:uint8_t)
-
- '''
- return MAVLink_fsm_tm_message(timestamp, ada_state, abk_state, dpl_state, fmm_state, nas_state, wes_state)
-
- def fsm_tm_send(self, timestamp, ada_state, abk_state, dpl_state, fmm_state, nas_state, wes_state, force_mavlink1=False):
- '''
- Flight State Machine status telemetry
-
- timestamp : Timestamp [us] (type:uint64_t)
- ada_state : Apogee Detection Algorithm state (type:uint8_t)
- abk_state : Air Brakes state (type:uint8_t)
- dpl_state : Deployment state (type:uint8_t)
- fmm_state : Flight Mode Manager state (type:uint8_t)
- nas_state : Navigation and Attitude System state (type:uint8_t)
- wes_state : Wind Estimation System state (type:uint8_t)
-
- '''
- return self.send(self.fsm_tm_encode(timestamp, ada_state, abk_state, dpl_state, fmm_state, nas_state, wes_state), force_mavlink1=force_mavlink1)
-
- def logger_tm_encode(self, timestamp, log_number, too_large_samples, dropped_samples, queued_samples, buffers_filled, buffers_written, writes_failed, last_write_error, average_write_time, max_write_time):
- '''
- Logger status telemetry
-
- timestamp : Timestamp [us] (type:uint64_t)
- log_number : Currently active log file, -1 if the logger is inactive (type:int16_t)
- too_large_samples : Number of dropped samples because too large (type:int32_t)
- dropped_samples : Number of dropped samples due to fifo full (type:int32_t)
- queued_samples : Number of samples written to buffer (type:int32_t)
- buffers_filled : Number of buffers filled (type:int32_t)
- buffers_written : Number of buffers written to disk (type:int32_t)
- writes_failed : Number of fwrite() that failed (type:int32_t)
- last_write_error : Error of the last fwrite() that failed (type:int32_t)
- average_write_time : Average time to perform an fwrite() of a buffer (type:int32_t)
- max_write_time : Max time to perform an fwrite() of a buffer (type:int32_t)
-
- '''
- return MAVLink_logger_tm_message(timestamp, log_number, too_large_samples, dropped_samples, queued_samples, buffers_filled, buffers_written, writes_failed, last_write_error, average_write_time, max_write_time)
-
- def logger_tm_send(self, timestamp, log_number, too_large_samples, dropped_samples, queued_samples, buffers_filled, buffers_written, writes_failed, last_write_error, average_write_time, max_write_time, force_mavlink1=False):
- '''
- Logger status telemetry
-
- timestamp : Timestamp [us] (type:uint64_t)
- log_number : Currently active log file, -1 if the logger is inactive (type:int16_t)
- too_large_samples : Number of dropped samples because too large (type:int32_t)
- dropped_samples : Number of dropped samples due to fifo full (type:int32_t)
- queued_samples : Number of samples written to buffer (type:int32_t)
- buffers_filled : Number of buffers filled (type:int32_t)
- buffers_written : Number of buffers written to disk (type:int32_t)
- writes_failed : Number of fwrite() that failed (type:int32_t)
- last_write_error : Error of the last fwrite() that failed (type:int32_t)
- average_write_time : Average time to perform an fwrite() of a buffer (type:int32_t)
- max_write_time : Max time to perform an fwrite() of a buffer (type:int32_t)
-
- '''
- return self.send(self.logger_tm_encode(timestamp, log_number, too_large_samples, dropped_samples, queued_samples, buffers_filled, buffers_written, writes_failed, last_write_error, average_write_time, max_write_time), force_mavlink1=force_mavlink1)
-
- def mavlink_stats_tm_encode(self, timestamp, n_send_queue, max_send_queue, n_send_errors, msg_received, buffer_overrun, parse_error, parse_state, packet_idx, current_rx_seq, current_tx_seq, packet_rx_success_count, packet_rx_drop_count):
- '''
- Status of the TMTCManager telemetry
-
- timestamp : When was this logged [us] (type:uint64_t)
- n_send_queue : Current len of the occupied portion of the queue (type:uint16_t)
- max_send_queue : Max occupied len of the queue (type:uint16_t)
- n_send_errors : Number of packet not sent correctly by the TMTC (type:uint16_t)
- msg_received : Number of received messages (type:uint8_t)
- buffer_overrun : Number of buffer overruns (type:uint8_t)
- parse_error : Number of parse errors (type:uint8_t)
- parse_state : Parsing state machine (type:uint32_t)
- packet_idx : Index in current packet (type:uint8_t)
- current_rx_seq : Sequence number of last packet received (type:uint8_t)
- current_tx_seq : Sequence number of last packet sent (type:uint8_t)
- packet_rx_success_count : Received packets (type:uint16_t)
- packet_rx_drop_count : Number of packet drops (type:uint16_t)
-
- '''
- return MAVLink_mavlink_stats_tm_message(timestamp, n_send_queue, max_send_queue, n_send_errors, msg_received, buffer_overrun, parse_error, parse_state, packet_idx, current_rx_seq, current_tx_seq, packet_rx_success_count, packet_rx_drop_count)
-
- def mavlink_stats_tm_send(self, timestamp, n_send_queue, max_send_queue, n_send_errors, msg_received, buffer_overrun, parse_error, parse_state, packet_idx, current_rx_seq, current_tx_seq, packet_rx_success_count, packet_rx_drop_count, force_mavlink1=False):
- '''
- Status of the TMTCManager telemetry
-
- timestamp : When was this logged [us] (type:uint64_t)
- n_send_queue : Current len of the occupied portion of the queue (type:uint16_t)
- max_send_queue : Max occupied len of the queue (type:uint16_t)
- n_send_errors : Number of packet not sent correctly by the TMTC (type:uint16_t)
- msg_received : Number of received messages (type:uint8_t)
- buffer_overrun : Number of buffer overruns (type:uint8_t)
- parse_error : Number of parse errors (type:uint8_t)
- parse_state : Parsing state machine (type:uint32_t)
- packet_idx : Index in current packet (type:uint8_t)
- current_rx_seq : Sequence number of last packet received (type:uint8_t)
- current_tx_seq : Sequence number of last packet sent (type:uint8_t)
- packet_rx_success_count : Received packets (type:uint16_t)
- packet_rx_drop_count : Number of packet drops (type:uint16_t)
-
- '''
- return self.send(self.mavlink_stats_tm_encode(timestamp, n_send_queue, max_send_queue, n_send_errors, msg_received, buffer_overrun, parse_error, parse_state, packet_idx, current_rx_seq, current_tx_seq, packet_rx_success_count, packet_rx_drop_count), force_mavlink1=force_mavlink1)
-
- def task_stats_tm_encode(self, timestamp, task_id, task_period, task_min, task_max, task_mean, task_stddev):
- '''
- Statistics of the Task Scheduler
-
- timestamp : When was this logged [us] (type:uint64_t)
- task_id : Task ID (type:uint8_t)
- task_period : Period of the task [ms] (type:uint16_t)
- task_min : Task min period (type:float)
- task_max : Task max period (type:float)
- task_mean : Task mean period (type:float)
- task_stddev : Task period std deviation (type:float)
-
- '''
- return MAVLink_task_stats_tm_message(timestamp, task_id, task_period, task_min, task_max, task_mean, task_stddev)
-
- def task_stats_tm_send(self, timestamp, task_id, task_period, task_min, task_max, task_mean, task_stddev, force_mavlink1=False):
- '''
- Statistics of the Task Scheduler
-
- timestamp : When was this logged [us] (type:uint64_t)
- task_id : Task ID (type:uint8_t)
- task_period : Period of the task [ms] (type:uint16_t)
- task_min : Task min period (type:float)
- task_max : Task max period (type:float)
- task_mean : Task mean period (type:float)
- task_stddev : Task period std deviation (type:float)
-
- '''
- return self.send(self.task_stats_tm_encode(timestamp, task_id, task_period, task_min, task_max, task_mean, task_stddev), force_mavlink1=force_mavlink1)
-
- def ada_tm_encode(self, timestamp, state, kalman_x0, kalman_x1, kalman_x2, vertical_speed, msl_altitude, ref_pressure, ref_altitude, ref_temperature, msl_pressure, msl_temperature, dpl_altitude):
- '''
- Apogee Detection Algorithm status telemetry
-
- timestamp : When was this logged [us] (type:uint64_t)
- state : ADA current state (type:uint8_t)
- kalman_x0 : Kalman state variable 0 (pressure) (type:float)
- kalman_x1 : Kalman state variable 1 (pressure velocity) (type:float)
- kalman_x2 : Kalman state variable 2 (pressure acceleration) (type:float)
- vertical_speed : Vertical speed computed by the ADA [m/s] (type:float)
- msl_altitude : Altitude w.r.t. mean sea level [m] (type:float)
- ref_pressure : Calibration pressure [Pa] (type:float)
- ref_altitude : Calibration altitude [m] (type:float)
- ref_temperature : Calibration temperature [degC] (type:float)
- msl_pressure : Expected pressure at mean sea level [Pa] (type:float)
- msl_temperature : Expected temperature at mean sea level [degC] (type:float)
- dpl_altitude : Main parachute deployment altituyde [m] (type:float)
-
- '''
- return MAVLink_ada_tm_message(timestamp, state, kalman_x0, kalman_x1, kalman_x2, vertical_speed, msl_altitude, ref_pressure, ref_altitude, ref_temperature, msl_pressure, msl_temperature, dpl_altitude)
-
- def ada_tm_send(self, timestamp, state, kalman_x0, kalman_x1, kalman_x2, vertical_speed, msl_altitude, ref_pressure, ref_altitude, ref_temperature, msl_pressure, msl_temperature, dpl_altitude, force_mavlink1=False):
- '''
- Apogee Detection Algorithm status telemetry
-
- timestamp : When was this logged [us] (type:uint64_t)
- state : ADA current state (type:uint8_t)
- kalman_x0 : Kalman state variable 0 (pressure) (type:float)
- kalman_x1 : Kalman state variable 1 (pressure velocity) (type:float)
- kalman_x2 : Kalman state variable 2 (pressure acceleration) (type:float)
- vertical_speed : Vertical speed computed by the ADA [m/s] (type:float)
- msl_altitude : Altitude w.r.t. mean sea level [m] (type:float)
- ref_pressure : Calibration pressure [Pa] (type:float)
- ref_altitude : Calibration altitude [m] (type:float)
- ref_temperature : Calibration temperature [degC] (type:float)
- msl_pressure : Expected pressure at mean sea level [Pa] (type:float)
- msl_temperature : Expected temperature at mean sea level [degC] (type:float)
- dpl_altitude : Main parachute deployment altituyde [m] (type:float)
-
- '''
- return self.send(self.ada_tm_encode(timestamp, state, kalman_x0, kalman_x1, kalman_x2, vertical_speed, msl_altitude, ref_pressure, ref_altitude, ref_temperature, msl_pressure, msl_temperature, dpl_altitude), force_mavlink1=force_mavlink1)
-
- def nas_tm_encode(self, timestamp, state, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, ref_pressure, ref_temperature, ref_latitude, ref_longitude):
- '''
- Navigation System status telemetry
-
- timestamp : When was this logged [us] (type:uint64_t)
- state : NAS current state (type:uint8_t)
- nas_n : Navigation system estimated noth position [deg] (type:float)
- nas_e : Navigation system estimated east position [deg] (type:float)
- nas_d : Navigation system estimated down position [m] (type:float)
- nas_vn : Navigation system estimated north velocity [m/s] (type:float)
- nas_ve : Navigation system estimated east velocity [m/s] (type:float)
- nas_vd : Navigation system estimated down velocity [m/s] (type:float)
- nas_qx : Navigation system estimated attitude (qx) [deg] (type:float)
- nas_qy : Navigation system estimated attitude (qy) [deg] (type:float)
- nas_qz : Navigation system estimated attitude (qz) [deg] (type:float)
- nas_qw : Navigation system estimated attitude (qw) [deg] (type:float)
- nas_bias_x : Navigation system gyroscope bias on x axis (type:float)
- nas_bias_y : Navigation system gyroscope bias on y axis (type:float)
- nas_bias_z : Navigation system gyroscope bias on z axis (type:float)
- ref_pressure : Calibration pressure [Pa] (type:float)
- ref_temperature : Calibration temperature [degC] (type:float)
- ref_latitude : Calibration latitude [deg] (type:float)
- ref_longitude : Calibration longitude [deg] (type:float)
-
- '''
- return MAVLink_nas_tm_message(timestamp, state, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, ref_pressure, ref_temperature, ref_latitude, ref_longitude)
-
- def nas_tm_send(self, timestamp, state, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, ref_pressure, ref_temperature, ref_latitude, ref_longitude, force_mavlink1=False):
- '''
- Navigation System status telemetry
-
- timestamp : When was this logged [us] (type:uint64_t)
- state : NAS current state (type:uint8_t)
- nas_n : Navigation system estimated noth position [deg] (type:float)
- nas_e : Navigation system estimated east position [deg] (type:float)
- nas_d : Navigation system estimated down position [m] (type:float)
- nas_vn : Navigation system estimated north velocity [m/s] (type:float)
- nas_ve : Navigation system estimated east velocity [m/s] (type:float)
- nas_vd : Navigation system estimated down velocity [m/s] (type:float)
- nas_qx : Navigation system estimated attitude (qx) [deg] (type:float)
- nas_qy : Navigation system estimated attitude (qy) [deg] (type:float)
- nas_qz : Navigation system estimated attitude (qz) [deg] (type:float)
- nas_qw : Navigation system estimated attitude (qw) [deg] (type:float)
- nas_bias_x : Navigation system gyroscope bias on x axis (type:float)
- nas_bias_y : Navigation system gyroscope bias on y axis (type:float)
- nas_bias_z : Navigation system gyroscope bias on z axis (type:float)
- ref_pressure : Calibration pressure [Pa] (type:float)
- ref_temperature : Calibration temperature [degC] (type:float)
- ref_latitude : Calibration latitude [deg] (type:float)
- ref_longitude : Calibration longitude [deg] (type:float)
-
- '''
- return self.send(self.nas_tm_encode(timestamp, state, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, ref_pressure, ref_temperature, ref_latitude, ref_longitude), force_mavlink1=force_mavlink1)
-
- def mea_tm_encode(self, timestamp, state, kalman_x0, kalman_x1, kalman_x2, mass, corrected_pressure):
- '''
- Mass Estimation Algorithm status telemetry
-
- timestamp : When was this logged [us] (type:uint64_t)
- state : MEA current state (type:uint8_t)
- kalman_x0 : Kalman state variable 0 (corrected pressure) (type:float)
- kalman_x1 : Kalman state variable 1 (type:float)
- kalman_x2 : Kalman state variable 2 (mass) (type:float)
- mass : Mass estimated [kg] (type:float)
- corrected_pressure : Corrected pressure [kg] (type:float)
-
- '''
- return MAVLink_mea_tm_message(timestamp, state, kalman_x0, kalman_x1, kalman_x2, mass, corrected_pressure)
-
- def mea_tm_send(self, timestamp, state, kalman_x0, kalman_x1, kalman_x2, mass, corrected_pressure, force_mavlink1=False):
- '''
- Mass Estimation Algorithm status telemetry
-
- timestamp : When was this logged [us] (type:uint64_t)
- state : MEA current state (type:uint8_t)
- kalman_x0 : Kalman state variable 0 (corrected pressure) (type:float)
- kalman_x1 : Kalman state variable 1 (type:float)
- kalman_x2 : Kalman state variable 2 (mass) (type:float)
- mass : Mass estimated [kg] (type:float)
- corrected_pressure : Corrected pressure [kg] (type:float)
-
- '''
- return self.send(self.mea_tm_encode(timestamp, state, kalman_x0, kalman_x1, kalman_x2, mass, corrected_pressure), force_mavlink1=force_mavlink1)
-
- def rocket_flight_tm_encode(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_quick_connector, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, current_consumption, temperature, logger_error):
- '''
- High Rate Telemetry
-
- timestamp : Timestamp in microseconds [us] (type:uint64_t)
- ada_state : ADA Controller State (type:uint8_t)
- fmm_state : Flight Mode Manager State (type:uint8_t)
- dpl_state : Deployment Controller State (type:uint8_t)
- abk_state : Airbrake FSM state (type:uint8_t)
- nas_state : Navigation System FSM State (type:uint8_t)
- mea_state : MEA Controller State (type:uint8_t)
- pressure_ada : Atmospheric pressure estimated by ADA [Pa] (type:float)
- pressure_digi : Pressure from digital sensor [Pa] (type:float)
- pressure_static : Pressure from static port [Pa] (type:float)
- pressure_dpl : Pressure from deployment vane sensor [Pa] (type:float)
- airspeed_pitot : Pitot airspeed [m/s] (type:float)
- altitude_agl : Altitude above ground level [m] (type:float)
- ada_vert_speed : Vertical speed estimated by ADA [m/s] (type:float)
- mea_mass : Mass estimated by MEA [kg] (type:float)
- acc_x : Acceleration on X axis (body) [m/s^2] (type:float)
- acc_y : Acceleration on Y axis (body) [m/s^2] (type:float)
- acc_z : Acceleration on Z axis (body) [m/s^2] (type:float)
- gyro_x : Angular speed on X axis (body) [rad/s] (type:float)
- gyro_y : Angular speed on Y axis (body) [rad/s] (type:float)
- gyro_z : Angular speed on Z axis (body) [rad/s] (type:float)
- mag_x : Magnetic field on X axis (body) [uT] (type:float)
- mag_y : Magnetic field on Y axis (body) [uT] (type:float)
- mag_z : Magnetic field on Z axis (body) [uT] (type:float)
- gps_fix : GPS fix (1 = fix, 0 = no fix) (type:uint8_t)
- gps_lat : Latitude [deg] (type:float)
- gps_lon : Longitude [deg] (type:float)
- gps_alt : GPS Altitude [m] (type:float)
- abk_angle : Air Brakes angle [deg] (type:float)
- nas_n : Navigation system estimated noth position [deg] (type:float)
- nas_e : Navigation system estimated east position [deg] (type:float)
- nas_d : Navigation system estimated down position [m] (type:float)
- nas_vn : Navigation system estimated north velocity [m/s] (type:float)
- nas_ve : Navigation system estimated east velocity [m/s] (type:float)
- nas_vd : Navigation system estimated down velocity [m/s] (type:float)
- nas_qx : Navigation system estimated attitude (qx) [deg] (type:float)
- nas_qy : Navigation system estimated attitude (qy) [deg] (type:float)
- nas_qz : Navigation system estimated attitude (qz) [deg] (type:float)
- nas_qw : Navigation system estimated attitude (qw) [deg] (type:float)
- nas_bias_x : Navigation system gyroscope bias on x axis (type:float)
- nas_bias_y : Navigation system gyroscope bias on y axis (type:float)
- nas_bias_z : Navigation system gyroscope bias on z axis (type:float)
- pin_quick_connector : Quick connector detach pin (type:float)
- pin_launch : Launch pin status (1 = connected, 0 = disconnected) (type:uint8_t)
- pin_nosecone : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t)
- pin_expulsion : Servo sensor status (1 = actuated, 0 = idle) (type:uint8_t)
- cutter_presence : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
- battery_voltage : Battery voltage [V] (type:float)
- cam_battery_voltage : Camera battery voltage [V] (type:float)
- current_consumption : Battery current [A] (type:float)
- temperature : Temperature [degC] (type:float)
- logger_error : Logger error (0 = no error, -1 otherwise) (type:int8_t)
-
- '''
- return MAVLink_rocket_flight_tm_message(timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_quick_connector, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, current_consumption, temperature, logger_error)
-
- def rocket_flight_tm_send(self, timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_quick_connector, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, current_consumption, temperature, logger_error, force_mavlink1=False):
- '''
- High Rate Telemetry
-
- timestamp : Timestamp in microseconds [us] (type:uint64_t)
- ada_state : ADA Controller State (type:uint8_t)
- fmm_state : Flight Mode Manager State (type:uint8_t)
- dpl_state : Deployment Controller State (type:uint8_t)
- abk_state : Airbrake FSM state (type:uint8_t)
- nas_state : Navigation System FSM State (type:uint8_t)
- mea_state : MEA Controller State (type:uint8_t)
- pressure_ada : Atmospheric pressure estimated by ADA [Pa] (type:float)
- pressure_digi : Pressure from digital sensor [Pa] (type:float)
- pressure_static : Pressure from static port [Pa] (type:float)
- pressure_dpl : Pressure from deployment vane sensor [Pa] (type:float)
- airspeed_pitot : Pitot airspeed [m/s] (type:float)
- altitude_agl : Altitude above ground level [m] (type:float)
- ada_vert_speed : Vertical speed estimated by ADA [m/s] (type:float)
- mea_mass : Mass estimated by MEA [kg] (type:float)
- acc_x : Acceleration on X axis (body) [m/s^2] (type:float)
- acc_y : Acceleration on Y axis (body) [m/s^2] (type:float)
- acc_z : Acceleration on Z axis (body) [m/s^2] (type:float)
- gyro_x : Angular speed on X axis (body) [rad/s] (type:float)
- gyro_y : Angular speed on Y axis (body) [rad/s] (type:float)
- gyro_z : Angular speed on Z axis (body) [rad/s] (type:float)
- mag_x : Magnetic field on X axis (body) [uT] (type:float)
- mag_y : Magnetic field on Y axis (body) [uT] (type:float)
- mag_z : Magnetic field on Z axis (body) [uT] (type:float)
- gps_fix : GPS fix (1 = fix, 0 = no fix) (type:uint8_t)
- gps_lat : Latitude [deg] (type:float)
- gps_lon : Longitude [deg] (type:float)
- gps_alt : GPS Altitude [m] (type:float)
- abk_angle : Air Brakes angle [deg] (type:float)
- nas_n : Navigation system estimated noth position [deg] (type:float)
- nas_e : Navigation system estimated east position [deg] (type:float)
- nas_d : Navigation system estimated down position [m] (type:float)
- nas_vn : Navigation system estimated north velocity [m/s] (type:float)
- nas_ve : Navigation system estimated east velocity [m/s] (type:float)
- nas_vd : Navigation system estimated down velocity [m/s] (type:float)
- nas_qx : Navigation system estimated attitude (qx) [deg] (type:float)
- nas_qy : Navigation system estimated attitude (qy) [deg] (type:float)
- nas_qz : Navigation system estimated attitude (qz) [deg] (type:float)
- nas_qw : Navigation system estimated attitude (qw) [deg] (type:float)
- nas_bias_x : Navigation system gyroscope bias on x axis (type:float)
- nas_bias_y : Navigation system gyroscope bias on y axis (type:float)
- nas_bias_z : Navigation system gyroscope bias on z axis (type:float)
- pin_quick_connector : Quick connector detach pin (type:float)
- pin_launch : Launch pin status (1 = connected, 0 = disconnected) (type:uint8_t)
- pin_nosecone : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t)
- pin_expulsion : Servo sensor status (1 = actuated, 0 = idle) (type:uint8_t)
- cutter_presence : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
- battery_voltage : Battery voltage [V] (type:float)
- cam_battery_voltage : Camera battery voltage [V] (type:float)
- current_consumption : Battery current [A] (type:float)
- temperature : Temperature [degC] (type:float)
- logger_error : Logger error (0 = no error, -1 otherwise) (type:int8_t)
-
- '''
- return self.send(self.rocket_flight_tm_encode(timestamp, ada_state, fmm_state, dpl_state, abk_state, nas_state, mea_state, pressure_ada, pressure_digi, pressure_static, pressure_dpl, airspeed_pitot, altitude_agl, ada_vert_speed, mea_mass, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, abk_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, pin_quick_connector, pin_launch, pin_nosecone, pin_expulsion, cutter_presence, battery_voltage, cam_battery_voltage, current_consumption, temperature, logger_error), force_mavlink1=force_mavlink1)
-
- def payload_flight_tm_encode(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, current_consumption, cutter_presence, temperature, logger_error):
- '''
- High Rate Telemetry
-
- timestamp : Timestamp in microseconds [us] (type:uint64_t)
- fmm_state : Flight Mode Manager State (type:uint8_t)
- nas_state : Navigation System FSM State (type:uint8_t)
- wes_state : Wind Estimation System FSM State (type:uint8_t)
- pressure_digi : Pressure from digital sensor [Pa] (type:float)
- pressure_static : Pressure from static port [Pa] (type:float)
- airspeed_pitot : Pitot airspeed [m/s] (type:float)
- altitude_agl : Altitude above ground level [m] (type:float)
- acc_x : Acceleration on X axis (body) [m/s^2] (type:float)
- acc_y : Acceleration on Y axis (body) [m/s^2] (type:float)
- acc_z : Acceleration on Z axis (body) [m/s^2] (type:float)
- gyro_x : Angular speed on X axis (body) [rad/s] (type:float)
- gyro_y : Angular speed on Y axis (body) [rad/s] (type:float)
- gyro_z : Angular speed on Z axis (body) [rad/s] (type:float)
- mag_x : Magnetic field on X axis (body) [uT] (type:float)
- mag_y : Magnetic field on Y axis (body) [uT] (type:float)
- mag_z : Magnetic field on Z axis (body) [uT] (type:float)
- gps_fix : GPS fix (1 = fix, 0 = no fix) (type:uint8_t)
- gps_lat : Latitude [deg] (type:float)
- gps_lon : Longitude [deg] (type:float)
- gps_alt : GPS Altitude [m] (type:float)
- left_servo_angle : Left servo motor angle [deg] (type:float)
- right_servo_angle : Right servo motor angle [deg] (type:float)
- nas_n : Navigation system estimated noth position [deg] (type:float)
- nas_e : Navigation system estimated east position [deg] (type:float)
- nas_d : Navigation system estimated down position [m] (type:float)
- nas_vn : Navigation system estimated north velocity [m/s] (type:float)
- nas_ve : Navigation system estimated east velocity [m/s] (type:float)
- nas_vd : Navigation system estimated down velocity [m/s] (type:float)
- nas_qx : Navigation system estimated attitude (qx) [deg] (type:float)
- nas_qy : Navigation system estimated attitude (qy) [deg] (type:float)
- nas_qz : Navigation system estimated attitude (qz) [deg] (type:float)
- nas_qw : Navigation system estimated attitude (qw) [deg] (type:float)
- nas_bias_x : Navigation system gyroscope bias on x axis (type:float)
- nas_bias_y : Navigation system gyroscope bias on y axis (type:float)
- nas_bias_z : Navigation system gyroscope bias on z axis (type:float)
- wes_n : Wind estimated north velocity [m/s] (type:float)
- wes_e : Wind estimated east velocity [m/s] (type:float)
- pin_nosecone : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t)
- battery_voltage : Battery voltage [V] (type:float)
- cam_battery_voltage : Camera battery voltage [V] (type:float)
- current_consumption : Battery current [A] (type:float)
- cutter_presence : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
- temperature : Temperature [degC] (type:float)
- logger_error : Logger error (0 = no error) (type:int8_t)
-
- '''
- return MAVLink_payload_flight_tm_message(timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, current_consumption, cutter_presence, temperature, logger_error)
-
- def payload_flight_tm_send(self, timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, current_consumption, cutter_presence, temperature, logger_error, force_mavlink1=False):
- '''
- High Rate Telemetry
-
- timestamp : Timestamp in microseconds [us] (type:uint64_t)
- fmm_state : Flight Mode Manager State (type:uint8_t)
- nas_state : Navigation System FSM State (type:uint8_t)
- wes_state : Wind Estimation System FSM State (type:uint8_t)
- pressure_digi : Pressure from digital sensor [Pa] (type:float)
- pressure_static : Pressure from static port [Pa] (type:float)
- airspeed_pitot : Pitot airspeed [m/s] (type:float)
- altitude_agl : Altitude above ground level [m] (type:float)
- acc_x : Acceleration on X axis (body) [m/s^2] (type:float)
- acc_y : Acceleration on Y axis (body) [m/s^2] (type:float)
- acc_z : Acceleration on Z axis (body) [m/s^2] (type:float)
- gyro_x : Angular speed on X axis (body) [rad/s] (type:float)
- gyro_y : Angular speed on Y axis (body) [rad/s] (type:float)
- gyro_z : Angular speed on Z axis (body) [rad/s] (type:float)
- mag_x : Magnetic field on X axis (body) [uT] (type:float)
- mag_y : Magnetic field on Y axis (body) [uT] (type:float)
- mag_z : Magnetic field on Z axis (body) [uT] (type:float)
- gps_fix : GPS fix (1 = fix, 0 = no fix) (type:uint8_t)
- gps_lat : Latitude [deg] (type:float)
- gps_lon : Longitude [deg] (type:float)
- gps_alt : GPS Altitude [m] (type:float)
- left_servo_angle : Left servo motor angle [deg] (type:float)
- right_servo_angle : Right servo motor angle [deg] (type:float)
- nas_n : Navigation system estimated noth position [deg] (type:float)
- nas_e : Navigation system estimated east position [deg] (type:float)
- nas_d : Navigation system estimated down position [m] (type:float)
- nas_vn : Navigation system estimated north velocity [m/s] (type:float)
- nas_ve : Navigation system estimated east velocity [m/s] (type:float)
- nas_vd : Navigation system estimated down velocity [m/s] (type:float)
- nas_qx : Navigation system estimated attitude (qx) [deg] (type:float)
- nas_qy : Navigation system estimated attitude (qy) [deg] (type:float)
- nas_qz : Navigation system estimated attitude (qz) [deg] (type:float)
- nas_qw : Navigation system estimated attitude (qw) [deg] (type:float)
- nas_bias_x : Navigation system gyroscope bias on x axis (type:float)
- nas_bias_y : Navigation system gyroscope bias on y axis (type:float)
- nas_bias_z : Navigation system gyroscope bias on z axis (type:float)
- wes_n : Wind estimated north velocity [m/s] (type:float)
- wes_e : Wind estimated east velocity [m/s] (type:float)
- pin_nosecone : Nosecone pin status (1 = connected, 0 = disconnected) (type:uint8_t)
- battery_voltage : Battery voltage [V] (type:float)
- cam_battery_voltage : Camera battery voltage [V] (type:float)
- current_consumption : Battery current [A] (type:float)
- cutter_presence : Cutter presence status (1 = present, 0 = missing) (type:uint8_t)
- temperature : Temperature [degC] (type:float)
- logger_error : Logger error (0 = no error) (type:int8_t)
-
- '''
- return self.send(self.payload_flight_tm_encode(timestamp, fmm_state, nas_state, wes_state, pressure_digi, pressure_static, airspeed_pitot, altitude_agl, acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, mag_x, mag_y, mag_z, gps_fix, gps_lat, gps_lon, gps_alt, left_servo_angle, right_servo_angle, nas_n, nas_e, nas_d, nas_vn, nas_ve, nas_vd, nas_qx, nas_qy, nas_qz, nas_qw, nas_bias_x, nas_bias_y, nas_bias_z, wes_n, wes_e, pin_nosecone, battery_voltage, cam_battery_voltage, current_consumption, cutter_presence, temperature, logger_error), force_mavlink1=force_mavlink1)
-
- def rocket_stats_tm_encode(self, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, ada_min_pressure, dpl_vane_max_pressure, cpu_load, free_heap):
- '''
- Low Rate Telemetry
-
- liftoff_ts : System clock at liftoff [us] (type:uint64_t)
- liftoff_max_acc_ts : System clock at the maximum liftoff acceleration [us] (type:uint64_t)
- liftoff_max_acc : Maximum liftoff acceleration [m/s2] (type:float)
- dpl_ts : System clock at drouge deployment [us] (type:uint64_t)
- dpl_max_acc : Max acceleration during drouge deployment [m/s2] (type:float)
- max_z_speed_ts : System clock at ADA max vertical speed [us] (type:uint64_t)
- max_z_speed : Max measured vertical speed - ADA [m/s] (type:float)
- max_airspeed_pitot : Max speed read by the pitot tube [m/s] (type:float)
- max_speed_altitude : Altitude at max speed [m] (type:float)
- apogee_ts : System clock at apogee [us] (type:uint64_t)
- apogee_lat : Apogee latitude [deg] (type:float)
- apogee_lon : Apogee longitude [deg] (type:float)
- apogee_alt : Apogee altitude [m] (type:float)
- min_pressure : Apogee pressure - Digital barometer [Pa] (type:float)
- ada_min_pressure : Apogee pressure - ADA filtered [Pa] (type:float)
- dpl_vane_max_pressure : Max pressure in the deployment bay during drogue deployment [Pa] (type:float)
- cpu_load : CPU load in percentage (type:float)
- free_heap : Amount of available heap in memory (type:uint32_t)
-
- '''
- return MAVLink_rocket_stats_tm_message(liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, ada_min_pressure, dpl_vane_max_pressure, cpu_load, free_heap)
-
- def rocket_stats_tm_send(self, liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, ada_min_pressure, dpl_vane_max_pressure, cpu_load, free_heap, force_mavlink1=False):
- '''
- Low Rate Telemetry
-
- liftoff_ts : System clock at liftoff [us] (type:uint64_t)
- liftoff_max_acc_ts : System clock at the maximum liftoff acceleration [us] (type:uint64_t)
- liftoff_max_acc : Maximum liftoff acceleration [m/s2] (type:float)
- dpl_ts : System clock at drouge deployment [us] (type:uint64_t)
- dpl_max_acc : Max acceleration during drouge deployment [m/s2] (type:float)
- max_z_speed_ts : System clock at ADA max vertical speed [us] (type:uint64_t)
- max_z_speed : Max measured vertical speed - ADA [m/s] (type:float)
- max_airspeed_pitot : Max speed read by the pitot tube [m/s] (type:float)
- max_speed_altitude : Altitude at max speed [m] (type:float)
- apogee_ts : System clock at apogee [us] (type:uint64_t)
- apogee_lat : Apogee latitude [deg] (type:float)
- apogee_lon : Apogee longitude [deg] (type:float)
- apogee_alt : Apogee altitude [m] (type:float)
- min_pressure : Apogee pressure - Digital barometer [Pa] (type:float)
- ada_min_pressure : Apogee pressure - ADA filtered [Pa] (type:float)
- dpl_vane_max_pressure : Max pressure in the deployment bay during drogue deployment [Pa] (type:float)
- cpu_load : CPU load in percentage (type:float)
- free_heap : Amount of available heap in memory (type:uint32_t)
-
- '''
- return self.send(self.rocket_stats_tm_encode(liftoff_ts, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, ada_min_pressure, dpl_vane_max_pressure, cpu_load, free_heap), force_mavlink1=force_mavlink1)
-
- def payload_stats_tm_encode(self, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap):
- '''
- Low Rate Telemetry
-
- liftoff_max_acc_ts : System clock at the maximum liftoff acceleration [us] (type:uint64_t)
- liftoff_max_acc : Maximum liftoff acceleration [m/s2] (type:float)
- dpl_ts : System clock at drouge deployment [us] (type:uint64_t)
- dpl_max_acc : Max acceleration during drouge deployment [m/s2] (type:float)
- max_z_speed_ts : System clock at max vertical speed [us] (type:uint64_t)
- max_z_speed : Max measured vertical speed [m/s] (type:float)
- max_airspeed_pitot : Max speed read by the pitot tube [m/s] (type:float)
- max_speed_altitude : Altitude at max speed [m] (type:float)
- apogee_ts : System clock at apogee [us] (type:uint64_t)
- apogee_lat : Apogee latitude [deg] (type:float)
- apogee_lon : Apogee longitude [deg] (type:float)
- apogee_alt : Apogee altitude [m] (type:float)
- min_pressure : Apogee pressure - Digital barometer [Pa] (type:float)
- cpu_load : CPU load in percentage (type:float)
- free_heap : Amount of available heap in memory (type:uint32_t)
-
- '''
- return MAVLink_payload_stats_tm_message(liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap)
-
- def payload_stats_tm_send(self, liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap, force_mavlink1=False):
- '''
- Low Rate Telemetry
-
- liftoff_max_acc_ts : System clock at the maximum liftoff acceleration [us] (type:uint64_t)
- liftoff_max_acc : Maximum liftoff acceleration [m/s2] (type:float)
- dpl_ts : System clock at drouge deployment [us] (type:uint64_t)
- dpl_max_acc : Max acceleration during drouge deployment [m/s2] (type:float)
- max_z_speed_ts : System clock at max vertical speed [us] (type:uint64_t)
- max_z_speed : Max measured vertical speed [m/s] (type:float)
- max_airspeed_pitot : Max speed read by the pitot tube [m/s] (type:float)
- max_speed_altitude : Altitude at max speed [m] (type:float)
- apogee_ts : System clock at apogee [us] (type:uint64_t)
- apogee_lat : Apogee latitude [deg] (type:float)
- apogee_lon : Apogee longitude [deg] (type:float)
- apogee_alt : Apogee altitude [m] (type:float)
- min_pressure : Apogee pressure - Digital barometer [Pa] (type:float)
- cpu_load : CPU load in percentage (type:float)
- free_heap : Amount of available heap in memory (type:uint32_t)
-
- '''
- return self.send(self.payload_stats_tm_encode(liftoff_max_acc_ts, liftoff_max_acc, dpl_ts, dpl_max_acc, max_z_speed_ts, max_z_speed, max_airspeed_pitot, max_speed_altitude, apogee_ts, apogee_lat, apogee_lon, apogee_alt, min_pressure, cpu_load, free_heap), force_mavlink1=force_mavlink1)
-
- def gse_tm_encode(self, timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, ignition_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status):
- '''
- Ground Segment Equipment telemetry
-
- timestamp : Timestamp in microseconds [us] (type:uint64_t)
- loadcell_rocket : Rocket weight [kg] (type:float)
- loadcell_vessel : External tank weight [kg] (type:float)
- filling_pressure : Refueling line pressure [Bar] (type:float)
- vessel_pressure : Vessel tank pressure [Bar] (type:float)
- arming_state : 1 If the rocket is armed (type:uint8_t)
- filling_valve_state : 1 If the filling valve is open (type:uint8_t)
- venting_valve_state : 1 If the venting valve is open (type:uint8_t)
- release_valve_state : 1 If the release valve is open (type:uint8_t)
- main_valve_state : 1 If the main valve is open (type:uint8_t)
- ignition_state : 1 If the RIG is in ignition process (type:uint8_t)
- tars_state : 1 If the TARS algorithm is running (type:uint8_t)
- battery_voltage : Battery voltage (type:float)
- current_consumption : RIG current (type:float)
- main_board_status : MAIN board status [0: not present, 1: online, 2: armed] (type:uint8_t)
- payload_board_status : PAYLOAD board status [0: not present, 1: online, 2: armed] (type:uint8_t)
- motor_board_status : MOTOR board status [0: not present, 1: online, 2: armed] (type:uint8_t)
-
- '''
- return MAVLink_gse_tm_message(timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, ignition_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status)
-
- def gse_tm_send(self, timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, ignition_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status, force_mavlink1=False):
- '''
- Ground Segment Equipment telemetry
-
- timestamp : Timestamp in microseconds [us] (type:uint64_t)
- loadcell_rocket : Rocket weight [kg] (type:float)
- loadcell_vessel : External tank weight [kg] (type:float)
- filling_pressure : Refueling line pressure [Bar] (type:float)
- vessel_pressure : Vessel tank pressure [Bar] (type:float)
- arming_state : 1 If the rocket is armed (type:uint8_t)
- filling_valve_state : 1 If the filling valve is open (type:uint8_t)
- venting_valve_state : 1 If the venting valve is open (type:uint8_t)
- release_valve_state : 1 If the release valve is open (type:uint8_t)
- main_valve_state : 1 If the main valve is open (type:uint8_t)
- ignition_state : 1 If the RIG is in ignition process (type:uint8_t)
- tars_state : 1 If the TARS algorithm is running (type:uint8_t)
- battery_voltage : Battery voltage (type:float)
- current_consumption : RIG current (type:float)
- main_board_status : MAIN board status [0: not present, 1: online, 2: armed] (type:uint8_t)
- payload_board_status : PAYLOAD board status [0: not present, 1: online, 2: armed] (type:uint8_t)
- motor_board_status : MOTOR board status [0: not present, 1: online, 2: armed] (type:uint8_t)
-
- '''
- return self.send(self.gse_tm_encode(timestamp, loadcell_rocket, loadcell_vessel, filling_pressure, vessel_pressure, arming_state, filling_valve_state, venting_valve_state, release_valve_state, main_valve_state, ignition_state, tars_state, battery_voltage, current_consumption, main_board_status, payload_board_status, motor_board_status), force_mavlink1=force_mavlink1)
-
- def motor_tm_encode(self, timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, floating_level, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, current_consumption):
- '''
- Motor rocket telemetry
-
- timestamp : Timestamp in microseconds [us] (type:uint64_t)
- top_tank_pressure : Tank upper pressure [Bar] (type:float)
- bottom_tank_pressure : Tank bottom pressure [Bar] (type:float)
- combustion_chamber_pressure : Pressure inside the combustion chamber used for automatic shutdown [Bar] (type:float)
- floating_level : Floating level in tank (type:uint8_t)
- tank_temperature : Tank temperature (type:float)
- main_valve_state : 1 If the main valve is open (type:uint8_t)
- venting_valve_state : 1 If the venting valve is open (type:uint8_t)
- battery_voltage : Battery voltage [V] (type:float)
- current_consumption : Current drained from the battery [A] (type:float)
-
- '''
- return MAVLink_motor_tm_message(timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, floating_level, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, current_consumption)
-
- def motor_tm_send(self, timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, floating_level, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, current_consumption, force_mavlink1=False):
- '''
- Motor rocket telemetry
-
- timestamp : Timestamp in microseconds [us] (type:uint64_t)
- top_tank_pressure : Tank upper pressure [Bar] (type:float)
- bottom_tank_pressure : Tank bottom pressure [Bar] (type:float)
- combustion_chamber_pressure : Pressure inside the combustion chamber used for automatic shutdown [Bar] (type:float)
- floating_level : Floating level in tank (type:uint8_t)
- tank_temperature : Tank temperature (type:float)
- main_valve_state : 1 If the main valve is open (type:uint8_t)
- venting_valve_state : 1 If the venting valve is open (type:uint8_t)
- battery_voltage : Battery voltage [V] (type:float)
- current_consumption : Current drained from the battery [A] (type:float)
-
- '''
- return self.send(self.motor_tm_encode(timestamp, top_tank_pressure, bottom_tank_pressure, combustion_chamber_pressure, floating_level, tank_temperature, main_valve_state, venting_valve_state, battery_voltage, current_consumption), force_mavlink1=force_mavlink1)
-
diff --git a/mavlink_lib/checksum.h b/mavlink_lib/checksum.h
deleted file mode 100644
index fcd5e1d55b3df83d5121551bb50a77dae1164b00..0000000000000000000000000000000000000000
--- a/mavlink_lib/checksum.h
+++ /dev/null
@@ -1,96 +0,0 @@
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#ifndef _CHECKSUM_H_
-#define _CHECKSUM_H_
-
-// 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 <stdint.h>
-
-/**
- *
- * CALCULATE THE CHECKSUM
- *
- */
-
-#define X25_INIT_CRC 0xffff
-#define X25_VALIDATE_CRC 0xf0b8
-
-#ifndef HAVE_CRC_ACCUMULATE
-/**
- * @brief Accumulate the MCRF4XX CRC16 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 MCRF4XX CRC16 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 CRC 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);
- }
-}
-
-#endif /* _CHECKSUM_H_ */
-
-#ifdef __cplusplus
-}
-#endif
diff --git a/mavlink_lib/gemini/gemini.h b/mavlink_lib/gemini/gemini.h
deleted file mode 100644
index d25bbe162a0927b4273638913af516de0ebce1a7..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/gemini.h
+++ /dev/null
@@ -1,246 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol generated from gemini.xml
- * @see http://mavlink.org
- */
-#pragma once
-#ifndef MAVLINK_GEMINI_H
-#define MAVLINK_GEMINI_H
-
-#ifndef MAVLINK_H
- #error Wrong include order: MAVLINK_GEMINI.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
-
-#undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH 1902963619411886953
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-// MESSAGE LENGTHS AND CRCS
-
-#ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 8, 2, 4, 8, 1, 5, 5, 7, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 74, 64, 32, 60, 32, 32, 32, 32, 56, 21, 5, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 52, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 14, 14, 46, 28, 27, 53, 77, 29, 176, 163, 92, 76, 42, 35, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
-#endif
-
-#ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 160, 226, 113, 38, 71, 67, 218, 44, 81, 181, 110, 22, 65, 79, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 146, 57, 72, 87, 229, 245, 212, 140, 148, 6, 155, 87, 255, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 117, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 242, 142, 108, 133, 234, 66, 11, 214, 84, 245, 115, 63, 79, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
-#endif
-
-#include "../protocol.h"
-
-#define MAVLINK_ENABLED_GEMINI
-
-// ENUM DEFINITIONS
-
-
-/** @brief Enum that lists all the system IDs of the various devices */
-#ifndef HAVE_ENUM_SysIDs
-#define HAVE_ENUM_SysIDs
-typedef enum SysIDs
-{
- MAV_SYSID_MAIN=1, /* | */
- MAV_SYSID_PAYLOAD=2, /* | */
- MAV_SYSID_RIG=3, /* | */
- MAV_SYSID_GS=4, /* | */
- SysIDs_ENUM_END=5, /* | */
-} SysIDs;
-#endif
-
-/** @brief Enum list for all the telemetries that can be requested */
-#ifndef HAVE_ENUM_SystemTMList
-#define HAVE_ENUM_SystemTMList
-typedef enum SystemTMList
-{
- MAV_SYS_ID=1, /* State of init results about system hardware/software components | */
- MAV_FSM_ID=2, /* States of all On-Board FSMs | */
- MAV_PIN_OBS_ID=3, /* Pin observer data | */
- MAV_LOGGER_ID=4, /* SD Logger stats | */
- MAV_MAVLINK_STATS=5, /* Mavlink driver stats | */
- MAV_TASK_STATS_ID=6, /* Task scheduler statistics answer: n mavlink messages where n is the number of tasks | */
- MAV_ADA_ID=7, /* ADA Status | */
- MAV_NAS_ID=8, /* NavigationSystem data | */
- MAV_MEA_ID=9, /* MEA Status | */
- MAV_CAN_ID=10, /* Canbus stats | */
- MAV_FLIGHT_ID=11, /* Flight telemetry | */
- MAV_STATS_ID=12, /* Satistics telemetry | */
- MAV_SENSORS_STATE_ID=13, /* Sensors init state telemetry | */
- MAV_GSE_ID=14, /* Ground Segnement Equipment | */
- MAV_MOTOR_ID=15, /* Rocket Motor data | */
- SystemTMList_ENUM_END=16, /* | */
-} SystemTMList;
-#endif
-
-/** @brief Enum list of all sensors telemetries that can be requested */
-#ifndef HAVE_ENUM_SensorsTMList
-#define HAVE_ENUM_SensorsTMList
-typedef enum SensorsTMList
-{
- MAV_GPS_ID=1, /* GPS data | */
- MAV_BMX160_ID=2, /* BMX160 IMU data | */
- MAV_VN100_ID=3, /* VN100 IMU data | */
- MAV_MPU9250_ID=4, /* MPU9250 IMU data | */
- MAV_ADS_ID=5, /* ADS 8 channel ADC data | */
- MAV_MS5803_ID=6, /* MS5803 barometer data | */
- MAV_BME280_ID=7, /* BME280 barometer data | */
- MAV_CURRENT_SENSE_ID=8, /* Electrical current sensors data | */
- MAV_LIS3MDL_ID=9, /* LIS3MDL compass data | */
- MAV_DPL_PRESS_ID=10, /* Deployment pressure data | */
- MAV_STATIC_PRESS_ID=11, /* Static pressure data | */
- MAV_PITOT_PRESS_ID=12, /* Pitot pressure data | */
- MAV_BATTERY_VOLTAGE_ID=13, /* Battery voltage data | */
- MAV_LOAD_CELL_ID=14, /* Load cell data | */
- MAV_FILLING_PRESS_ID=15, /* Filling line pressure | */
- MAV_TANK_TOP_PRESS_ID=16, /* Top tank pressure | */
- MAV_TANK_BOTTOM_PRESS_ID=17, /* Bottom tank pressure | */
- MAV_TANK_TEMP_ID=18, /* Tank temperature | */
- MAV_COMBUSTION_PRESS_ID=19, /* Combustion chamber pressure | */
- MAV_VESSEL_PRESS_ID=20, /* Vessel pressure | */
- MAV_LOAD_CELL_VESSEL_ID=21, /* Vessel tank weight | */
- MAV_LOAD_CELL_TANK_ID=22, /* Tank weight | */
- MAV_LIS2MDL_ID=23, /* Magnetometer data | */
- MAV_LPS28DFW_ID=24, /* Pressure sensor data | */
- MAV_LSM6DSRX_ID=25, /* IMU data | */
- MAV_H3LIS331DL_ID=26, /* 400G accelerometer | */
- MAV_LPS22DF_ID=27, /* Pressure sensor data | */
- SensorsTMList_ENUM_END=28, /* | */
-} SensorsTMList;
-#endif
-
-/** @brief Enum of the commands */
-#ifndef HAVE_ENUM_MavCommandList
-#define HAVE_ENUM_MavCommandList
-typedef enum MavCommandList
-{
- MAV_CMD_ARM=1, /* Command to arm the rocket | */
- MAV_CMD_DISARM=2, /* Command to disarm the rocket | */
- MAV_CMD_CALIBRATE=3, /* Command to trigger the calibration | */
- MAV_CMD_SAVE_CALIBRATION=4, /* Command to save the current calibration into a file | */
- MAV_CMD_FORCE_INIT=5, /* Command to init the rocket | */
- MAV_CMD_FORCE_LAUNCH=6, /* Command to force the launch state on the rocket | */
- MAV_CMD_FORCE_LANDING=7, /* Command to communicate the end of the mission and close the file descriptors in the SD card | */
- MAV_CMD_FORCE_APOGEE=8, /* Command to trigger the apogee event | */
- MAV_CMD_FORCE_EXPULSION=9, /* Command to open the nosecone | */
- MAV_CMD_FORCE_DEPLOYMENT=10, /* Command to activate the thermal cutters and cut the drogue, activating both thermal cutters sequentially | */
- MAV_CMD_START_LOGGING=11, /* Command to enable sensor logging | */
- MAV_CMD_STOP_LOGGING=12, /* Command to permanently close the log file | */
- MAV_CMD_FORCE_REBOOT=13, /* Command to reset the board from test status | */
- MAV_CMD_ENTER_TEST_MODE=14, /* Command to enter the test mode | */
- MAV_CMD_EXIT_TEST_MODE=15, /* Command to exit the test mode | */
- MAV_CMD_START_RECORDING=16, /* Command to start the internal cameras recordings | */
- MAV_CMD_STOP_RECORDING=17, /* Command to stop the internal cameras recordings | */
- MavCommandList_ENUM_END=18, /* | */
-} MavCommandList;
-#endif
-
-/** @brief Enum of all the servos used on Gemini */
-#ifndef HAVE_ENUM_ServosList
-#define HAVE_ENUM_ServosList
-typedef enum ServosList
-{
- AIR_BRAKES_SERVO=1, /* | */
- EXPULSION_SERVO=2, /* | */
- PARAFOIL_LEFT_SERVO=3, /* | */
- PARAFOIL_RIGHT_SERVO=4, /* | */
- MAIN_VALVE=5, /* | */
- VENTING_VALVE=6, /* | */
- RELEASE_VALVE=7, /* | */
- FILLING_VALVE=8, /* | */
- DISCONNECT_SERVO=9, /* | */
- ServosList_ENUM_END=10, /* | */
-} ServosList;
-#endif
-
-/** @brief Enum of all the pins used on Gemini */
-#ifndef HAVE_ENUM_PinsList
-#define HAVE_ENUM_PinsList
-typedef enum PinsList
-{
- LAUNCH_PIN=1, /* | */
- NOSECONE_PIN=2, /* | */
- DEPLOYMENT_PIN=3, /* | */
- QUICK_CONNECTOR_PIN=4, /* | */
- PinsList_ENUM_END=5, /* | */
-} PinsList;
-#endif
-
-// MAVLINK VERSION
-
-#ifndef MAVLINK_VERSION
-#define MAVLINK_VERSION 1
-#endif
-
-#if (MAVLINK_VERSION == 0)
-#undef MAVLINK_VERSION
-#define MAVLINK_VERSION 1
-#endif
-
-// MESSAGE DEFINITIONS
-#include "./mavlink_msg_ping_tc.h"
-#include "./mavlink_msg_command_tc.h"
-#include "./mavlink_msg_system_tm_request_tc.h"
-#include "./mavlink_msg_sensor_tm_request_tc.h"
-#include "./mavlink_msg_servo_tm_request_tc.h"
-#include "./mavlink_msg_set_servo_angle_tc.h"
-#include "./mavlink_msg_wiggle_servo_tc.h"
-#include "./mavlink_msg_reset_servo_tc.h"
-#include "./mavlink_msg_set_reference_altitude_tc.h"
-#include "./mavlink_msg_set_reference_temperature_tc.h"
-#include "./mavlink_msg_set_orientation_tc.h"
-#include "./mavlink_msg_set_coordinates_tc.h"
-#include "./mavlink_msg_raw_event_tc.h"
-#include "./mavlink_msg_set_deployment_altitude_tc.h"
-#include "./mavlink_msg_set_target_coordinates_tc.h"
-#include "./mavlink_msg_set_algorithm_tc.h"
-#include "./mavlink_msg_set_atomic_valve_timing_tc.h"
-#include "./mavlink_msg_set_valve_maximum_aperture_tc.h"
-#include "./mavlink_msg_conrig_state_tc.h"
-#include "./mavlink_msg_set_ignition_time_tc.h"
-#include "./mavlink_msg_ack_tm.h"
-#include "./mavlink_msg_nack_tm.h"
-#include "./mavlink_msg_gps_tm.h"
-#include "./mavlink_msg_imu_tm.h"
-#include "./mavlink_msg_pressure_tm.h"
-#include "./mavlink_msg_adc_tm.h"
-#include "./mavlink_msg_voltage_tm.h"
-#include "./mavlink_msg_current_tm.h"
-#include "./mavlink_msg_temp_tm.h"
-#include "./mavlink_msg_load_tm.h"
-#include "./mavlink_msg_attitude_tm.h"
-#include "./mavlink_msg_sensor_state_tm.h"
-#include "./mavlink_msg_servo_tm.h"
-#include "./mavlink_msg_pin_tm.h"
-#include "./mavlink_msg_receiver_tm.h"
-#include "./mavlink_msg_sys_tm.h"
-#include "./mavlink_msg_fsm_tm.h"
-#include "./mavlink_msg_logger_tm.h"
-#include "./mavlink_msg_mavlink_stats_tm.h"
-#include "./mavlink_msg_task_stats_tm.h"
-#include "./mavlink_msg_ada_tm.h"
-#include "./mavlink_msg_nas_tm.h"
-#include "./mavlink_msg_mea_tm.h"
-#include "./mavlink_msg_rocket_flight_tm.h"
-#include "./mavlink_msg_payload_flight_tm.h"
-#include "./mavlink_msg_rocket_stats_tm.h"
-#include "./mavlink_msg_payload_stats_tm.h"
-#include "./mavlink_msg_gse_tm.h"
-#include "./mavlink_msg_motor_tm.h"
-
-// base include
-
-
-#undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH 1902963619411886953
-
-#if MAVLINK_THIS_XML_HASH == MAVLINK_PRIMARY_XML_HASH
-# define MAVLINK_MESSAGE_INFO {{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING_TC, MAVLINK_MESSAGE_INFO_COMMAND_TC, MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC, MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC, MAVLINK_MESSAGE_INFO_RESET_SERVO_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC, MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_RAW_EVENT_TC, MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC, MAVLINK_MESSAGE_INFO_SET_ATOMIC_VALVE_TIMING_TC, MAVLINK_MESSAGE_INFO_SET_VALVE_MAXIMUM_APERTURE_TC, MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC, MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACK_TM, MAVLINK_MESSAGE_INFO_NACK_TM, MAVLINK_MESSAGE_INFO_GPS_TM, MAVLINK_MESSAGE_INFO_IMU_TM, MAVLINK_MESSAGE_INFO_PRESSURE_TM, MAVLINK_MESSAGE_INFO_ADC_TM, MAVLINK_MESSAGE_INFO_VOLTAGE_TM, MAVLINK_MESSAGE_INFO_CURRENT_TM, MAVLINK_MESSAGE_INFO_TEMP_TM, MAVLINK_MESSAGE_INFO_LOAD_TM, MAVLINK_MESSAGE_INFO_ATTITUDE_TM, MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM, MAVLINK_MESSAGE_INFO_SERVO_TM, MAVLINK_MESSAGE_INFO_PIN_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_RECEIVER_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_TM, MAVLINK_MESSAGE_INFO_FSM_TM, MAVLINK_MESSAGE_INFO_LOGGER_TM, MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM, MAVLINK_MESSAGE_INFO_TASK_STATS_TM, MAVLINK_MESSAGE_INFO_ADA_TM, MAVLINK_MESSAGE_INFO_NAS_TM, MAVLINK_MESSAGE_INFO_MEA_TM, MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM, MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM, MAVLINK_MESSAGE_INFO_GSE_TM, MAVLINK_MESSAGE_INFO_MOTOR_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
-# define MAVLINK_MESSAGE_NAMES {{ "ACK_TM", 100 }, { "ADA_TM", 205 }, { "ADC_TM", 105 }, { "ATTITUDE_TM", 110 }, { "COMMAND_TC", 2 }, { "CONRIG_STATE_TC", 19 }, { "CURRENT_TM", 107 }, { "FSM_TM", 201 }, { "GPS_TM", 102 }, { "GSE_TM", 212 }, { "IMU_TM", 103 }, { "LOAD_TM", 109 }, { "LOGGER_TM", 202 }, { "MAVLINK_STATS_TM", 203 }, { "MEA_TM", 207 }, { "MOTOR_TM", 213 }, { "NACK_TM", 101 }, { "NAS_TM", 206 }, { "PAYLOAD_FLIGHT_TM", 209 }, { "PAYLOAD_STATS_TM", 211 }, { "PING_TC", 1 }, { "PIN_TM", 113 }, { "PRESSURE_TM", 104 }, { "RAW_EVENT_TC", 13 }, { "RECEIVER_TM", 150 }, { "RESET_SERVO_TC", 8 }, { "ROCKET_FLIGHT_TM", 208 }, { "ROCKET_STATS_TM", 210 }, { "SENSOR_STATE_TM", 111 }, { "SENSOR_TM_REQUEST_TC", 4 }, { "SERVO_TM", 112 }, { "SERVO_TM_REQUEST_TC", 5 }, { "SET_ALGORITHM_TC", 16 }, { "SET_ATOMIC_VALVE_TIMING_TC", 17 }, { "SET_COORDINATES_TC", 12 }, { "SET_DEPLOYMENT_ALTITUDE_TC", 14 }, { "SET_IGNITION_TIME_TC", 20 }, { "SET_ORIENTATION_TC", 11 }, { "SET_REFERENCE_ALTITUDE_TC", 9 }, { "SET_REFERENCE_TEMPERATURE_TC", 10 }, { "SET_SERVO_ANGLE_TC", 6 }, { "SET_TARGET_COORDINATES_TC", 15 }, { "SET_VALVE_MAXIMUM_APERTURE_TC", 18 }, { "SYSTEM_TM_REQUEST_TC", 3 }, { "SYS_TM", 200 }, { "TASK_STATS_TM", 204 }, { "TEMP_TM", 108 }, { "VOLTAGE_TM", 106 }, { "WIGGLE_SERVO_TC", 7 }}
-# if MAVLINK_COMMAND_24BIT
-# include "../mavlink_get_info.h"
-# endif
-#endif
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // MAVLINK_GEMINI_H
diff --git a/mavlink_lib/gemini/mavlink.h b/mavlink_lib/gemini/mavlink.h
deleted file mode 100644
index 823dbc7577f5166f3090e8b99d7bad1834b265ff..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink.h
+++ /dev/null
@@ -1,34 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol built from gemini.xml
- * @see http://mavlink.org
- */
-#pragma once
-#ifndef MAVLINK_H
-#define MAVLINK_H
-
-#define MAVLINK_PRIMARY_XML_HASH 1902963619411886953
-
-#ifndef MAVLINK_STX
-#define MAVLINK_STX 254
-#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 0
-#endif
-
-#include "version.h"
-#include "gemini.h"
-
-#endif // MAVLINK_H
diff --git a/mavlink_lib/gemini/mavlink_msg_ack_tm.h b/mavlink_lib/gemini/mavlink_msg_ack_tm.h
deleted file mode 100644
index 8abc2a50773e576580ab8179be7c6a2348071c59..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_ack_tm.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE ACK_TM PACKING
-
-#define MAVLINK_MSG_ID_ACK_TM 100
-
-
-typedef struct __mavlink_ack_tm_t {
- uint8_t recv_msgid; /*< Message id of the received message*/
- uint8_t seq_ack; /*< Sequence number of the received message*/
-} mavlink_ack_tm_t;
-
-#define MAVLINK_MSG_ID_ACK_TM_LEN 2
-#define MAVLINK_MSG_ID_ACK_TM_MIN_LEN 2
-#define MAVLINK_MSG_ID_100_LEN 2
-#define MAVLINK_MSG_ID_100_MIN_LEN 2
-
-#define MAVLINK_MSG_ID_ACK_TM_CRC 50
-#define MAVLINK_MSG_ID_100_CRC 50
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ACK_TM { \
- 100, \
- "ACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_ack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_ack_tm_t, seq_ack) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ACK_TM { \
- "ACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_ack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_ack_tm_t, seq_ack) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ack_tm 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 recv_msgid Message id of the received message
- * @param seq_ack Sequence number of the received message
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ack_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACK_TM_LEN);
-#else
- mavlink_ack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ACK_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-}
-
-/**
- * @brief Pack a ack_tm 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 recv_msgid Message id of the received message
- * @param seq_ack Sequence number of the received message
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ack_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t recv_msgid,uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACK_TM_LEN);
-#else
- mavlink_ack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ACK_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-}
-
-/**
- * @brief Encode a ack_tm 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 ack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ack_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ack_tm_t* ack_tm)
-{
- return mavlink_msg_ack_tm_pack(system_id, component_id, msg, ack_tm->recv_msgid, ack_tm->seq_ack);
-}
-
-/**
- * @brief Encode a ack_tm 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 ack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ack_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ack_tm_t* ack_tm)
-{
- return mavlink_msg_ack_tm_pack_chan(system_id, component_id, chan, msg, ack_tm->recv_msgid, ack_tm->seq_ack);
-}
-
-/**
- * @brief Send a ack_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param recv_msgid Message id of the received message
- * @param seq_ack Sequence number of the received message
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ack_tm_send(mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, buf, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#else
- mavlink_ack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, (const char *)&packet, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a ack_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ack_tm_send_struct(mavlink_channel_t chan, const mavlink_ack_tm_t* ack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ack_tm_send(chan, ack_tm->recv_msgid, ack_tm->seq_ack);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, (const char *)ack_tm, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ACK_TM_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_ack_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, buf, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#else
- mavlink_ack_tm_t *packet = (mavlink_ack_tm_t *)msgbuf;
- packet->recv_msgid = recv_msgid;
- packet->seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, (const char *)packet, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ACK_TM UNPACKING
-
-
-/**
- * @brief Get field recv_msgid from ack_tm message
- *
- * @return Message id of the received message
- */
-static inline uint8_t mavlink_msg_ack_tm_get_recv_msgid(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field seq_ack from ack_tm message
- *
- * @return Sequence number of the received message
- */
-static inline uint8_t mavlink_msg_ack_tm_get_seq_ack(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Decode a ack_tm message into a struct
- *
- * @param msg The message to decode
- * @param ack_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ack_tm_decode(const mavlink_message_t* msg, mavlink_ack_tm_t* ack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ack_tm->recv_msgid = mavlink_msg_ack_tm_get_recv_msgid(msg);
- ack_tm->seq_ack = mavlink_msg_ack_tm_get_seq_ack(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ACK_TM_LEN? msg->len : MAVLINK_MSG_ID_ACK_TM_LEN;
- memset(ack_tm, 0, MAVLINK_MSG_ID_ACK_TM_LEN);
- memcpy(ack_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_ada_tm.h b/mavlink_lib/gemini/mavlink_msg_ada_tm.h
deleted file mode 100644
index f96a75c0db6fcd54bea1d9bb6658860e7e998179..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_ada_tm.h
+++ /dev/null
@@ -1,513 +0,0 @@
-#pragma once
-// MESSAGE ADA_TM PACKING
-
-#define MAVLINK_MSG_ID_ADA_TM 205
-
-
-typedef struct __mavlink_ada_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float kalman_x0; /*< Kalman state variable 0 (pressure)*/
- float kalman_x1; /*< Kalman state variable 1 (pressure velocity)*/
- float kalman_x2; /*< Kalman state variable 2 (pressure acceleration)*/
- float vertical_speed; /*< [m/s] Vertical speed computed by the ADA*/
- float msl_altitude; /*< [m] Altitude w.r.t. mean sea level*/
- float ref_pressure; /*< [Pa] Calibration pressure*/
- float ref_altitude; /*< [m] Calibration altitude*/
- float ref_temperature; /*< [degC] Calibration temperature*/
- float msl_pressure; /*< [Pa] Expected pressure at mean sea level*/
- float msl_temperature; /*< [degC] Expected temperature at mean sea level*/
- float dpl_altitude; /*< [m] Main parachute deployment altituyde*/
- uint8_t state; /*< ADA current state*/
-} mavlink_ada_tm_t;
-
-#define MAVLINK_MSG_ID_ADA_TM_LEN 53
-#define MAVLINK_MSG_ID_ADA_TM_MIN_LEN 53
-#define MAVLINK_MSG_ID_205_LEN 53
-#define MAVLINK_MSG_ID_205_MIN_LEN 53
-
-#define MAVLINK_MSG_ID_ADA_TM_CRC 234
-#define MAVLINK_MSG_ID_205_CRC 234
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ADA_TM { \
- 205, \
- "ADA_TM", \
- 13, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ada_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_ada_tm_t, state) }, \
- { "kalman_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ada_tm_t, kalman_x0) }, \
- { "kalman_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ada_tm_t, kalman_x1) }, \
- { "kalman_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ada_tm_t, kalman_x2) }, \
- { "vertical_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ada_tm_t, vertical_speed) }, \
- { "msl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ada_tm_t, msl_altitude) }, \
- { "ref_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_ada_tm_t, ref_pressure) }, \
- { "ref_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_ada_tm_t, ref_altitude) }, \
- { "ref_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_ada_tm_t, ref_temperature) }, \
- { "msl_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_ada_tm_t, msl_pressure) }, \
- { "msl_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_ada_tm_t, msl_temperature) }, \
- { "dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_ada_tm_t, dpl_altitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ADA_TM { \
- "ADA_TM", \
- 13, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ada_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_ada_tm_t, state) }, \
- { "kalman_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ada_tm_t, kalman_x0) }, \
- { "kalman_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ada_tm_t, kalman_x1) }, \
- { "kalman_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ada_tm_t, kalman_x2) }, \
- { "vertical_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ada_tm_t, vertical_speed) }, \
- { "msl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ada_tm_t, msl_altitude) }, \
- { "ref_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_ada_tm_t, ref_pressure) }, \
- { "ref_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_ada_tm_t, ref_altitude) }, \
- { "ref_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_ada_tm_t, ref_temperature) }, \
- { "msl_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_ada_tm_t, msl_pressure) }, \
- { "msl_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_ada_tm_t, msl_temperature) }, \
- { "dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_ada_tm_t, dpl_altitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ada_tm 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] When was this logged
- * @param state ADA current state
- * @param kalman_x0 Kalman state variable 0 (pressure)
- * @param kalman_x1 Kalman state variable 1 (pressure velocity)
- * @param kalman_x2 Kalman state variable 2 (pressure acceleration)
- * @param vertical_speed [m/s] Vertical speed computed by the ADA
- * @param msl_altitude [m] Altitude w.r.t. mean sea level
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_altitude [m] Calibration altitude
- * @param ref_temperature [degC] Calibration temperature
- * @param msl_pressure [Pa] Expected pressure at mean sea level
- * @param msl_temperature [degC] Expected temperature at mean sea level
- * @param dpl_altitude [m] Main parachute deployment altituyde
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ada_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float vertical_speed, float msl_altitude, float ref_pressure, float ref_altitude, float ref_temperature, float msl_pressure, float msl_temperature, float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, kalman_x0);
- _mav_put_float(buf, 12, kalman_x1);
- _mav_put_float(buf, 16, kalman_x2);
- _mav_put_float(buf, 20, vertical_speed);
- _mav_put_float(buf, 24, msl_altitude);
- _mav_put_float(buf, 28, ref_pressure);
- _mav_put_float(buf, 32, ref_altitude);
- _mav_put_float(buf, 36, ref_temperature);
- _mav_put_float(buf, 40, msl_pressure);
- _mav_put_float(buf, 44, msl_temperature);
- _mav_put_float(buf, 48, dpl_altitude);
- _mav_put_uint8_t(buf, 52, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADA_TM_LEN);
-#else
- mavlink_ada_tm_t packet;
- packet.timestamp = timestamp;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.vertical_speed = vertical_speed;
- packet.msl_altitude = msl_altitude;
- packet.ref_pressure = ref_pressure;
- packet.ref_altitude = ref_altitude;
- packet.ref_temperature = ref_temperature;
- packet.msl_pressure = msl_pressure;
- packet.msl_temperature = msl_temperature;
- packet.dpl_altitude = dpl_altitude;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADA_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADA_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-}
-
-/**
- * @brief Pack a ada_tm 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] When was this logged
- * @param state ADA current state
- * @param kalman_x0 Kalman state variable 0 (pressure)
- * @param kalman_x1 Kalman state variable 1 (pressure velocity)
- * @param kalman_x2 Kalman state variable 2 (pressure acceleration)
- * @param vertical_speed [m/s] Vertical speed computed by the ADA
- * @param msl_altitude [m] Altitude w.r.t. mean sea level
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_altitude [m] Calibration altitude
- * @param ref_temperature [degC] Calibration temperature
- * @param msl_pressure [Pa] Expected pressure at mean sea level
- * @param msl_temperature [degC] Expected temperature at mean sea level
- * @param dpl_altitude [m] Main parachute deployment altituyde
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ada_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t state,float kalman_x0,float kalman_x1,float kalman_x2,float vertical_speed,float msl_altitude,float ref_pressure,float ref_altitude,float ref_temperature,float msl_pressure,float msl_temperature,float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, kalman_x0);
- _mav_put_float(buf, 12, kalman_x1);
- _mav_put_float(buf, 16, kalman_x2);
- _mav_put_float(buf, 20, vertical_speed);
- _mav_put_float(buf, 24, msl_altitude);
- _mav_put_float(buf, 28, ref_pressure);
- _mav_put_float(buf, 32, ref_altitude);
- _mav_put_float(buf, 36, ref_temperature);
- _mav_put_float(buf, 40, msl_pressure);
- _mav_put_float(buf, 44, msl_temperature);
- _mav_put_float(buf, 48, dpl_altitude);
- _mav_put_uint8_t(buf, 52, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADA_TM_LEN);
-#else
- mavlink_ada_tm_t packet;
- packet.timestamp = timestamp;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.vertical_speed = vertical_speed;
- packet.msl_altitude = msl_altitude;
- packet.ref_pressure = ref_pressure;
- packet.ref_altitude = ref_altitude;
- packet.ref_temperature = ref_temperature;
- packet.msl_pressure = msl_pressure;
- packet.msl_temperature = msl_temperature;
- packet.dpl_altitude = dpl_altitude;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADA_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADA_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-}
-
-/**
- * @brief Encode a ada_tm 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 ada_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ada_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ada_tm_t* ada_tm)
-{
- return mavlink_msg_ada_tm_pack(system_id, component_id, msg, ada_tm->timestamp, ada_tm->state, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->vertical_speed, ada_tm->msl_altitude, ada_tm->ref_pressure, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_pressure, ada_tm->msl_temperature, ada_tm->dpl_altitude);
-}
-
-/**
- * @brief Encode a ada_tm 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 ada_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ada_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ada_tm_t* ada_tm)
-{
- return mavlink_msg_ada_tm_pack_chan(system_id, component_id, chan, msg, ada_tm->timestamp, ada_tm->state, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->vertical_speed, ada_tm->msl_altitude, ada_tm->ref_pressure, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_pressure, ada_tm->msl_temperature, ada_tm->dpl_altitude);
-}
-
-/**
- * @brief Send a ada_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param state ADA current state
- * @param kalman_x0 Kalman state variable 0 (pressure)
- * @param kalman_x1 Kalman state variable 1 (pressure velocity)
- * @param kalman_x2 Kalman state variable 2 (pressure acceleration)
- * @param vertical_speed [m/s] Vertical speed computed by the ADA
- * @param msl_altitude [m] Altitude w.r.t. mean sea level
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_altitude [m] Calibration altitude
- * @param ref_temperature [degC] Calibration temperature
- * @param msl_pressure [Pa] Expected pressure at mean sea level
- * @param msl_temperature [degC] Expected temperature at mean sea level
- * @param dpl_altitude [m] Main parachute deployment altituyde
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ada_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float vertical_speed, float msl_altitude, float ref_pressure, float ref_altitude, float ref_temperature, float msl_pressure, float msl_temperature, float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, kalman_x0);
- _mav_put_float(buf, 12, kalman_x1);
- _mav_put_float(buf, 16, kalman_x2);
- _mav_put_float(buf, 20, vertical_speed);
- _mav_put_float(buf, 24, msl_altitude);
- _mav_put_float(buf, 28, ref_pressure);
- _mav_put_float(buf, 32, ref_altitude);
- _mav_put_float(buf, 36, ref_temperature);
- _mav_put_float(buf, 40, msl_pressure);
- _mav_put_float(buf, 44, msl_temperature);
- _mav_put_float(buf, 48, dpl_altitude);
- _mav_put_uint8_t(buf, 52, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, buf, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#else
- mavlink_ada_tm_t packet;
- packet.timestamp = timestamp;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.vertical_speed = vertical_speed;
- packet.msl_altitude = msl_altitude;
- packet.ref_pressure = ref_pressure;
- packet.ref_altitude = ref_altitude;
- packet.ref_temperature = ref_temperature;
- packet.msl_pressure = msl_pressure;
- packet.msl_temperature = msl_temperature;
- packet.dpl_altitude = dpl_altitude;
- packet.state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, (const char *)&packet, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a ada_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ada_tm_send_struct(mavlink_channel_t chan, const mavlink_ada_tm_t* ada_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ada_tm_send(chan, ada_tm->timestamp, ada_tm->state, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->vertical_speed, ada_tm->msl_altitude, ada_tm->ref_pressure, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_pressure, ada_tm->msl_temperature, ada_tm->dpl_altitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, (const char *)ada_tm, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ADA_TM_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_ada_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float vertical_speed, float msl_altitude, float ref_pressure, float ref_altitude, float ref_temperature, float msl_pressure, float msl_temperature, float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, kalman_x0);
- _mav_put_float(buf, 12, kalman_x1);
- _mav_put_float(buf, 16, kalman_x2);
- _mav_put_float(buf, 20, vertical_speed);
- _mav_put_float(buf, 24, msl_altitude);
- _mav_put_float(buf, 28, ref_pressure);
- _mav_put_float(buf, 32, ref_altitude);
- _mav_put_float(buf, 36, ref_temperature);
- _mav_put_float(buf, 40, msl_pressure);
- _mav_put_float(buf, 44, msl_temperature);
- _mav_put_float(buf, 48, dpl_altitude);
- _mav_put_uint8_t(buf, 52, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, buf, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#else
- mavlink_ada_tm_t *packet = (mavlink_ada_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->kalman_x0 = kalman_x0;
- packet->kalman_x1 = kalman_x1;
- packet->kalman_x2 = kalman_x2;
- packet->vertical_speed = vertical_speed;
- packet->msl_altitude = msl_altitude;
- packet->ref_pressure = ref_pressure;
- packet->ref_altitude = ref_altitude;
- packet->ref_temperature = ref_temperature;
- packet->msl_pressure = msl_pressure;
- packet->msl_temperature = msl_temperature;
- packet->dpl_altitude = dpl_altitude;
- packet->state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, (const char *)packet, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ADA_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from ada_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_ada_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field state from ada_tm message
- *
- * @return ADA current state
- */
-static inline uint8_t mavlink_msg_ada_tm_get_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 52);
-}
-
-/**
- * @brief Get field kalman_x0 from ada_tm message
- *
- * @return Kalman state variable 0 (pressure)
- */
-static inline float mavlink_msg_ada_tm_get_kalman_x0(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field kalman_x1 from ada_tm message
- *
- * @return Kalman state variable 1 (pressure velocity)
- */
-static inline float mavlink_msg_ada_tm_get_kalman_x1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field kalman_x2 from ada_tm message
- *
- * @return Kalman state variable 2 (pressure acceleration)
- */
-static inline float mavlink_msg_ada_tm_get_kalman_x2(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field vertical_speed from ada_tm message
- *
- * @return [m/s] Vertical speed computed by the ADA
- */
-static inline float mavlink_msg_ada_tm_get_vertical_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field msl_altitude from ada_tm message
- *
- * @return [m] Altitude w.r.t. mean sea level
- */
-static inline float mavlink_msg_ada_tm_get_msl_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field ref_pressure from ada_tm message
- *
- * @return [Pa] Calibration pressure
- */
-static inline float mavlink_msg_ada_tm_get_ref_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field ref_altitude from ada_tm message
- *
- * @return [m] Calibration altitude
- */
-static inline float mavlink_msg_ada_tm_get_ref_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field ref_temperature from ada_tm message
- *
- * @return [degC] Calibration temperature
- */
-static inline float mavlink_msg_ada_tm_get_ref_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field msl_pressure from ada_tm message
- *
- * @return [Pa] Expected pressure at mean sea level
- */
-static inline float mavlink_msg_ada_tm_get_msl_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field msl_temperature from ada_tm message
- *
- * @return [degC] Expected temperature at mean sea level
- */
-static inline float mavlink_msg_ada_tm_get_msl_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field dpl_altitude from ada_tm message
- *
- * @return [m] Main parachute deployment altituyde
- */
-static inline float mavlink_msg_ada_tm_get_dpl_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Decode a ada_tm message into a struct
- *
- * @param msg The message to decode
- * @param ada_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ada_tm_decode(const mavlink_message_t* msg, mavlink_ada_tm_t* ada_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ada_tm->timestamp = mavlink_msg_ada_tm_get_timestamp(msg);
- ada_tm->kalman_x0 = mavlink_msg_ada_tm_get_kalman_x0(msg);
- ada_tm->kalman_x1 = mavlink_msg_ada_tm_get_kalman_x1(msg);
- ada_tm->kalman_x2 = mavlink_msg_ada_tm_get_kalman_x2(msg);
- ada_tm->vertical_speed = mavlink_msg_ada_tm_get_vertical_speed(msg);
- ada_tm->msl_altitude = mavlink_msg_ada_tm_get_msl_altitude(msg);
- ada_tm->ref_pressure = mavlink_msg_ada_tm_get_ref_pressure(msg);
- ada_tm->ref_altitude = mavlink_msg_ada_tm_get_ref_altitude(msg);
- ada_tm->ref_temperature = mavlink_msg_ada_tm_get_ref_temperature(msg);
- ada_tm->msl_pressure = mavlink_msg_ada_tm_get_msl_pressure(msg);
- ada_tm->msl_temperature = mavlink_msg_ada_tm_get_msl_temperature(msg);
- ada_tm->dpl_altitude = mavlink_msg_ada_tm_get_dpl_altitude(msg);
- ada_tm->state = mavlink_msg_ada_tm_get_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ADA_TM_LEN? msg->len : MAVLINK_MSG_ID_ADA_TM_LEN;
- memset(ada_tm, 0, MAVLINK_MSG_ID_ADA_TM_LEN);
- memcpy(ada_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_adc_tm.h b/mavlink_lib/gemini/mavlink_msg_adc_tm.h
deleted file mode 100644
index 04c7612852769618318043c1a36059b224ba9a18..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_adc_tm.h
+++ /dev/null
@@ -1,430 +0,0 @@
-#pragma once
-// MESSAGE ADC_TM PACKING
-
-#define MAVLINK_MSG_ID_ADC_TM 105
-
-
-typedef struct __mavlink_adc_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float channel_0; /*< [V] ADC voltage measured on channel 0*/
- float channel_1; /*< [V] ADC voltage measured on channel 1*/
- float channel_2; /*< [V] ADC voltage measured on channel 2*/
- float channel_3; /*< [V] ADC voltage measured on channel 3*/
- float channel_4; /*< [V] ADC voltage measured on channel 4*/
- float channel_5; /*< [V] ADC voltage measured on channel 5*/
- float channel_6; /*< [V] ADC voltage measured on channel 6*/
- float channel_7; /*< [V] ADC voltage measured on channel 7*/
- char sensor_name[20]; /*< Sensor name*/
-} mavlink_adc_tm_t;
-
-#define MAVLINK_MSG_ID_ADC_TM_LEN 60
-#define MAVLINK_MSG_ID_ADC_TM_MIN_LEN 60
-#define MAVLINK_MSG_ID_105_LEN 60
-#define MAVLINK_MSG_ID_105_MIN_LEN 60
-
-#define MAVLINK_MSG_ID_ADC_TM_CRC 229
-#define MAVLINK_MSG_ID_105_CRC 229
-
-#define MAVLINK_MSG_ADC_TM_FIELD_SENSOR_NAME_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ADC_TM { \
- 105, \
- "ADC_TM", \
- 10, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_adc_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 40, offsetof(mavlink_adc_tm_t, sensor_name) }, \
- { "channel_0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_adc_tm_t, channel_0) }, \
- { "channel_1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_adc_tm_t, channel_1) }, \
- { "channel_2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_adc_tm_t, channel_2) }, \
- { "channel_3", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_adc_tm_t, channel_3) }, \
- { "channel_4", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_adc_tm_t, channel_4) }, \
- { "channel_5", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_adc_tm_t, channel_5) }, \
- { "channel_6", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_adc_tm_t, channel_6) }, \
- { "channel_7", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_adc_tm_t, channel_7) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ADC_TM { \
- "ADC_TM", \
- 10, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_adc_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 40, offsetof(mavlink_adc_tm_t, sensor_name) }, \
- { "channel_0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_adc_tm_t, channel_0) }, \
- { "channel_1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_adc_tm_t, channel_1) }, \
- { "channel_2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_adc_tm_t, channel_2) }, \
- { "channel_3", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_adc_tm_t, channel_3) }, \
- { "channel_4", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_adc_tm_t, channel_4) }, \
- { "channel_5", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_adc_tm_t, channel_5) }, \
- { "channel_6", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_adc_tm_t, channel_6) }, \
- { "channel_7", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_adc_tm_t, channel_7) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a adc_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param channel_0 [V] ADC voltage measured on channel 0
- * @param channel_1 [V] ADC voltage measured on channel 1
- * @param channel_2 [V] ADC voltage measured on channel 2
- * @param channel_3 [V] ADC voltage measured on channel 3
- * @param channel_4 [V] ADC voltage measured on channel 4
- * @param channel_5 [V] ADC voltage measured on channel 5
- * @param channel_6 [V] ADC voltage measured on channel 6
- * @param channel_7 [V] ADC voltage measured on channel 7
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_adc_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_name, float channel_0, float channel_1, float channel_2, float channel_3, float channel_4, float channel_5, float channel_6, float channel_7)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, channel_0);
- _mav_put_float(buf, 12, channel_1);
- _mav_put_float(buf, 16, channel_2);
- _mav_put_float(buf, 20, channel_3);
- _mav_put_float(buf, 24, channel_4);
- _mav_put_float(buf, 28, channel_5);
- _mav_put_float(buf, 32, channel_6);
- _mav_put_float(buf, 36, channel_7);
- _mav_put_char_array(buf, 40, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADC_TM_LEN);
-#else
- mavlink_adc_tm_t packet;
- packet.timestamp = timestamp;
- packet.channel_0 = channel_0;
- packet.channel_1 = channel_1;
- packet.channel_2 = channel_2;
- packet.channel_3 = channel_3;
- packet.channel_4 = channel_4;
- packet.channel_5 = channel_5;
- packet.channel_6 = channel_6;
- packet.channel_7 = channel_7;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADC_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADC_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-}
-
-/**
- * @brief Pack a adc_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param channel_0 [V] ADC voltage measured on channel 0
- * @param channel_1 [V] ADC voltage measured on channel 1
- * @param channel_2 [V] ADC voltage measured on channel 2
- * @param channel_3 [V] ADC voltage measured on channel 3
- * @param channel_4 [V] ADC voltage measured on channel 4
- * @param channel_5 [V] ADC voltage measured on channel 5
- * @param channel_6 [V] ADC voltage measured on channel 6
- * @param channel_7 [V] ADC voltage measured on channel 7
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_adc_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_name,float channel_0,float channel_1,float channel_2,float channel_3,float channel_4,float channel_5,float channel_6,float channel_7)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, channel_0);
- _mav_put_float(buf, 12, channel_1);
- _mav_put_float(buf, 16, channel_2);
- _mav_put_float(buf, 20, channel_3);
- _mav_put_float(buf, 24, channel_4);
- _mav_put_float(buf, 28, channel_5);
- _mav_put_float(buf, 32, channel_6);
- _mav_put_float(buf, 36, channel_7);
- _mav_put_char_array(buf, 40, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADC_TM_LEN);
-#else
- mavlink_adc_tm_t packet;
- packet.timestamp = timestamp;
- packet.channel_0 = channel_0;
- packet.channel_1 = channel_1;
- packet.channel_2 = channel_2;
- packet.channel_3 = channel_3;
- packet.channel_4 = channel_4;
- packet.channel_5 = channel_5;
- packet.channel_6 = channel_6;
- packet.channel_7 = channel_7;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADC_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADC_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-}
-
-/**
- * @brief Encode a adc_tm 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 adc_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_adc_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_adc_tm_t* adc_tm)
-{
- return mavlink_msg_adc_tm_pack(system_id, component_id, msg, adc_tm->timestamp, adc_tm->sensor_name, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3, adc_tm->channel_4, adc_tm->channel_5, adc_tm->channel_6, adc_tm->channel_7);
-}
-
-/**
- * @brief Encode a adc_tm 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 adc_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_adc_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_adc_tm_t* adc_tm)
-{
- return mavlink_msg_adc_tm_pack_chan(system_id, component_id, chan, msg, adc_tm->timestamp, adc_tm->sensor_name, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3, adc_tm->channel_4, adc_tm->channel_5, adc_tm->channel_6, adc_tm->channel_7);
-}
-
-/**
- * @brief Send a adc_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_name Sensor name
- * @param channel_0 [V] ADC voltage measured on channel 0
- * @param channel_1 [V] ADC voltage measured on channel 1
- * @param channel_2 [V] ADC voltage measured on channel 2
- * @param channel_3 [V] ADC voltage measured on channel 3
- * @param channel_4 [V] ADC voltage measured on channel 4
- * @param channel_5 [V] ADC voltage measured on channel 5
- * @param channel_6 [V] ADC voltage measured on channel 6
- * @param channel_7 [V] ADC voltage measured on channel 7
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_adc_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float channel_0, float channel_1, float channel_2, float channel_3, float channel_4, float channel_5, float channel_6, float channel_7)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, channel_0);
- _mav_put_float(buf, 12, channel_1);
- _mav_put_float(buf, 16, channel_2);
- _mav_put_float(buf, 20, channel_3);
- _mav_put_float(buf, 24, channel_4);
- _mav_put_float(buf, 28, channel_5);
- _mav_put_float(buf, 32, channel_6);
- _mav_put_float(buf, 36, channel_7);
- _mav_put_char_array(buf, 40, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, buf, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#else
- mavlink_adc_tm_t packet;
- packet.timestamp = timestamp;
- packet.channel_0 = channel_0;
- packet.channel_1 = channel_1;
- packet.channel_2 = channel_2;
- packet.channel_3 = channel_3;
- packet.channel_4 = channel_4;
- packet.channel_5 = channel_5;
- packet.channel_6 = channel_6;
- packet.channel_7 = channel_7;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)&packet, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a adc_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_adc_tm_send_struct(mavlink_channel_t chan, const mavlink_adc_tm_t* adc_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_adc_tm_send(chan, adc_tm->timestamp, adc_tm->sensor_name, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3, adc_tm->channel_4, adc_tm->channel_5, adc_tm->channel_6, adc_tm->channel_7);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)adc_tm, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ADC_TM_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_adc_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float channel_0, float channel_1, float channel_2, float channel_3, float channel_4, float channel_5, float channel_6, float channel_7)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, channel_0);
- _mav_put_float(buf, 12, channel_1);
- _mav_put_float(buf, 16, channel_2);
- _mav_put_float(buf, 20, channel_3);
- _mav_put_float(buf, 24, channel_4);
- _mav_put_float(buf, 28, channel_5);
- _mav_put_float(buf, 32, channel_6);
- _mav_put_float(buf, 36, channel_7);
- _mav_put_char_array(buf, 40, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, buf, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#else
- mavlink_adc_tm_t *packet = (mavlink_adc_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->channel_0 = channel_0;
- packet->channel_1 = channel_1;
- packet->channel_2 = channel_2;
- packet->channel_3 = channel_3;
- packet->channel_4 = channel_4;
- packet->channel_5 = channel_5;
- packet->channel_6 = channel_6;
- packet->channel_7 = channel_7;
- mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)packet, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ADC_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from adc_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_adc_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_name from adc_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_adc_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
-{
- return _MAV_RETURN_char_array(msg, sensor_name, 20, 40);
-}
-
-/**
- * @brief Get field channel_0 from adc_tm message
- *
- * @return [V] ADC voltage measured on channel 0
- */
-static inline float mavlink_msg_adc_tm_get_channel_0(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field channel_1 from adc_tm message
- *
- * @return [V] ADC voltage measured on channel 1
- */
-static inline float mavlink_msg_adc_tm_get_channel_1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field channel_2 from adc_tm message
- *
- * @return [V] ADC voltage measured on channel 2
- */
-static inline float mavlink_msg_adc_tm_get_channel_2(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field channel_3 from adc_tm message
- *
- * @return [V] ADC voltage measured on channel 3
- */
-static inline float mavlink_msg_adc_tm_get_channel_3(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field channel_4 from adc_tm message
- *
- * @return [V] ADC voltage measured on channel 4
- */
-static inline float mavlink_msg_adc_tm_get_channel_4(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field channel_5 from adc_tm message
- *
- * @return [V] ADC voltage measured on channel 5
- */
-static inline float mavlink_msg_adc_tm_get_channel_5(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field channel_6 from adc_tm message
- *
- * @return [V] ADC voltage measured on channel 6
- */
-static inline float mavlink_msg_adc_tm_get_channel_6(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field channel_7 from adc_tm message
- *
- * @return [V] ADC voltage measured on channel 7
- */
-static inline float mavlink_msg_adc_tm_get_channel_7(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Decode a adc_tm message into a struct
- *
- * @param msg The message to decode
- * @param adc_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_adc_tm_decode(const mavlink_message_t* msg, mavlink_adc_tm_t* adc_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- adc_tm->timestamp = mavlink_msg_adc_tm_get_timestamp(msg);
- adc_tm->channel_0 = mavlink_msg_adc_tm_get_channel_0(msg);
- adc_tm->channel_1 = mavlink_msg_adc_tm_get_channel_1(msg);
- adc_tm->channel_2 = mavlink_msg_adc_tm_get_channel_2(msg);
- adc_tm->channel_3 = mavlink_msg_adc_tm_get_channel_3(msg);
- adc_tm->channel_4 = mavlink_msg_adc_tm_get_channel_4(msg);
- adc_tm->channel_5 = mavlink_msg_adc_tm_get_channel_5(msg);
- adc_tm->channel_6 = mavlink_msg_adc_tm_get_channel_6(msg);
- adc_tm->channel_7 = mavlink_msg_adc_tm_get_channel_7(msg);
- mavlink_msg_adc_tm_get_sensor_name(msg, adc_tm->sensor_name);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ADC_TM_LEN? msg->len : MAVLINK_MSG_ID_ADC_TM_LEN;
- memset(adc_tm, 0, MAVLINK_MSG_ID_ADC_TM_LEN);
- memcpy(adc_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_attitude_tm.h b/mavlink_lib/gemini/mavlink_msg_attitude_tm.h
deleted file mode 100644
index c16dba2fd216b82c35caba889893c630eb261145..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_attitude_tm.h
+++ /dev/null
@@ -1,405 +0,0 @@
-#pragma once
-// MESSAGE ATTITUDE_TM PACKING
-
-#define MAVLINK_MSG_ID_ATTITUDE_TM 110
-
-
-typedef struct __mavlink_attitude_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float roll; /*< [deg] Roll angle*/
- float pitch; /*< [deg] Pitch angle*/
- float yaw; /*< [deg] Yaw angle*/
- float quat_x; /*< Quaternion x component*/
- float quat_y; /*< Quaternion y component*/
- float quat_z; /*< Quaternion z component*/
- float quat_w; /*< Quaternion w component*/
- char sensor_name[20]; /*< Sensor name*/
-} mavlink_attitude_tm_t;
-
-#define MAVLINK_MSG_ID_ATTITUDE_TM_LEN 56
-#define MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN 56
-#define MAVLINK_MSG_ID_110_LEN 56
-#define MAVLINK_MSG_ID_110_MIN_LEN 56
-
-#define MAVLINK_MSG_ID_ATTITUDE_TM_CRC 6
-#define MAVLINK_MSG_ID_110_CRC 6
-
-#define MAVLINK_MSG_ATTITUDE_TM_FIELD_SENSOR_NAME_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ATTITUDE_TM { \
- 110, \
- "ATTITUDE_TM", \
- 9, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_attitude_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 36, offsetof(mavlink_attitude_tm_t, sensor_name) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_tm_t, roll) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_tm_t, pitch) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_tm_t, yaw) }, \
- { "quat_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_tm_t, quat_x) }, \
- { "quat_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_tm_t, quat_y) }, \
- { "quat_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_tm_t, quat_z) }, \
- { "quat_w", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_tm_t, quat_w) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ATTITUDE_TM { \
- "ATTITUDE_TM", \
- 9, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_attitude_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 36, offsetof(mavlink_attitude_tm_t, sensor_name) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_tm_t, roll) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_tm_t, pitch) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_tm_t, yaw) }, \
- { "quat_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_tm_t, quat_x) }, \
- { "quat_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_tm_t, quat_y) }, \
- { "quat_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_tm_t, quat_z) }, \
- { "quat_w", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_tm_t, quat_w) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a attitude_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param roll [deg] Roll angle
- * @param pitch [deg] Pitch angle
- * @param yaw [deg] Yaw angle
- * @param quat_x Quaternion x component
- * @param quat_y Quaternion y component
- * @param quat_z Quaternion z component
- * @param quat_w Quaternion w component
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_attitude_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_name, float roll, float pitch, float yaw, float quat_x, float quat_y, float quat_z, float quat_w)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ATTITUDE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, roll);
- _mav_put_float(buf, 12, pitch);
- _mav_put_float(buf, 16, yaw);
- _mav_put_float(buf, 20, quat_x);
- _mav_put_float(buf, 24, quat_y);
- _mav_put_float(buf, 28, quat_z);
- _mav_put_float(buf, 32, quat_w);
- _mav_put_char_array(buf, 36, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TM_LEN);
-#else
- mavlink_attitude_tm_t packet;
- packet.timestamp = timestamp;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.quat_x = quat_x;
- packet.quat_y = quat_y;
- packet.quat_z = quat_z;
- packet.quat_w = quat_w;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-}
-
-/**
- * @brief Pack a attitude_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param roll [deg] Roll angle
- * @param pitch [deg] Pitch angle
- * @param yaw [deg] Yaw angle
- * @param quat_x Quaternion x component
- * @param quat_y Quaternion y component
- * @param quat_z Quaternion z component
- * @param quat_w Quaternion w component
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_attitude_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_name,float roll,float pitch,float yaw,float quat_x,float quat_y,float quat_z,float quat_w)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ATTITUDE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, roll);
- _mav_put_float(buf, 12, pitch);
- _mav_put_float(buf, 16, yaw);
- _mav_put_float(buf, 20, quat_x);
- _mav_put_float(buf, 24, quat_y);
- _mav_put_float(buf, 28, quat_z);
- _mav_put_float(buf, 32, quat_w);
- _mav_put_char_array(buf, 36, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TM_LEN);
-#else
- mavlink_attitude_tm_t packet;
- packet.timestamp = timestamp;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.quat_x = quat_x;
- packet.quat_y = quat_y;
- packet.quat_z = quat_z;
- packet.quat_w = quat_w;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-}
-
-/**
- * @brief Encode a attitude_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_attitude_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_tm_t* attitude_tm)
-{
- return mavlink_msg_attitude_tm_pack(system_id, component_id, msg, attitude_tm->timestamp, attitude_tm->sensor_name, attitude_tm->roll, attitude_tm->pitch, attitude_tm->yaw, attitude_tm->quat_x, attitude_tm->quat_y, attitude_tm->quat_z, attitude_tm->quat_w);
-}
-
-/**
- * @brief Encode a attitude_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_attitude_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_tm_t* attitude_tm)
-{
- return mavlink_msg_attitude_tm_pack_chan(system_id, component_id, chan, msg, attitude_tm->timestamp, attitude_tm->sensor_name, attitude_tm->roll, attitude_tm->pitch, attitude_tm->yaw, attitude_tm->quat_x, attitude_tm->quat_y, attitude_tm->quat_z, attitude_tm->quat_w);
-}
-
-/**
- * @brief Send a attitude_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_name Sensor name
- * @param roll [deg] Roll angle
- * @param pitch [deg] Pitch angle
- * @param yaw [deg] Yaw angle
- * @param quat_x Quaternion x component
- * @param quat_y Quaternion y component
- * @param quat_z Quaternion z component
- * @param quat_w Quaternion w component
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_attitude_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float roll, float pitch, float yaw, float quat_x, float quat_y, float quat_z, float quat_w)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ATTITUDE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, roll);
- _mav_put_float(buf, 12, pitch);
- _mav_put_float(buf, 16, yaw);
- _mav_put_float(buf, 20, quat_x);
- _mav_put_float(buf, 24, quat_y);
- _mav_put_float(buf, 28, quat_z);
- _mav_put_float(buf, 32, quat_w);
- _mav_put_char_array(buf, 36, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TM, buf, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-#else
- mavlink_attitude_tm_t packet;
- packet.timestamp = timestamp;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.quat_x = quat_x;
- packet.quat_y = quat_y;
- packet.quat_z = quat_z;
- packet.quat_w = quat_w;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TM, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a attitude_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_attitude_tm_send_struct(mavlink_channel_t chan, const mavlink_attitude_tm_t* attitude_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_attitude_tm_send(chan, attitude_tm->timestamp, attitude_tm->sensor_name, attitude_tm->roll, attitude_tm->pitch, attitude_tm->yaw, attitude_tm->quat_x, attitude_tm->quat_y, attitude_tm->quat_z, attitude_tm->quat_w);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TM, (const char *)attitude_tm, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ATTITUDE_TM_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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float roll, float pitch, float yaw, float quat_x, float quat_y, float quat_z, float quat_w)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, roll);
- _mav_put_float(buf, 12, pitch);
- _mav_put_float(buf, 16, yaw);
- _mav_put_float(buf, 20, quat_x);
- _mav_put_float(buf, 24, quat_y);
- _mav_put_float(buf, 28, quat_z);
- _mav_put_float(buf, 32, quat_w);
- _mav_put_char_array(buf, 36, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TM, buf, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-#else
- mavlink_attitude_tm_t *packet = (mavlink_attitude_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->roll = roll;
- packet->pitch = pitch;
- packet->yaw = yaw;
- packet->quat_x = quat_x;
- packet->quat_y = quat_y;
- packet->quat_z = quat_z;
- packet->quat_w = quat_w;
- mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TM, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ATTITUDE_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from attitude_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_attitude_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_name from attitude_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_attitude_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
-{
- return _MAV_RETURN_char_array(msg, sensor_name, 20, 36);
-}
-
-/**
- * @brief Get field roll from attitude_tm message
- *
- * @return [deg] Roll angle
- */
-static inline float mavlink_msg_attitude_tm_get_roll(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field pitch from attitude_tm message
- *
- * @return [deg] Pitch angle
- */
-static inline float mavlink_msg_attitude_tm_get_pitch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field yaw from attitude_tm message
- *
- * @return [deg] Yaw angle
- */
-static inline float mavlink_msg_attitude_tm_get_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field quat_x from attitude_tm message
- *
- * @return Quaternion x component
- */
-static inline float mavlink_msg_attitude_tm_get_quat_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field quat_y from attitude_tm message
- *
- * @return Quaternion y component
- */
-static inline float mavlink_msg_attitude_tm_get_quat_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field quat_z from attitude_tm message
- *
- * @return Quaternion z component
- */
-static inline float mavlink_msg_attitude_tm_get_quat_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field quat_w from attitude_tm message
- *
- * @return Quaternion w component
- */
-static inline float mavlink_msg_attitude_tm_get_quat_w(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Decode a attitude_tm message into a struct
- *
- * @param msg The message to decode
- * @param attitude_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_attitude_tm_decode(const mavlink_message_t* msg, mavlink_attitude_tm_t* attitude_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- attitude_tm->timestamp = mavlink_msg_attitude_tm_get_timestamp(msg);
- attitude_tm->roll = mavlink_msg_attitude_tm_get_roll(msg);
- attitude_tm->pitch = mavlink_msg_attitude_tm_get_pitch(msg);
- attitude_tm->yaw = mavlink_msg_attitude_tm_get_yaw(msg);
- attitude_tm->quat_x = mavlink_msg_attitude_tm_get_quat_x(msg);
- attitude_tm->quat_y = mavlink_msg_attitude_tm_get_quat_y(msg);
- attitude_tm->quat_z = mavlink_msg_attitude_tm_get_quat_z(msg);
- attitude_tm->quat_w = mavlink_msg_attitude_tm_get_quat_w(msg);
- mavlink_msg_attitude_tm_get_sensor_name(msg, attitude_tm->sensor_name);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_TM_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_TM_LEN;
- memset(attitude_tm, 0, MAVLINK_MSG_ID_ATTITUDE_TM_LEN);
- memcpy(attitude_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_command_tc.h b/mavlink_lib/gemini/mavlink_msg_command_tc.h
deleted file mode 100644
index a4d0886b3f67df648cfd4ed0b8debc059ecfa272..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_command_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE COMMAND_TC PACKING
-
-#define MAVLINK_MSG_ID_COMMAND_TC 2
-
-
-typedef struct __mavlink_command_tc_t {
- uint8_t command_id; /*< A member of the MavCommandList enum*/
-} mavlink_command_tc_t;
-
-#define MAVLINK_MSG_ID_COMMAND_TC_LEN 1
-#define MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_2_LEN 1
-#define MAVLINK_MSG_ID_2_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_COMMAND_TC_CRC 198
-#define MAVLINK_MSG_ID_2_CRC 198
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_COMMAND_TC { \
- 2, \
- "COMMAND_TC", \
- 1, \
- { { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_command_tc_t, command_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_COMMAND_TC { \
- "COMMAND_TC", \
- 1, \
- { { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_command_tc_t, command_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a command_tc 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_id A member of the MavCommandList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_command_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_COMMAND_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_TC_LEN);
-#else
- mavlink_command_tc_t packet;
- packet.command_id = command_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_COMMAND_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-}
-
-/**
- * @brief Pack a command_tc 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_id A member of the MavCommandList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_command_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_COMMAND_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_TC_LEN);
-#else
- mavlink_command_tc_t packet;
- packet.command_id = command_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_COMMAND_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-}
-
-/**
- * @brief Encode a command_tc 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_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_command_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_tc_t* command_tc)
-{
- return mavlink_msg_command_tc_pack(system_id, component_id, msg, command_tc->command_id);
-}
-
-/**
- * @brief Encode a command_tc 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_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_command_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_tc_t* command_tc)
-{
- return mavlink_msg_command_tc_pack_chan(system_id, component_id, chan, msg, command_tc->command_id);
-}
-
-/**
- * @brief Send a command_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param command_id A member of the MavCommandList enum
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_command_tc_send(mavlink_channel_t chan, uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_COMMAND_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_TC, buf, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-#else
- mavlink_command_tc_t packet;
- packet.command_id = command_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_TC, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a command_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_command_tc_send_struct(mavlink_channel_t chan, const mavlink_command_tc_t* command_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_command_tc_send(chan, command_tc->command_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_TC, (const char *)command_tc, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_COMMAND_TC_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_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, command_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_TC, buf, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-#else
- mavlink_command_tc_t *packet = (mavlink_command_tc_t *)msgbuf;
- packet->command_id = command_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_TC, (const char *)packet, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE COMMAND_TC UNPACKING
-
-
-/**
- * @brief Get field command_id from command_tc message
- *
- * @return A member of the MavCommandList enum
- */
-static inline uint8_t mavlink_msg_command_tc_get_command_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a command_tc message into a struct
- *
- * @param msg The message to decode
- * @param command_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_command_tc_decode(const mavlink_message_t* msg, mavlink_command_tc_t* command_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- command_tc->command_id = mavlink_msg_command_tc_get_command_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_TC_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_TC_LEN;
- memset(command_tc, 0, MAVLINK_MSG_ID_COMMAND_TC_LEN);
- memcpy(command_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_conrig_state_tc.h b/mavlink_lib/gemini/mavlink_msg_conrig_state_tc.h
deleted file mode 100644
index 9f1ada850a2a7f233ba5f5e9ae41e55121488da2..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_conrig_state_tc.h
+++ /dev/null
@@ -1,363 +0,0 @@
-#pragma once
-// MESSAGE CONRIG_STATE_TC PACKING
-
-#define MAVLINK_MSG_ID_CONRIG_STATE_TC 19
-
-
-typedef struct __mavlink_conrig_state_tc_t {
- uint8_t ignition_btn; /*< Ignition button pressed*/
- uint8_t filling_valve_btn; /*< Open filling valve pressed*/
- uint8_t venting_valve_btn; /*< Open venting valve pressed*/
- uint8_t release_pressure_btn; /*< Release filling line pressure pressed*/
- uint8_t quick_connector_btn; /*< Detach quick connector pressed*/
- uint8_t start_tars_btn; /*< Startup TARS pressed*/
- uint8_t arm_switch; /*< Arming switch state*/
-} mavlink_conrig_state_tc_t;
-
-#define MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN 7
-#define MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN 7
-#define MAVLINK_MSG_ID_19_LEN 7
-#define MAVLINK_MSG_ID_19_MIN_LEN 7
-
-#define MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC 65
-#define MAVLINK_MSG_ID_19_CRC 65
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC { \
- 19, \
- "CONRIG_STATE_TC", \
- 7, \
- { { "ignition_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_conrig_state_tc_t, ignition_btn) }, \
- { "filling_valve_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_conrig_state_tc_t, filling_valve_btn) }, \
- { "venting_valve_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_conrig_state_tc_t, venting_valve_btn) }, \
- { "release_pressure_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_conrig_state_tc_t, release_pressure_btn) }, \
- { "quick_connector_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_conrig_state_tc_t, quick_connector_btn) }, \
- { "start_tars_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_conrig_state_tc_t, start_tars_btn) }, \
- { "arm_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_conrig_state_tc_t, arm_switch) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC { \
- "CONRIG_STATE_TC", \
- 7, \
- { { "ignition_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_conrig_state_tc_t, ignition_btn) }, \
- { "filling_valve_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_conrig_state_tc_t, filling_valve_btn) }, \
- { "venting_valve_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_conrig_state_tc_t, venting_valve_btn) }, \
- { "release_pressure_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_conrig_state_tc_t, release_pressure_btn) }, \
- { "quick_connector_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_conrig_state_tc_t, quick_connector_btn) }, \
- { "start_tars_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_conrig_state_tc_t, start_tars_btn) }, \
- { "arm_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_conrig_state_tc_t, arm_switch) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a conrig_state_tc 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 ignition_btn Ignition button pressed
- * @param filling_valve_btn Open filling valve pressed
- * @param venting_valve_btn Open venting valve pressed
- * @param release_pressure_btn Release filling line pressure pressed
- * @param quick_connector_btn Detach quick connector pressed
- * @param start_tars_btn Startup TARS pressed
- * @param arm_switch Arming switch state
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_conrig_state_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t ignition_btn, uint8_t filling_valve_btn, uint8_t venting_valve_btn, uint8_t release_pressure_btn, uint8_t quick_connector_btn, uint8_t start_tars_btn, uint8_t arm_switch)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN];
- _mav_put_uint8_t(buf, 0, ignition_btn);
- _mav_put_uint8_t(buf, 1, filling_valve_btn);
- _mav_put_uint8_t(buf, 2, venting_valve_btn);
- _mav_put_uint8_t(buf, 3, release_pressure_btn);
- _mav_put_uint8_t(buf, 4, quick_connector_btn);
- _mav_put_uint8_t(buf, 5, start_tars_btn);
- _mav_put_uint8_t(buf, 6, arm_switch);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN);
-#else
- mavlink_conrig_state_tc_t packet;
- packet.ignition_btn = ignition_btn;
- packet.filling_valve_btn = filling_valve_btn;
- packet.venting_valve_btn = venting_valve_btn;
- packet.release_pressure_btn = release_pressure_btn;
- packet.quick_connector_btn = quick_connector_btn;
- packet.start_tars_btn = start_tars_btn;
- packet.arm_switch = arm_switch;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_CONRIG_STATE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC);
-}
-
-/**
- * @brief Pack a conrig_state_tc 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 ignition_btn Ignition button pressed
- * @param filling_valve_btn Open filling valve pressed
- * @param venting_valve_btn Open venting valve pressed
- * @param release_pressure_btn Release filling line pressure pressed
- * @param quick_connector_btn Detach quick connector pressed
- * @param start_tars_btn Startup TARS pressed
- * @param arm_switch Arming switch state
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_conrig_state_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t ignition_btn,uint8_t filling_valve_btn,uint8_t venting_valve_btn,uint8_t release_pressure_btn,uint8_t quick_connector_btn,uint8_t start_tars_btn,uint8_t arm_switch)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN];
- _mav_put_uint8_t(buf, 0, ignition_btn);
- _mav_put_uint8_t(buf, 1, filling_valve_btn);
- _mav_put_uint8_t(buf, 2, venting_valve_btn);
- _mav_put_uint8_t(buf, 3, release_pressure_btn);
- _mav_put_uint8_t(buf, 4, quick_connector_btn);
- _mav_put_uint8_t(buf, 5, start_tars_btn);
- _mav_put_uint8_t(buf, 6, arm_switch);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN);
-#else
- mavlink_conrig_state_tc_t packet;
- packet.ignition_btn = ignition_btn;
- packet.filling_valve_btn = filling_valve_btn;
- packet.venting_valve_btn = venting_valve_btn;
- packet.release_pressure_btn = release_pressure_btn;
- packet.quick_connector_btn = quick_connector_btn;
- packet.start_tars_btn = start_tars_btn;
- packet.arm_switch = arm_switch;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_CONRIG_STATE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC);
-}
-
-/**
- * @brief Encode a conrig_state_tc 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 conrig_state_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_conrig_state_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_conrig_state_tc_t* conrig_state_tc)
-{
- return mavlink_msg_conrig_state_tc_pack(system_id, component_id, msg, conrig_state_tc->ignition_btn, conrig_state_tc->filling_valve_btn, conrig_state_tc->venting_valve_btn, conrig_state_tc->release_pressure_btn, conrig_state_tc->quick_connector_btn, conrig_state_tc->start_tars_btn, conrig_state_tc->arm_switch);
-}
-
-/**
- * @brief Encode a conrig_state_tc 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 conrig_state_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_conrig_state_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_conrig_state_tc_t* conrig_state_tc)
-{
- return mavlink_msg_conrig_state_tc_pack_chan(system_id, component_id, chan, msg, conrig_state_tc->ignition_btn, conrig_state_tc->filling_valve_btn, conrig_state_tc->venting_valve_btn, conrig_state_tc->release_pressure_btn, conrig_state_tc->quick_connector_btn, conrig_state_tc->start_tars_btn, conrig_state_tc->arm_switch);
-}
-
-/**
- * @brief Send a conrig_state_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param ignition_btn Ignition button pressed
- * @param filling_valve_btn Open filling valve pressed
- * @param venting_valve_btn Open venting valve pressed
- * @param release_pressure_btn Release filling line pressure pressed
- * @param quick_connector_btn Detach quick connector pressed
- * @param start_tars_btn Startup TARS pressed
- * @param arm_switch Arming switch state
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_conrig_state_tc_send(mavlink_channel_t chan, uint8_t ignition_btn, uint8_t filling_valve_btn, uint8_t venting_valve_btn, uint8_t release_pressure_btn, uint8_t quick_connector_btn, uint8_t start_tars_btn, uint8_t arm_switch)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN];
- _mav_put_uint8_t(buf, 0, ignition_btn);
- _mav_put_uint8_t(buf, 1, filling_valve_btn);
- _mav_put_uint8_t(buf, 2, venting_valve_btn);
- _mav_put_uint8_t(buf, 3, release_pressure_btn);
- _mav_put_uint8_t(buf, 4, quick_connector_btn);
- _mav_put_uint8_t(buf, 5, start_tars_btn);
- _mav_put_uint8_t(buf, 6, arm_switch);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONRIG_STATE_TC, buf, MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC);
-#else
- mavlink_conrig_state_tc_t packet;
- packet.ignition_btn = ignition_btn;
- packet.filling_valve_btn = filling_valve_btn;
- packet.venting_valve_btn = venting_valve_btn;
- packet.release_pressure_btn = release_pressure_btn;
- packet.quick_connector_btn = quick_connector_btn;
- packet.start_tars_btn = start_tars_btn;
- packet.arm_switch = arm_switch;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONRIG_STATE_TC, (const char *)&packet, MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a conrig_state_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_conrig_state_tc_send_struct(mavlink_channel_t chan, const mavlink_conrig_state_tc_t* conrig_state_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_conrig_state_tc_send(chan, conrig_state_tc->ignition_btn, conrig_state_tc->filling_valve_btn, conrig_state_tc->venting_valve_btn, conrig_state_tc->release_pressure_btn, conrig_state_tc->quick_connector_btn, conrig_state_tc->start_tars_btn, conrig_state_tc->arm_switch);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONRIG_STATE_TC, (const char *)conrig_state_tc, MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_CONRIG_STATE_TC_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_conrig_state_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t ignition_btn, uint8_t filling_valve_btn, uint8_t venting_valve_btn, uint8_t release_pressure_btn, uint8_t quick_connector_btn, uint8_t start_tars_btn, uint8_t arm_switch)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, ignition_btn);
- _mav_put_uint8_t(buf, 1, filling_valve_btn);
- _mav_put_uint8_t(buf, 2, venting_valve_btn);
- _mav_put_uint8_t(buf, 3, release_pressure_btn);
- _mav_put_uint8_t(buf, 4, quick_connector_btn);
- _mav_put_uint8_t(buf, 5, start_tars_btn);
- _mav_put_uint8_t(buf, 6, arm_switch);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONRIG_STATE_TC, buf, MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC);
-#else
- mavlink_conrig_state_tc_t *packet = (mavlink_conrig_state_tc_t *)msgbuf;
- packet->ignition_btn = ignition_btn;
- packet->filling_valve_btn = filling_valve_btn;
- packet->venting_valve_btn = venting_valve_btn;
- packet->release_pressure_btn = release_pressure_btn;
- packet->quick_connector_btn = quick_connector_btn;
- packet->start_tars_btn = start_tars_btn;
- packet->arm_switch = arm_switch;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONRIG_STATE_TC, (const char *)packet, MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE CONRIG_STATE_TC UNPACKING
-
-
-/**
- * @brief Get field ignition_btn from conrig_state_tc message
- *
- * @return Ignition button pressed
- */
-static inline uint8_t mavlink_msg_conrig_state_tc_get_ignition_btn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field filling_valve_btn from conrig_state_tc message
- *
- * @return Open filling valve pressed
- */
-static inline uint8_t mavlink_msg_conrig_state_tc_get_filling_valve_btn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Get field venting_valve_btn from conrig_state_tc message
- *
- * @return Open venting valve pressed
- */
-static inline uint8_t mavlink_msg_conrig_state_tc_get_venting_valve_btn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 2);
-}
-
-/**
- * @brief Get field release_pressure_btn from conrig_state_tc message
- *
- * @return Release filling line pressure pressed
- */
-static inline uint8_t mavlink_msg_conrig_state_tc_get_release_pressure_btn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 3);
-}
-
-/**
- * @brief Get field quick_connector_btn from conrig_state_tc message
- *
- * @return Detach quick connector pressed
- */
-static inline uint8_t mavlink_msg_conrig_state_tc_get_quick_connector_btn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 4);
-}
-
-/**
- * @brief Get field start_tars_btn from conrig_state_tc message
- *
- * @return Startup TARS pressed
- */
-static inline uint8_t mavlink_msg_conrig_state_tc_get_start_tars_btn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 5);
-}
-
-/**
- * @brief Get field arm_switch from conrig_state_tc message
- *
- * @return Arming switch state
- */
-static inline uint8_t mavlink_msg_conrig_state_tc_get_arm_switch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 6);
-}
-
-/**
- * @brief Decode a conrig_state_tc message into a struct
- *
- * @param msg The message to decode
- * @param conrig_state_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_conrig_state_tc_decode(const mavlink_message_t* msg, mavlink_conrig_state_tc_t* conrig_state_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- conrig_state_tc->ignition_btn = mavlink_msg_conrig_state_tc_get_ignition_btn(msg);
- conrig_state_tc->filling_valve_btn = mavlink_msg_conrig_state_tc_get_filling_valve_btn(msg);
- conrig_state_tc->venting_valve_btn = mavlink_msg_conrig_state_tc_get_venting_valve_btn(msg);
- conrig_state_tc->release_pressure_btn = mavlink_msg_conrig_state_tc_get_release_pressure_btn(msg);
- conrig_state_tc->quick_connector_btn = mavlink_msg_conrig_state_tc_get_quick_connector_btn(msg);
- conrig_state_tc->start_tars_btn = mavlink_msg_conrig_state_tc_get_start_tars_btn(msg);
- conrig_state_tc->arm_switch = mavlink_msg_conrig_state_tc_get_arm_switch(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN? msg->len : MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN;
- memset(conrig_state_tc, 0, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN);
- memcpy(conrig_state_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_current_tm.h b/mavlink_lib/gemini/mavlink_msg_current_tm.h
deleted file mode 100644
index a63460b470e330fb90ada85f4cf61a1ec67401b2..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_current_tm.h
+++ /dev/null
@@ -1,255 +0,0 @@
-#pragma once
-// MESSAGE CURRENT_TM PACKING
-
-#define MAVLINK_MSG_ID_CURRENT_TM 107
-
-
-typedef struct __mavlink_current_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float current; /*< [A] Current*/
- char sensor_name[20]; /*< Sensor name*/
-} mavlink_current_tm_t;
-
-#define MAVLINK_MSG_ID_CURRENT_TM_LEN 32
-#define MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_107_LEN 32
-#define MAVLINK_MSG_ID_107_MIN_LEN 32
-
-#define MAVLINK_MSG_ID_CURRENT_TM_CRC 212
-#define MAVLINK_MSG_ID_107_CRC 212
-
-#define MAVLINK_MSG_CURRENT_TM_FIELD_SENSOR_NAME_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_CURRENT_TM { \
- 107, \
- "CURRENT_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_current_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_current_tm_t, sensor_name) }, \
- { "current", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_current_tm_t, current) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_CURRENT_TM { \
- "CURRENT_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_current_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_current_tm_t, sensor_name) }, \
- { "current", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_current_tm_t, current) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a current_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param current [A] Current
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_current_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_name, float current)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CURRENT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, current);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CURRENT_TM_LEN);
-#else
- mavlink_current_tm_t packet;
- packet.timestamp = timestamp;
- packet.current = current;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CURRENT_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_CURRENT_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-}
-
-/**
- * @brief Pack a current_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param current [A] Current
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_current_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_name,float current)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CURRENT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, current);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CURRENT_TM_LEN);
-#else
- mavlink_current_tm_t packet;
- packet.timestamp = timestamp;
- packet.current = current;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CURRENT_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_CURRENT_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-}
-
-/**
- * @brief Encode a current_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_current_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_current_tm_t* current_tm)
-{
- return mavlink_msg_current_tm_pack(system_id, component_id, msg, current_tm->timestamp, current_tm->sensor_name, current_tm->current);
-}
-
-/**
- * @brief Encode a current_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_current_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_current_tm_t* current_tm)
-{
- return mavlink_msg_current_tm_pack_chan(system_id, component_id, chan, msg, current_tm->timestamp, current_tm->sensor_name, current_tm->current);
-}
-
-/**
- * @brief Send a current_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_name Sensor name
- * @param current [A] Current
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_current_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float current)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CURRENT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, current);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CURRENT_TM, buf, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-#else
- mavlink_current_tm_t packet;
- packet.timestamp = timestamp;
- packet.current = current;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CURRENT_TM, (const char *)&packet, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a current_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_current_tm_send_struct(mavlink_channel_t chan, const mavlink_current_tm_t* current_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_current_tm_send(chan, current_tm->timestamp, current_tm->sensor_name, current_tm->current);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CURRENT_TM, (const char *)current_tm, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_CURRENT_TM_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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float current)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, current);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CURRENT_TM, buf, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-#else
- mavlink_current_tm_t *packet = (mavlink_current_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->current = current;
- mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CURRENT_TM, (const char *)packet, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE CURRENT_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from current_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_current_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_name from current_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_current_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
-{
- return _MAV_RETURN_char_array(msg, sensor_name, 20, 12);
-}
-
-/**
- * @brief Get field current from current_tm message
- *
- * @return [A] Current
- */
-static inline float mavlink_msg_current_tm_get_current(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Decode a current_tm message into a struct
- *
- * @param msg The message to decode
- * @param current_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_current_tm_decode(const mavlink_message_t* msg, mavlink_current_tm_t* current_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- current_tm->timestamp = mavlink_msg_current_tm_get_timestamp(msg);
- current_tm->current = mavlink_msg_current_tm_get_current(msg);
- mavlink_msg_current_tm_get_sensor_name(msg, current_tm->sensor_name);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_CURRENT_TM_LEN? msg->len : MAVLINK_MSG_ID_CURRENT_TM_LEN;
- memset(current_tm, 0, MAVLINK_MSG_ID_CURRENT_TM_LEN);
- memcpy(current_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_fsm_tm.h b/mavlink_lib/gemini/mavlink_msg_fsm_tm.h
deleted file mode 100644
index cc60afc359614defcc489ad0497c01e43dfc908a..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_fsm_tm.h
+++ /dev/null
@@ -1,363 +0,0 @@
-#pragma once
-// MESSAGE FSM_TM PACKING
-
-#define MAVLINK_MSG_ID_FSM_TM 201
-
-
-typedef struct __mavlink_fsm_tm_t {
- uint64_t timestamp; /*< [us] Timestamp*/
- uint8_t ada_state; /*< Apogee Detection Algorithm state*/
- uint8_t abk_state; /*< Air Brakes state*/
- uint8_t dpl_state; /*< Deployment state*/
- uint8_t fmm_state; /*< Flight Mode Manager state*/
- uint8_t nas_state; /*< Navigation and Attitude System state*/
- uint8_t wes_state; /*< Wind Estimation System state*/
-} mavlink_fsm_tm_t;
-
-#define MAVLINK_MSG_ID_FSM_TM_LEN 14
-#define MAVLINK_MSG_ID_FSM_TM_MIN_LEN 14
-#define MAVLINK_MSG_ID_201_LEN 14
-#define MAVLINK_MSG_ID_201_MIN_LEN 14
-
-#define MAVLINK_MSG_ID_FSM_TM_CRC 242
-#define MAVLINK_MSG_ID_201_CRC 242
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_FSM_TM { \
- 201, \
- "FSM_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_fsm_tm_t, timestamp) }, \
- { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fsm_tm_t, ada_state) }, \
- { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_fsm_tm_t, abk_state) }, \
- { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_fsm_tm_t, dpl_state) }, \
- { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_fsm_tm_t, fmm_state) }, \
- { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_fsm_tm_t, nas_state) }, \
- { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_fsm_tm_t, wes_state) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_FSM_TM { \
- "FSM_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_fsm_tm_t, timestamp) }, \
- { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fsm_tm_t, ada_state) }, \
- { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_fsm_tm_t, abk_state) }, \
- { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_fsm_tm_t, dpl_state) }, \
- { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_fsm_tm_t, fmm_state) }, \
- { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_fsm_tm_t, nas_state) }, \
- { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_fsm_tm_t, wes_state) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a fsm_tm 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
- * @param ada_state Apogee Detection Algorithm state
- * @param abk_state Air Brakes state
- * @param dpl_state Deployment state
- * @param fmm_state Flight Mode Manager state
- * @param nas_state Navigation and Attitude System state
- * @param wes_state Wind Estimation System state
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_fsm_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t ada_state, uint8_t abk_state, uint8_t dpl_state, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_FSM_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, ada_state);
- _mav_put_uint8_t(buf, 9, abk_state);
- _mav_put_uint8_t(buf, 10, dpl_state);
- _mav_put_uint8_t(buf, 11, fmm_state);
- _mav_put_uint8_t(buf, 12, nas_state);
- _mav_put_uint8_t(buf, 13, wes_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FSM_TM_LEN);
-#else
- mavlink_fsm_tm_t packet;
- packet.timestamp = timestamp;
- packet.ada_state = ada_state;
- packet.abk_state = abk_state;
- packet.dpl_state = dpl_state;
- packet.fmm_state = fmm_state;
- packet.nas_state = nas_state;
- packet.wes_state = wes_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FSM_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_FSM_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-}
-
-/**
- * @brief Pack a fsm_tm 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
- * @param ada_state Apogee Detection Algorithm state
- * @param abk_state Air Brakes state
- * @param dpl_state Deployment state
- * @param fmm_state Flight Mode Manager state
- * @param nas_state Navigation and Attitude System state
- * @param wes_state Wind Estimation System state
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_fsm_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t ada_state,uint8_t abk_state,uint8_t dpl_state,uint8_t fmm_state,uint8_t nas_state,uint8_t wes_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_FSM_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, ada_state);
- _mav_put_uint8_t(buf, 9, abk_state);
- _mav_put_uint8_t(buf, 10, dpl_state);
- _mav_put_uint8_t(buf, 11, fmm_state);
- _mav_put_uint8_t(buf, 12, nas_state);
- _mav_put_uint8_t(buf, 13, wes_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FSM_TM_LEN);
-#else
- mavlink_fsm_tm_t packet;
- packet.timestamp = timestamp;
- packet.ada_state = ada_state;
- packet.abk_state = abk_state;
- packet.dpl_state = dpl_state;
- packet.fmm_state = fmm_state;
- packet.nas_state = nas_state;
- packet.wes_state = wes_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FSM_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_FSM_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-}
-
-/**
- * @brief Encode a fsm_tm 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 fsm_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_fsm_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fsm_tm_t* fsm_tm)
-{
- return mavlink_msg_fsm_tm_pack(system_id, component_id, msg, fsm_tm->timestamp, fsm_tm->ada_state, fsm_tm->abk_state, fsm_tm->dpl_state, fsm_tm->fmm_state, fsm_tm->nas_state, fsm_tm->wes_state);
-}
-
-/**
- * @brief Encode a fsm_tm 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 fsm_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_fsm_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fsm_tm_t* fsm_tm)
-{
- return mavlink_msg_fsm_tm_pack_chan(system_id, component_id, chan, msg, fsm_tm->timestamp, fsm_tm->ada_state, fsm_tm->abk_state, fsm_tm->dpl_state, fsm_tm->fmm_state, fsm_tm->nas_state, fsm_tm->wes_state);
-}
-
-/**
- * @brief Send a fsm_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp
- * @param ada_state Apogee Detection Algorithm state
- * @param abk_state Air Brakes state
- * @param dpl_state Deployment state
- * @param fmm_state Flight Mode Manager state
- * @param nas_state Navigation and Attitude System state
- * @param wes_state Wind Estimation System state
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_fsm_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t abk_state, uint8_t dpl_state, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_FSM_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, ada_state);
- _mav_put_uint8_t(buf, 9, abk_state);
- _mav_put_uint8_t(buf, 10, dpl_state);
- _mav_put_uint8_t(buf, 11, fmm_state);
- _mav_put_uint8_t(buf, 12, nas_state);
- _mav_put_uint8_t(buf, 13, wes_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, buf, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-#else
- mavlink_fsm_tm_t packet;
- packet.timestamp = timestamp;
- packet.ada_state = ada_state;
- packet.abk_state = abk_state;
- packet.dpl_state = dpl_state;
- packet.fmm_state = fmm_state;
- packet.nas_state = nas_state;
- packet.wes_state = wes_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, (const char *)&packet, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a fsm_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_fsm_tm_send_struct(mavlink_channel_t chan, const mavlink_fsm_tm_t* fsm_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_fsm_tm_send(chan, fsm_tm->timestamp, fsm_tm->ada_state, fsm_tm->abk_state, fsm_tm->dpl_state, fsm_tm->fmm_state, fsm_tm->nas_state, fsm_tm->wes_state);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, (const char *)fsm_tm, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_FSM_TM_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_fsm_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t abk_state, uint8_t dpl_state, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, ada_state);
- _mav_put_uint8_t(buf, 9, abk_state);
- _mav_put_uint8_t(buf, 10, dpl_state);
- _mav_put_uint8_t(buf, 11, fmm_state);
- _mav_put_uint8_t(buf, 12, nas_state);
- _mav_put_uint8_t(buf, 13, wes_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, buf, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-#else
- mavlink_fsm_tm_t *packet = (mavlink_fsm_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->ada_state = ada_state;
- packet->abk_state = abk_state;
- packet->dpl_state = dpl_state;
- packet->fmm_state = fmm_state;
- packet->nas_state = nas_state;
- packet->wes_state = wes_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, (const char *)packet, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE FSM_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from fsm_tm message
- *
- * @return [us] Timestamp
- */
-static inline uint64_t mavlink_msg_fsm_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field ada_state from fsm_tm message
- *
- * @return Apogee Detection Algorithm state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_ada_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 8);
-}
-
-/**
- * @brief Get field abk_state from fsm_tm message
- *
- * @return Air Brakes state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_abk_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 9);
-}
-
-/**
- * @brief Get field dpl_state from fsm_tm message
- *
- * @return Deployment state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_dpl_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 10);
-}
-
-/**
- * @brief Get field fmm_state from fsm_tm message
- *
- * @return Flight Mode Manager state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_fmm_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 11);
-}
-
-/**
- * @brief Get field nas_state from fsm_tm message
- *
- * @return Navigation and Attitude System state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_nas_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 12);
-}
-
-/**
- * @brief Get field wes_state from fsm_tm message
- *
- * @return Wind Estimation System state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_wes_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 13);
-}
-
-/**
- * @brief Decode a fsm_tm message into a struct
- *
- * @param msg The message to decode
- * @param fsm_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_fsm_tm_decode(const mavlink_message_t* msg, mavlink_fsm_tm_t* fsm_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- fsm_tm->timestamp = mavlink_msg_fsm_tm_get_timestamp(msg);
- fsm_tm->ada_state = mavlink_msg_fsm_tm_get_ada_state(msg);
- fsm_tm->abk_state = mavlink_msg_fsm_tm_get_abk_state(msg);
- fsm_tm->dpl_state = mavlink_msg_fsm_tm_get_dpl_state(msg);
- fsm_tm->fmm_state = mavlink_msg_fsm_tm_get_fmm_state(msg);
- fsm_tm->nas_state = mavlink_msg_fsm_tm_get_nas_state(msg);
- fsm_tm->wes_state = mavlink_msg_fsm_tm_get_wes_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_FSM_TM_LEN? msg->len : MAVLINK_MSG_ID_FSM_TM_LEN;
- memset(fsm_tm, 0, MAVLINK_MSG_ID_FSM_TM_LEN);
- memcpy(fsm_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_gps_tm.h b/mavlink_lib/gemini/mavlink_msg_gps_tm.h
deleted file mode 100644
index 96f4891e5530a812d22ae2891cded1543bfddd74..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_gps_tm.h
+++ /dev/null
@@ -1,480 +0,0 @@
-#pragma once
-// MESSAGE GPS_TM PACKING
-
-#define MAVLINK_MSG_ID_GPS_TM 102
-
-
-typedef struct __mavlink_gps_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- double latitude; /*< [deg] Latitude*/
- double longitude; /*< [deg] Longitude*/
- double height; /*< [m] Altitude*/
- float vel_north; /*< [m/s] Velocity in NED frame (north)*/
- float vel_east; /*< [m/s] Velocity in NED frame (east)*/
- float vel_down; /*< [m/s] Velocity in NED frame (down)*/
- float speed; /*< [m/s] Speed*/
- float track; /*< [deg] Track*/
- char sensor_name[20]; /*< Sensor name*/
- uint8_t fix; /*< Wether the GPS has a FIX*/
- uint8_t n_satellites; /*< Number of connected satellites*/
-} mavlink_gps_tm_t;
-
-#define MAVLINK_MSG_ID_GPS_TM_LEN 74
-#define MAVLINK_MSG_ID_GPS_TM_MIN_LEN 74
-#define MAVLINK_MSG_ID_102_LEN 74
-#define MAVLINK_MSG_ID_102_MIN_LEN 74
-
-#define MAVLINK_MSG_ID_GPS_TM_CRC 57
-#define MAVLINK_MSG_ID_102_CRC 57
-
-#define MAVLINK_MSG_GPS_TM_FIELD_SENSOR_NAME_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_GPS_TM { \
- 102, \
- "GPS_TM", \
- 12, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 52, offsetof(mavlink_gps_tm_t, sensor_name) }, \
- { "fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 72, offsetof(mavlink_gps_tm_t, fix) }, \
- { "latitude", NULL, MAVLINK_TYPE_DOUBLE, 0, 8, offsetof(mavlink_gps_tm_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_DOUBLE, 0, 16, offsetof(mavlink_gps_tm_t, longitude) }, \
- { "height", NULL, MAVLINK_TYPE_DOUBLE, 0, 24, offsetof(mavlink_gps_tm_t, height) }, \
- { "vel_north", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_tm_t, vel_north) }, \
- { "vel_east", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gps_tm_t, vel_east) }, \
- { "vel_down", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gps_tm_t, vel_down) }, \
- { "speed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_tm_t, speed) }, \
- { "track", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_tm_t, track) }, \
- { "n_satellites", NULL, MAVLINK_TYPE_UINT8_T, 0, 73, offsetof(mavlink_gps_tm_t, n_satellites) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_GPS_TM { \
- "GPS_TM", \
- 12, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 52, offsetof(mavlink_gps_tm_t, sensor_name) }, \
- { "fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 72, offsetof(mavlink_gps_tm_t, fix) }, \
- { "latitude", NULL, MAVLINK_TYPE_DOUBLE, 0, 8, offsetof(mavlink_gps_tm_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_DOUBLE, 0, 16, offsetof(mavlink_gps_tm_t, longitude) }, \
- { "height", NULL, MAVLINK_TYPE_DOUBLE, 0, 24, offsetof(mavlink_gps_tm_t, height) }, \
- { "vel_north", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_tm_t, vel_north) }, \
- { "vel_east", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gps_tm_t, vel_east) }, \
- { "vel_down", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gps_tm_t, vel_down) }, \
- { "speed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_tm_t, speed) }, \
- { "track", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_tm_t, track) }, \
- { "n_satellites", NULL, MAVLINK_TYPE_UINT8_T, 0, 73, offsetof(mavlink_gps_tm_t, n_satellites) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a gps_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param fix Wether the GPS has a FIX
- * @param latitude [deg] Latitude
- * @param longitude [deg] Longitude
- * @param height [m] Altitude
- * @param vel_north [m/s] Velocity in NED frame (north)
- * @param vel_east [m/s] Velocity in NED frame (east)
- * @param vel_down [m/s] Velocity in NED frame (down)
- * @param speed [m/s] Speed
- * @param track [deg] Track
- * @param n_satellites Number of connected satellites
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_gps_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_name, uint8_t fix, double latitude, double longitude, double height, float vel_north, float vel_east, float vel_down, float speed, float track, uint8_t n_satellites)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GPS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, latitude);
- _mav_put_double(buf, 16, longitude);
- _mav_put_double(buf, 24, height);
- _mav_put_float(buf, 32, vel_north);
- _mav_put_float(buf, 36, vel_east);
- _mav_put_float(buf, 40, vel_down);
- _mav_put_float(buf, 44, speed);
- _mav_put_float(buf, 48, track);
- _mav_put_uint8_t(buf, 72, fix);
- _mav_put_uint8_t(buf, 73, n_satellites);
- _mav_put_char_array(buf, 52, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_TM_LEN);
-#else
- mavlink_gps_tm_t packet;
- packet.timestamp = timestamp;
- packet.latitude = latitude;
- packet.longitude = longitude;
- packet.height = height;
- packet.vel_north = vel_north;
- packet.vel_east = vel_east;
- packet.vel_down = vel_down;
- packet.speed = speed;
- packet.track = track;
- packet.fix = fix;
- packet.n_satellites = n_satellites;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_GPS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-}
-
-/**
- * @brief Pack a gps_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param fix Wether the GPS has a FIX
- * @param latitude [deg] Latitude
- * @param longitude [deg] Longitude
- * @param height [m] Altitude
- * @param vel_north [m/s] Velocity in NED frame (north)
- * @param vel_east [m/s] Velocity in NED frame (east)
- * @param vel_down [m/s] Velocity in NED frame (down)
- * @param speed [m/s] Speed
- * @param track [deg] Track
- * @param n_satellites Number of connected satellites
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_gps_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_name,uint8_t fix,double latitude,double longitude,double height,float vel_north,float vel_east,float vel_down,float speed,float track,uint8_t n_satellites)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GPS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, latitude);
- _mav_put_double(buf, 16, longitude);
- _mav_put_double(buf, 24, height);
- _mav_put_float(buf, 32, vel_north);
- _mav_put_float(buf, 36, vel_east);
- _mav_put_float(buf, 40, vel_down);
- _mav_put_float(buf, 44, speed);
- _mav_put_float(buf, 48, track);
- _mav_put_uint8_t(buf, 72, fix);
- _mav_put_uint8_t(buf, 73, n_satellites);
- _mav_put_char_array(buf, 52, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_TM_LEN);
-#else
- mavlink_gps_tm_t packet;
- packet.timestamp = timestamp;
- packet.latitude = latitude;
- packet.longitude = longitude;
- packet.height = height;
- packet.vel_north = vel_north;
- packet.vel_east = vel_east;
- packet.vel_down = vel_down;
- packet.speed = speed;
- packet.track = track;
- packet.fix = fix;
- packet.n_satellites = n_satellites;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_GPS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-}
-
-/**
- * @brief Encode a gps_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_gps_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_tm_t* gps_tm)
-{
- return mavlink_msg_gps_tm_pack(system_id, component_id, msg, gps_tm->timestamp, gps_tm->sensor_name, gps_tm->fix, gps_tm->latitude, gps_tm->longitude, gps_tm->height, gps_tm->vel_north, gps_tm->vel_east, gps_tm->vel_down, gps_tm->speed, gps_tm->track, gps_tm->n_satellites);
-}
-
-/**
- * @brief Encode a gps_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_gps_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_tm_t* gps_tm)
-{
- return mavlink_msg_gps_tm_pack_chan(system_id, component_id, chan, msg, gps_tm->timestamp, gps_tm->sensor_name, gps_tm->fix, gps_tm->latitude, gps_tm->longitude, gps_tm->height, gps_tm->vel_north, gps_tm->vel_east, gps_tm->vel_down, gps_tm->speed, gps_tm->track, gps_tm->n_satellites);
-}
-
-/**
- * @brief Send a gps_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_name Sensor name
- * @param fix Wether the GPS has a FIX
- * @param latitude [deg] Latitude
- * @param longitude [deg] Longitude
- * @param height [m] Altitude
- * @param vel_north [m/s] Velocity in NED frame (north)
- * @param vel_east [m/s] Velocity in NED frame (east)
- * @param vel_down [m/s] Velocity in NED frame (down)
- * @param speed [m/s] Speed
- * @param track [deg] Track
- * @param n_satellites Number of connected satellites
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_gps_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, uint8_t fix, double latitude, double longitude, double height, float vel_north, float vel_east, float vel_down, float speed, float track, uint8_t n_satellites)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GPS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, latitude);
- _mav_put_double(buf, 16, longitude);
- _mav_put_double(buf, 24, height);
- _mav_put_float(buf, 32, vel_north);
- _mav_put_float(buf, 36, vel_east);
- _mav_put_float(buf, 40, vel_down);
- _mav_put_float(buf, 44, speed);
- _mav_put_float(buf, 48, track);
- _mav_put_uint8_t(buf, 72, fix);
- _mav_put_uint8_t(buf, 73, n_satellites);
- _mav_put_char_array(buf, 52, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, buf, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#else
- mavlink_gps_tm_t packet;
- packet.timestamp = timestamp;
- packet.latitude = latitude;
- packet.longitude = longitude;
- packet.height = height;
- packet.vel_north = vel_north;
- packet.vel_east = vel_east;
- packet.vel_down = vel_down;
- packet.speed = speed;
- packet.track = track;
- packet.fix = fix;
- packet.n_satellites = n_satellites;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, (const char *)&packet, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a gps_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_gps_tm_send_struct(mavlink_channel_t chan, const mavlink_gps_tm_t* gps_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_gps_tm_send(chan, gps_tm->timestamp, gps_tm->sensor_name, gps_tm->fix, gps_tm->latitude, gps_tm->longitude, gps_tm->height, gps_tm->vel_north, gps_tm->vel_east, gps_tm->vel_down, gps_tm->speed, gps_tm->track, gps_tm->n_satellites);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, (const char *)gps_tm, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_GPS_TM_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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, uint8_t fix, double latitude, double longitude, double height, float vel_north, float vel_east, float vel_down, float speed, float track, uint8_t n_satellites)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, latitude);
- _mav_put_double(buf, 16, longitude);
- _mav_put_double(buf, 24, height);
- _mav_put_float(buf, 32, vel_north);
- _mav_put_float(buf, 36, vel_east);
- _mav_put_float(buf, 40, vel_down);
- _mav_put_float(buf, 44, speed);
- _mav_put_float(buf, 48, track);
- _mav_put_uint8_t(buf, 72, fix);
- _mav_put_uint8_t(buf, 73, n_satellites);
- _mav_put_char_array(buf, 52, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, buf, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#else
- mavlink_gps_tm_t *packet = (mavlink_gps_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->latitude = latitude;
- packet->longitude = longitude;
- packet->height = height;
- packet->vel_north = vel_north;
- packet->vel_east = vel_east;
- packet->vel_down = vel_down;
- packet->speed = speed;
- packet->track = track;
- packet->fix = fix;
- packet->n_satellites = n_satellites;
- mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, (const char *)packet, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE GPS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from gps_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_gps_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_name from gps_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_gps_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
-{
- return _MAV_RETURN_char_array(msg, sensor_name, 20, 52);
-}
-
-/**
- * @brief Get field fix from gps_tm message
- *
- * @return Wether the GPS has a FIX
- */
-static inline uint8_t mavlink_msg_gps_tm_get_fix(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 72);
-}
-
-/**
- * @brief Get field latitude from gps_tm message
- *
- * @return [deg] Latitude
- */
-static inline double mavlink_msg_gps_tm_get_latitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_double(msg, 8);
-}
-
-/**
- * @brief Get field longitude from gps_tm message
- *
- * @return [deg] Longitude
- */
-static inline double mavlink_msg_gps_tm_get_longitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_double(msg, 16);
-}
-
-/**
- * @brief Get field height from gps_tm message
- *
- * @return [m] Altitude
- */
-static inline double mavlink_msg_gps_tm_get_height(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_double(msg, 24);
-}
-
-/**
- * @brief Get field vel_north from gps_tm message
- *
- * @return [m/s] Velocity in NED frame (north)
- */
-static inline float mavlink_msg_gps_tm_get_vel_north(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field vel_east from gps_tm message
- *
- * @return [m/s] Velocity in NED frame (east)
- */
-static inline float mavlink_msg_gps_tm_get_vel_east(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field vel_down from gps_tm message
- *
- * @return [m/s] Velocity in NED frame (down)
- */
-static inline float mavlink_msg_gps_tm_get_vel_down(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field speed from gps_tm message
- *
- * @return [m/s] Speed
- */
-static inline float mavlink_msg_gps_tm_get_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field track from gps_tm message
- *
- * @return [deg] Track
- */
-static inline float mavlink_msg_gps_tm_get_track(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field n_satellites from gps_tm message
- *
- * @return Number of connected satellites
- */
-static inline uint8_t mavlink_msg_gps_tm_get_n_satellites(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 73);
-}
-
-/**
- * @brief Decode a gps_tm message into a struct
- *
- * @param msg The message to decode
- * @param gps_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_gps_tm_decode(const mavlink_message_t* msg, mavlink_gps_tm_t* gps_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- gps_tm->timestamp = mavlink_msg_gps_tm_get_timestamp(msg);
- gps_tm->latitude = mavlink_msg_gps_tm_get_latitude(msg);
- gps_tm->longitude = mavlink_msg_gps_tm_get_longitude(msg);
- gps_tm->height = mavlink_msg_gps_tm_get_height(msg);
- gps_tm->vel_north = mavlink_msg_gps_tm_get_vel_north(msg);
- gps_tm->vel_east = mavlink_msg_gps_tm_get_vel_east(msg);
- gps_tm->vel_down = mavlink_msg_gps_tm_get_vel_down(msg);
- gps_tm->speed = mavlink_msg_gps_tm_get_speed(msg);
- gps_tm->track = mavlink_msg_gps_tm_get_track(msg);
- mavlink_msg_gps_tm_get_sensor_name(msg, gps_tm->sensor_name);
- gps_tm->fix = mavlink_msg_gps_tm_get_fix(msg);
- gps_tm->n_satellites = mavlink_msg_gps_tm_get_n_satellites(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_TM_LEN? msg->len : MAVLINK_MSG_ID_GPS_TM_LEN;
- memset(gps_tm, 0, MAVLINK_MSG_ID_GPS_TM_LEN);
- memcpy(gps_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_gse_tm.h b/mavlink_lib/gemini/mavlink_msg_gse_tm.h
deleted file mode 100644
index 5b5742e639f0cc49886bd5df0396e8821a9075b3..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_gse_tm.h
+++ /dev/null
@@ -1,613 +0,0 @@
-#pragma once
-// MESSAGE GSE_TM PACKING
-
-#define MAVLINK_MSG_ID_GSE_TM 212
-
-
-typedef struct __mavlink_gse_tm_t {
- uint64_t timestamp; /*< [us] Timestamp in microseconds*/
- float loadcell_rocket; /*< [kg] Rocket weight*/
- float loadcell_vessel; /*< [kg] External tank weight*/
- float filling_pressure; /*< [Bar] Refueling line pressure*/
- float vessel_pressure; /*< [Bar] Vessel tank pressure*/
- float battery_voltage; /*< Battery voltage*/
- float current_consumption; /*< RIG current */
- uint8_t arming_state; /*< 1 If the rocket is armed*/
- uint8_t filling_valve_state; /*< 1 If the filling valve is open*/
- uint8_t venting_valve_state; /*< 1 If the venting valve is open*/
- uint8_t release_valve_state; /*< 1 If the release valve is open*/
- uint8_t main_valve_state; /*< 1 If the main valve is open */
- uint8_t ignition_state; /*< 1 If the RIG is in ignition process*/
- uint8_t tars_state; /*< 1 If the TARS algorithm is running*/
- uint8_t main_board_status; /*< MAIN board status [0: not present, 1: online, 2: armed]*/
- uint8_t payload_board_status; /*< PAYLOAD board status [0: not present, 1: online, 2: armed]*/
- uint8_t motor_board_status; /*< MOTOR board status [0: not present, 1: online, 2: armed]*/
-} mavlink_gse_tm_t;
-
-#define MAVLINK_MSG_ID_GSE_TM_LEN 42
-#define MAVLINK_MSG_ID_GSE_TM_MIN_LEN 42
-#define MAVLINK_MSG_ID_212_LEN 42
-#define MAVLINK_MSG_ID_212_MIN_LEN 42
-
-#define MAVLINK_MSG_ID_GSE_TM_CRC 63
-#define MAVLINK_MSG_ID_212_CRC 63
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_GSE_TM { \
- 212, \
- "GSE_TM", \
- 17, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gse_tm_t, timestamp) }, \
- { "loadcell_rocket", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gse_tm_t, loadcell_rocket) }, \
- { "loadcell_vessel", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gse_tm_t, loadcell_vessel) }, \
- { "filling_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gse_tm_t, filling_pressure) }, \
- { "vessel_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gse_tm_t, vessel_pressure) }, \
- { "arming_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gse_tm_t, arming_state) }, \
- { "filling_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gse_tm_t, filling_valve_state) }, \
- { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gse_tm_t, venting_valve_state) }, \
- { "release_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_gse_tm_t, release_valve_state) }, \
- { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_gse_tm_t, main_valve_state) }, \
- { "ignition_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_gse_tm_t, ignition_state) }, \
- { "tars_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_gse_tm_t, tars_state) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gse_tm_t, battery_voltage) }, \
- { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gse_tm_t, current_consumption) }, \
- { "main_board_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_gse_tm_t, main_board_status) }, \
- { "payload_board_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_gse_tm_t, payload_board_status) }, \
- { "motor_board_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_gse_tm_t, motor_board_status) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_GSE_TM { \
- "GSE_TM", \
- 17, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gse_tm_t, timestamp) }, \
- { "loadcell_rocket", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gse_tm_t, loadcell_rocket) }, \
- { "loadcell_vessel", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gse_tm_t, loadcell_vessel) }, \
- { "filling_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gse_tm_t, filling_pressure) }, \
- { "vessel_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gse_tm_t, vessel_pressure) }, \
- { "arming_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gse_tm_t, arming_state) }, \
- { "filling_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gse_tm_t, filling_valve_state) }, \
- { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gse_tm_t, venting_valve_state) }, \
- { "release_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_gse_tm_t, release_valve_state) }, \
- { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_gse_tm_t, main_valve_state) }, \
- { "ignition_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_gse_tm_t, ignition_state) }, \
- { "tars_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_gse_tm_t, tars_state) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gse_tm_t, battery_voltage) }, \
- { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gse_tm_t, current_consumption) }, \
- { "main_board_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_gse_tm_t, main_board_status) }, \
- { "payload_board_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_gse_tm_t, payload_board_status) }, \
- { "motor_board_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_gse_tm_t, motor_board_status) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a gse_tm 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 in microseconds
- * @param loadcell_rocket [kg] Rocket weight
- * @param loadcell_vessel [kg] External tank weight
- * @param filling_pressure [Bar] Refueling line pressure
- * @param vessel_pressure [Bar] Vessel tank pressure
- * @param arming_state 1 If the rocket is armed
- * @param filling_valve_state 1 If the filling valve is open
- * @param venting_valve_state 1 If the venting valve is open
- * @param release_valve_state 1 If the release valve is open
- * @param main_valve_state 1 If the main valve is open
- * @param ignition_state 1 If the RIG is in ignition process
- * @param tars_state 1 If the TARS algorithm is running
- * @param battery_voltage Battery voltage
- * @param current_consumption RIG current
- * @param main_board_status MAIN board status [0: not present, 1: online, 2: armed]
- * @param payload_board_status PAYLOAD board status [0: not present, 1: online, 2: armed]
- * @param motor_board_status MOTOR board status [0: not present, 1: online, 2: armed]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_gse_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, float loadcell_rocket, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t ignition_state, uint8_t tars_state, float battery_voltage, float current_consumption, uint8_t main_board_status, uint8_t payload_board_status, uint8_t motor_board_status)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GSE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, loadcell_rocket);
- _mav_put_float(buf, 12, loadcell_vessel);
- _mav_put_float(buf, 16, filling_pressure);
- _mav_put_float(buf, 20, vessel_pressure);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_float(buf, 28, current_consumption);
- _mav_put_uint8_t(buf, 32, arming_state);
- _mav_put_uint8_t(buf, 33, filling_valve_state);
- _mav_put_uint8_t(buf, 34, venting_valve_state);
- _mav_put_uint8_t(buf, 35, release_valve_state);
- _mav_put_uint8_t(buf, 36, main_valve_state);
- _mav_put_uint8_t(buf, 37, ignition_state);
- _mav_put_uint8_t(buf, 38, tars_state);
- _mav_put_uint8_t(buf, 39, main_board_status);
- _mav_put_uint8_t(buf, 40, payload_board_status);
- _mav_put_uint8_t(buf, 41, motor_board_status);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GSE_TM_LEN);
-#else
- mavlink_gse_tm_t packet;
- packet.timestamp = timestamp;
- packet.loadcell_rocket = loadcell_rocket;
- packet.loadcell_vessel = loadcell_vessel;
- packet.filling_pressure = filling_pressure;
- packet.vessel_pressure = vessel_pressure;
- packet.battery_voltage = battery_voltage;
- packet.current_consumption = current_consumption;
- packet.arming_state = arming_state;
- packet.filling_valve_state = filling_valve_state;
- packet.venting_valve_state = venting_valve_state;
- packet.release_valve_state = release_valve_state;
- packet.main_valve_state = main_valve_state;
- packet.ignition_state = ignition_state;
- packet.tars_state = tars_state;
- packet.main_board_status = main_board_status;
- packet.payload_board_status = payload_board_status;
- packet.motor_board_status = motor_board_status;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GSE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_GSE_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
-}
-
-/**
- * @brief Pack a gse_tm 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 in microseconds
- * @param loadcell_rocket [kg] Rocket weight
- * @param loadcell_vessel [kg] External tank weight
- * @param filling_pressure [Bar] Refueling line pressure
- * @param vessel_pressure [Bar] Vessel tank pressure
- * @param arming_state 1 If the rocket is armed
- * @param filling_valve_state 1 If the filling valve is open
- * @param venting_valve_state 1 If the venting valve is open
- * @param release_valve_state 1 If the release valve is open
- * @param main_valve_state 1 If the main valve is open
- * @param ignition_state 1 If the RIG is in ignition process
- * @param tars_state 1 If the TARS algorithm is running
- * @param battery_voltage Battery voltage
- * @param current_consumption RIG current
- * @param main_board_status MAIN board status [0: not present, 1: online, 2: armed]
- * @param payload_board_status PAYLOAD board status [0: not present, 1: online, 2: armed]
- * @param motor_board_status MOTOR board status [0: not present, 1: online, 2: armed]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_gse_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,float loadcell_rocket,float loadcell_vessel,float filling_pressure,float vessel_pressure,uint8_t arming_state,uint8_t filling_valve_state,uint8_t venting_valve_state,uint8_t release_valve_state,uint8_t main_valve_state,uint8_t ignition_state,uint8_t tars_state,float battery_voltage,float current_consumption,uint8_t main_board_status,uint8_t payload_board_status,uint8_t motor_board_status)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GSE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, loadcell_rocket);
- _mav_put_float(buf, 12, loadcell_vessel);
- _mav_put_float(buf, 16, filling_pressure);
- _mav_put_float(buf, 20, vessel_pressure);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_float(buf, 28, current_consumption);
- _mav_put_uint8_t(buf, 32, arming_state);
- _mav_put_uint8_t(buf, 33, filling_valve_state);
- _mav_put_uint8_t(buf, 34, venting_valve_state);
- _mav_put_uint8_t(buf, 35, release_valve_state);
- _mav_put_uint8_t(buf, 36, main_valve_state);
- _mav_put_uint8_t(buf, 37, ignition_state);
- _mav_put_uint8_t(buf, 38, tars_state);
- _mav_put_uint8_t(buf, 39, main_board_status);
- _mav_put_uint8_t(buf, 40, payload_board_status);
- _mav_put_uint8_t(buf, 41, motor_board_status);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GSE_TM_LEN);
-#else
- mavlink_gse_tm_t packet;
- packet.timestamp = timestamp;
- packet.loadcell_rocket = loadcell_rocket;
- packet.loadcell_vessel = loadcell_vessel;
- packet.filling_pressure = filling_pressure;
- packet.vessel_pressure = vessel_pressure;
- packet.battery_voltage = battery_voltage;
- packet.current_consumption = current_consumption;
- packet.arming_state = arming_state;
- packet.filling_valve_state = filling_valve_state;
- packet.venting_valve_state = venting_valve_state;
- packet.release_valve_state = release_valve_state;
- packet.main_valve_state = main_valve_state;
- packet.ignition_state = ignition_state;
- packet.tars_state = tars_state;
- packet.main_board_status = main_board_status;
- packet.payload_board_status = payload_board_status;
- packet.motor_board_status = motor_board_status;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GSE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_GSE_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
-}
-
-/**
- * @brief Encode a gse_tm 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 gse_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_gse_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gse_tm_t* gse_tm)
-{
- return mavlink_msg_gse_tm_pack(system_id, component_id, msg, gse_tm->timestamp, gse_tm->loadcell_rocket, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->ignition_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->main_board_status, gse_tm->payload_board_status, gse_tm->motor_board_status);
-}
-
-/**
- * @brief Encode a gse_tm 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 gse_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_gse_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gse_tm_t* gse_tm)
-{
- return mavlink_msg_gse_tm_pack_chan(system_id, component_id, chan, msg, gse_tm->timestamp, gse_tm->loadcell_rocket, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->ignition_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->main_board_status, gse_tm->payload_board_status, gse_tm->motor_board_status);
-}
-
-/**
- * @brief Send a gse_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp in microseconds
- * @param loadcell_rocket [kg] Rocket weight
- * @param loadcell_vessel [kg] External tank weight
- * @param filling_pressure [Bar] Refueling line pressure
- * @param vessel_pressure [Bar] Vessel tank pressure
- * @param arming_state 1 If the rocket is armed
- * @param filling_valve_state 1 If the filling valve is open
- * @param venting_valve_state 1 If the venting valve is open
- * @param release_valve_state 1 If the release valve is open
- * @param main_valve_state 1 If the main valve is open
- * @param ignition_state 1 If the RIG is in ignition process
- * @param tars_state 1 If the TARS algorithm is running
- * @param battery_voltage Battery voltage
- * @param current_consumption RIG current
- * @param main_board_status MAIN board status [0: not present, 1: online, 2: armed]
- * @param payload_board_status PAYLOAD board status [0: not present, 1: online, 2: armed]
- * @param motor_board_status MOTOR board status [0: not present, 1: online, 2: armed]
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_gse_tm_send(mavlink_channel_t chan, uint64_t timestamp, float loadcell_rocket, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t ignition_state, uint8_t tars_state, float battery_voltage, float current_consumption, uint8_t main_board_status, uint8_t payload_board_status, uint8_t motor_board_status)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GSE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, loadcell_rocket);
- _mav_put_float(buf, 12, loadcell_vessel);
- _mav_put_float(buf, 16, filling_pressure);
- _mav_put_float(buf, 20, vessel_pressure);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_float(buf, 28, current_consumption);
- _mav_put_uint8_t(buf, 32, arming_state);
- _mav_put_uint8_t(buf, 33, filling_valve_state);
- _mav_put_uint8_t(buf, 34, venting_valve_state);
- _mav_put_uint8_t(buf, 35, release_valve_state);
- _mav_put_uint8_t(buf, 36, main_valve_state);
- _mav_put_uint8_t(buf, 37, ignition_state);
- _mav_put_uint8_t(buf, 38, tars_state);
- _mav_put_uint8_t(buf, 39, main_board_status);
- _mav_put_uint8_t(buf, 40, payload_board_status);
- _mav_put_uint8_t(buf, 41, motor_board_status);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_TM, buf, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
-#else
- mavlink_gse_tm_t packet;
- packet.timestamp = timestamp;
- packet.loadcell_rocket = loadcell_rocket;
- packet.loadcell_vessel = loadcell_vessel;
- packet.filling_pressure = filling_pressure;
- packet.vessel_pressure = vessel_pressure;
- packet.battery_voltage = battery_voltage;
- packet.current_consumption = current_consumption;
- packet.arming_state = arming_state;
- packet.filling_valve_state = filling_valve_state;
- packet.venting_valve_state = venting_valve_state;
- packet.release_valve_state = release_valve_state;
- packet.main_valve_state = main_valve_state;
- packet.ignition_state = ignition_state;
- packet.tars_state = tars_state;
- packet.main_board_status = main_board_status;
- packet.payload_board_status = payload_board_status;
- packet.motor_board_status = motor_board_status;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_TM, (const char *)&packet, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a gse_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_gse_tm_send_struct(mavlink_channel_t chan, const mavlink_gse_tm_t* gse_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_gse_tm_send(chan, gse_tm->timestamp, gse_tm->loadcell_rocket, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->ignition_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->main_board_status, gse_tm->payload_board_status, gse_tm->motor_board_status);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_TM, (const char *)gse_tm, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_GSE_TM_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_gse_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float loadcell_rocket, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t ignition_state, uint8_t tars_state, float battery_voltage, float current_consumption, uint8_t main_board_status, uint8_t payload_board_status, uint8_t motor_board_status)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, loadcell_rocket);
- _mav_put_float(buf, 12, loadcell_vessel);
- _mav_put_float(buf, 16, filling_pressure);
- _mav_put_float(buf, 20, vessel_pressure);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_float(buf, 28, current_consumption);
- _mav_put_uint8_t(buf, 32, arming_state);
- _mav_put_uint8_t(buf, 33, filling_valve_state);
- _mav_put_uint8_t(buf, 34, venting_valve_state);
- _mav_put_uint8_t(buf, 35, release_valve_state);
- _mav_put_uint8_t(buf, 36, main_valve_state);
- _mav_put_uint8_t(buf, 37, ignition_state);
- _mav_put_uint8_t(buf, 38, tars_state);
- _mav_put_uint8_t(buf, 39, main_board_status);
- _mav_put_uint8_t(buf, 40, payload_board_status);
- _mav_put_uint8_t(buf, 41, motor_board_status);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_TM, buf, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
-#else
- mavlink_gse_tm_t *packet = (mavlink_gse_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->loadcell_rocket = loadcell_rocket;
- packet->loadcell_vessel = loadcell_vessel;
- packet->filling_pressure = filling_pressure;
- packet->vessel_pressure = vessel_pressure;
- packet->battery_voltage = battery_voltage;
- packet->current_consumption = current_consumption;
- packet->arming_state = arming_state;
- packet->filling_valve_state = filling_valve_state;
- packet->venting_valve_state = venting_valve_state;
- packet->release_valve_state = release_valve_state;
- packet->main_valve_state = main_valve_state;
- packet->ignition_state = ignition_state;
- packet->tars_state = tars_state;
- packet->main_board_status = main_board_status;
- packet->payload_board_status = payload_board_status;
- packet->motor_board_status = motor_board_status;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_TM, (const char *)packet, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE GSE_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from gse_tm message
- *
- * @return [us] Timestamp in microseconds
- */
-static inline uint64_t mavlink_msg_gse_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field loadcell_rocket from gse_tm message
- *
- * @return [kg] Rocket weight
- */
-static inline float mavlink_msg_gse_tm_get_loadcell_rocket(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field loadcell_vessel from gse_tm message
- *
- * @return [kg] External tank weight
- */
-static inline float mavlink_msg_gse_tm_get_loadcell_vessel(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field filling_pressure from gse_tm message
- *
- * @return [Bar] Refueling line pressure
- */
-static inline float mavlink_msg_gse_tm_get_filling_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field vessel_pressure from gse_tm message
- *
- * @return [Bar] Vessel tank pressure
- */
-static inline float mavlink_msg_gse_tm_get_vessel_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field arming_state from gse_tm message
- *
- * @return 1 If the rocket is armed
- */
-static inline uint8_t mavlink_msg_gse_tm_get_arming_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 32);
-}
-
-/**
- * @brief Get field filling_valve_state from gse_tm message
- *
- * @return 1 If the filling valve is open
- */
-static inline uint8_t mavlink_msg_gse_tm_get_filling_valve_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 33);
-}
-
-/**
- * @brief Get field venting_valve_state from gse_tm message
- *
- * @return 1 If the venting valve is open
- */
-static inline uint8_t mavlink_msg_gse_tm_get_venting_valve_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 34);
-}
-
-/**
- * @brief Get field release_valve_state from gse_tm message
- *
- * @return 1 If the release valve is open
- */
-static inline uint8_t mavlink_msg_gse_tm_get_release_valve_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 35);
-}
-
-/**
- * @brief Get field main_valve_state from gse_tm message
- *
- * @return 1 If the main valve is open
- */
-static inline uint8_t mavlink_msg_gse_tm_get_main_valve_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 36);
-}
-
-/**
- * @brief Get field ignition_state from gse_tm message
- *
- * @return 1 If the RIG is in ignition process
- */
-static inline uint8_t mavlink_msg_gse_tm_get_ignition_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 37);
-}
-
-/**
- * @brief Get field tars_state from gse_tm message
- *
- * @return 1 If the TARS algorithm is running
- */
-static inline uint8_t mavlink_msg_gse_tm_get_tars_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 38);
-}
-
-/**
- * @brief Get field battery_voltage from gse_tm message
- *
- * @return Battery voltage
- */
-static inline float mavlink_msg_gse_tm_get_battery_voltage(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field current_consumption from gse_tm message
- *
- * @return RIG current
- */
-static inline float mavlink_msg_gse_tm_get_current_consumption(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field main_board_status from gse_tm message
- *
- * @return MAIN board status [0: not present, 1: online, 2: armed]
- */
-static inline uint8_t mavlink_msg_gse_tm_get_main_board_status(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 39);
-}
-
-/**
- * @brief Get field payload_board_status from gse_tm message
- *
- * @return PAYLOAD board status [0: not present, 1: online, 2: armed]
- */
-static inline uint8_t mavlink_msg_gse_tm_get_payload_board_status(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 40);
-}
-
-/**
- * @brief Get field motor_board_status from gse_tm message
- *
- * @return MOTOR board status [0: not present, 1: online, 2: armed]
- */
-static inline uint8_t mavlink_msg_gse_tm_get_motor_board_status(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 41);
-}
-
-/**
- * @brief Decode a gse_tm message into a struct
- *
- * @param msg The message to decode
- * @param gse_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_gse_tm_decode(const mavlink_message_t* msg, mavlink_gse_tm_t* gse_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- gse_tm->timestamp = mavlink_msg_gse_tm_get_timestamp(msg);
- gse_tm->loadcell_rocket = mavlink_msg_gse_tm_get_loadcell_rocket(msg);
- gse_tm->loadcell_vessel = mavlink_msg_gse_tm_get_loadcell_vessel(msg);
- gse_tm->filling_pressure = mavlink_msg_gse_tm_get_filling_pressure(msg);
- gse_tm->vessel_pressure = mavlink_msg_gse_tm_get_vessel_pressure(msg);
- gse_tm->battery_voltage = mavlink_msg_gse_tm_get_battery_voltage(msg);
- gse_tm->current_consumption = mavlink_msg_gse_tm_get_current_consumption(msg);
- gse_tm->arming_state = mavlink_msg_gse_tm_get_arming_state(msg);
- gse_tm->filling_valve_state = mavlink_msg_gse_tm_get_filling_valve_state(msg);
- gse_tm->venting_valve_state = mavlink_msg_gse_tm_get_venting_valve_state(msg);
- gse_tm->release_valve_state = mavlink_msg_gse_tm_get_release_valve_state(msg);
- gse_tm->main_valve_state = mavlink_msg_gse_tm_get_main_valve_state(msg);
- gse_tm->ignition_state = mavlink_msg_gse_tm_get_ignition_state(msg);
- gse_tm->tars_state = mavlink_msg_gse_tm_get_tars_state(msg);
- gse_tm->main_board_status = mavlink_msg_gse_tm_get_main_board_status(msg);
- gse_tm->payload_board_status = mavlink_msg_gse_tm_get_payload_board_status(msg);
- gse_tm->motor_board_status = mavlink_msg_gse_tm_get_motor_board_status(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_GSE_TM_LEN? msg->len : MAVLINK_MSG_ID_GSE_TM_LEN;
- memset(gse_tm, 0, MAVLINK_MSG_ID_GSE_TM_LEN);
- memcpy(gse_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_imu_tm.h b/mavlink_lib/gemini/mavlink_msg_imu_tm.h
deleted file mode 100644
index 23c4739ce795a498ca8a3df799443719c003547b..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_imu_tm.h
+++ /dev/null
@@ -1,455 +0,0 @@
-#pragma once
-// MESSAGE IMU_TM PACKING
-
-#define MAVLINK_MSG_ID_IMU_TM 103
-
-
-typedef struct __mavlink_imu_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float acc_x; /*< [m/s2] X axis acceleration*/
- float acc_y; /*< [m/s2] Y axis acceleration*/
- float acc_z; /*< [m/s2] Z axis acceleration*/
- float gyro_x; /*< [rad/s] X axis gyro*/
- float gyro_y; /*< [rad/s] Y axis gyro*/
- float gyro_z; /*< [rad/s] Z axis gyro*/
- float mag_x; /*< [uT] X axis compass*/
- float mag_y; /*< [uT] Y axis compass*/
- float mag_z; /*< [uT] Z axis compass*/
- char sensor_name[20]; /*< Sensor name*/
-} mavlink_imu_tm_t;
-
-#define MAVLINK_MSG_ID_IMU_TM_LEN 64
-#define MAVLINK_MSG_ID_IMU_TM_MIN_LEN 64
-#define MAVLINK_MSG_ID_103_LEN 64
-#define MAVLINK_MSG_ID_103_MIN_LEN 64
-
-#define MAVLINK_MSG_ID_IMU_TM_CRC 72
-#define MAVLINK_MSG_ID_103_CRC 72
-
-#define MAVLINK_MSG_IMU_TM_FIELD_SENSOR_NAME_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_IMU_TM { \
- 103, \
- "IMU_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_imu_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 44, offsetof(mavlink_imu_tm_t, sensor_name) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_imu_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_imu_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_imu_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_imu_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_imu_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_imu_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_imu_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_imu_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_imu_tm_t, mag_z) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_IMU_TM { \
- "IMU_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_imu_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 44, offsetof(mavlink_imu_tm_t, sensor_name) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_imu_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_imu_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_imu_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_imu_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_imu_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_imu_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_imu_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_imu_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_imu_tm_t, mag_z) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a imu_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param acc_x [m/s2] X axis acceleration
- * @param acc_y [m/s2] Y axis acceleration
- * @param acc_z [m/s2] Z axis acceleration
- * @param gyro_x [rad/s] X axis gyro
- * @param gyro_y [rad/s] Y axis gyro
- * @param gyro_z [rad/s] Z axis gyro
- * @param mag_x [uT] X axis compass
- * @param mag_y [uT] Y axis compass
- * @param mag_z [uT] Z axis compass
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_imu_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_name, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_IMU_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, mag_x);
- _mav_put_float(buf, 36, mag_y);
- _mav_put_float(buf, 40, mag_z);
- _mav_put_char_array(buf, 44, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IMU_TM_LEN);
-#else
- mavlink_imu_tm_t packet;
- packet.timestamp = timestamp;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IMU_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_IMU_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-}
-
-/**
- * @brief Pack a imu_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param acc_x [m/s2] X axis acceleration
- * @param acc_y [m/s2] Y axis acceleration
- * @param acc_z [m/s2] Z axis acceleration
- * @param gyro_x [rad/s] X axis gyro
- * @param gyro_y [rad/s] Y axis gyro
- * @param gyro_z [rad/s] Z axis gyro
- * @param mag_x [uT] X axis compass
- * @param mag_y [uT] Y axis compass
- * @param mag_z [uT] Z axis compass
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_imu_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_name,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_IMU_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, mag_x);
- _mav_put_float(buf, 36, mag_y);
- _mav_put_float(buf, 40, mag_z);
- _mav_put_char_array(buf, 44, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IMU_TM_LEN);
-#else
- mavlink_imu_tm_t packet;
- packet.timestamp = timestamp;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IMU_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_IMU_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-}
-
-/**
- * @brief Encode a imu_tm 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 imu_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_imu_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_imu_tm_t* imu_tm)
-{
- return mavlink_msg_imu_tm_pack(system_id, component_id, msg, imu_tm->timestamp, imu_tm->sensor_name, imu_tm->acc_x, imu_tm->acc_y, imu_tm->acc_z, imu_tm->gyro_x, imu_tm->gyro_y, imu_tm->gyro_z, imu_tm->mag_x, imu_tm->mag_y, imu_tm->mag_z);
-}
-
-/**
- * @brief Encode a imu_tm 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 imu_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_imu_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_imu_tm_t* imu_tm)
-{
- return mavlink_msg_imu_tm_pack_chan(system_id, component_id, chan, msg, imu_tm->timestamp, imu_tm->sensor_name, imu_tm->acc_x, imu_tm->acc_y, imu_tm->acc_z, imu_tm->gyro_x, imu_tm->gyro_y, imu_tm->gyro_z, imu_tm->mag_x, imu_tm->mag_y, imu_tm->mag_z);
-}
-
-/**
- * @brief Send a imu_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_name Sensor name
- * @param acc_x [m/s2] X axis acceleration
- * @param acc_y [m/s2] Y axis acceleration
- * @param acc_z [m/s2] Z axis acceleration
- * @param gyro_x [rad/s] X axis gyro
- * @param gyro_y [rad/s] Y axis gyro
- * @param gyro_z [rad/s] Z axis gyro
- * @param mag_x [uT] X axis compass
- * @param mag_y [uT] Y axis compass
- * @param mag_z [uT] Z axis compass
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_imu_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_IMU_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, mag_x);
- _mav_put_float(buf, 36, mag_y);
- _mav_put_float(buf, 40, mag_z);
- _mav_put_char_array(buf, 44, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMU_TM, buf, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-#else
- mavlink_imu_tm_t packet;
- packet.timestamp = timestamp;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMU_TM, (const char *)&packet, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a imu_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_imu_tm_send_struct(mavlink_channel_t chan, const mavlink_imu_tm_t* imu_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_imu_tm_send(chan, imu_tm->timestamp, imu_tm->sensor_name, imu_tm->acc_x, imu_tm->acc_y, imu_tm->acc_z, imu_tm->gyro_x, imu_tm->gyro_y, imu_tm->gyro_z, imu_tm->mag_x, imu_tm->mag_y, imu_tm->mag_z);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMU_TM, (const char *)imu_tm, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_IMU_TM_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_imu_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, mag_x);
- _mav_put_float(buf, 36, mag_y);
- _mav_put_float(buf, 40, mag_z);
- _mav_put_char_array(buf, 44, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMU_TM, buf, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-#else
- mavlink_imu_tm_t *packet = (mavlink_imu_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->acc_x = acc_x;
- packet->acc_y = acc_y;
- packet->acc_z = acc_z;
- packet->gyro_x = gyro_x;
- packet->gyro_y = gyro_y;
- packet->gyro_z = gyro_z;
- packet->mag_x = mag_x;
- packet->mag_y = mag_y;
- packet->mag_z = mag_z;
- mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMU_TM, (const char *)packet, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE IMU_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from imu_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_imu_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_name from imu_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_imu_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
-{
- return _MAV_RETURN_char_array(msg, sensor_name, 20, 44);
-}
-
-/**
- * @brief Get field acc_x from imu_tm message
- *
- * @return [m/s2] X axis acceleration
- */
-static inline float mavlink_msg_imu_tm_get_acc_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field acc_y from imu_tm message
- *
- * @return [m/s2] Y axis acceleration
- */
-static inline float mavlink_msg_imu_tm_get_acc_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field acc_z from imu_tm message
- *
- * @return [m/s2] Z axis acceleration
- */
-static inline float mavlink_msg_imu_tm_get_acc_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field gyro_x from imu_tm message
- *
- * @return [rad/s] X axis gyro
- */
-static inline float mavlink_msg_imu_tm_get_gyro_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field gyro_y from imu_tm message
- *
- * @return [rad/s] Y axis gyro
- */
-static inline float mavlink_msg_imu_tm_get_gyro_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field gyro_z from imu_tm message
- *
- * @return [rad/s] Z axis gyro
- */
-static inline float mavlink_msg_imu_tm_get_gyro_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field mag_x from imu_tm message
- *
- * @return [uT] X axis compass
- */
-static inline float mavlink_msg_imu_tm_get_mag_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field mag_y from imu_tm message
- *
- * @return [uT] Y axis compass
- */
-static inline float mavlink_msg_imu_tm_get_mag_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field mag_z from imu_tm message
- *
- * @return [uT] Z axis compass
- */
-static inline float mavlink_msg_imu_tm_get_mag_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Decode a imu_tm message into a struct
- *
- * @param msg The message to decode
- * @param imu_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_imu_tm_decode(const mavlink_message_t* msg, mavlink_imu_tm_t* imu_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- imu_tm->timestamp = mavlink_msg_imu_tm_get_timestamp(msg);
- imu_tm->acc_x = mavlink_msg_imu_tm_get_acc_x(msg);
- imu_tm->acc_y = mavlink_msg_imu_tm_get_acc_y(msg);
- imu_tm->acc_z = mavlink_msg_imu_tm_get_acc_z(msg);
- imu_tm->gyro_x = mavlink_msg_imu_tm_get_gyro_x(msg);
- imu_tm->gyro_y = mavlink_msg_imu_tm_get_gyro_y(msg);
- imu_tm->gyro_z = mavlink_msg_imu_tm_get_gyro_z(msg);
- imu_tm->mag_x = mavlink_msg_imu_tm_get_mag_x(msg);
- imu_tm->mag_y = mavlink_msg_imu_tm_get_mag_y(msg);
- imu_tm->mag_z = mavlink_msg_imu_tm_get_mag_z(msg);
- mavlink_msg_imu_tm_get_sensor_name(msg, imu_tm->sensor_name);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_IMU_TM_LEN? msg->len : MAVLINK_MSG_ID_IMU_TM_LEN;
- memset(imu_tm, 0, MAVLINK_MSG_ID_IMU_TM_LEN);
- memcpy(imu_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_load_tm.h b/mavlink_lib/gemini/mavlink_msg_load_tm.h
deleted file mode 100644
index 27c578f3b208b1174ea5499a1e31a0497c925d07..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_load_tm.h
+++ /dev/null
@@ -1,255 +0,0 @@
-#pragma once
-// MESSAGE LOAD_TM PACKING
-
-#define MAVLINK_MSG_ID_LOAD_TM 109
-
-
-typedef struct __mavlink_load_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float load; /*< [kg] Load force*/
- char sensor_name[20]; /*< Sensor name*/
-} mavlink_load_tm_t;
-
-#define MAVLINK_MSG_ID_LOAD_TM_LEN 32
-#define MAVLINK_MSG_ID_LOAD_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_109_LEN 32
-#define MAVLINK_MSG_ID_109_MIN_LEN 32
-
-#define MAVLINK_MSG_ID_LOAD_TM_CRC 148
-#define MAVLINK_MSG_ID_109_CRC 148
-
-#define MAVLINK_MSG_LOAD_TM_FIELD_SENSOR_NAME_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_LOAD_TM { \
- 109, \
- "LOAD_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_load_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_load_tm_t, sensor_name) }, \
- { "load", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_load_tm_t, load) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_LOAD_TM { \
- "LOAD_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_load_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_load_tm_t, sensor_name) }, \
- { "load", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_load_tm_t, load) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a load_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param load [kg] Load force
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_load_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_name, float load)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOAD_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, load);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOAD_TM_LEN);
-#else
- mavlink_load_tm_t packet;
- packet.timestamp = timestamp;
- packet.load = load;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOAD_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LOAD_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-}
-
-/**
- * @brief Pack a load_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param load [kg] Load force
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_load_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_name,float load)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOAD_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, load);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOAD_TM_LEN);
-#else
- mavlink_load_tm_t packet;
- packet.timestamp = timestamp;
- packet.load = load;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOAD_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LOAD_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-}
-
-/**
- * @brief Encode a load_tm 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 load_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_load_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_load_tm_t* load_tm)
-{
- return mavlink_msg_load_tm_pack(system_id, component_id, msg, load_tm->timestamp, load_tm->sensor_name, load_tm->load);
-}
-
-/**
- * @brief Encode a load_tm 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 load_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_load_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_load_tm_t* load_tm)
-{
- return mavlink_msg_load_tm_pack_chan(system_id, component_id, chan, msg, load_tm->timestamp, load_tm->sensor_name, load_tm->load);
-}
-
-/**
- * @brief Send a load_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_name Sensor name
- * @param load [kg] Load force
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_load_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float load)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOAD_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, load);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOAD_TM, buf, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-#else
- mavlink_load_tm_t packet;
- packet.timestamp = timestamp;
- packet.load = load;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOAD_TM, (const char *)&packet, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a load_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_load_tm_send_struct(mavlink_channel_t chan, const mavlink_load_tm_t* load_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_load_tm_send(chan, load_tm->timestamp, load_tm->sensor_name, load_tm->load);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOAD_TM, (const char *)load_tm, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_LOAD_TM_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_load_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float load)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, load);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOAD_TM, buf, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-#else
- mavlink_load_tm_t *packet = (mavlink_load_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->load = load;
- mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOAD_TM, (const char *)packet, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE LOAD_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from load_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_load_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_name from load_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_load_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
-{
- return _MAV_RETURN_char_array(msg, sensor_name, 20, 12);
-}
-
-/**
- * @brief Get field load from load_tm message
- *
- * @return [kg] Load force
- */
-static inline float mavlink_msg_load_tm_get_load(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Decode a load_tm message into a struct
- *
- * @param msg The message to decode
- * @param load_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_load_tm_decode(const mavlink_message_t* msg, mavlink_load_tm_t* load_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- load_tm->timestamp = mavlink_msg_load_tm_get_timestamp(msg);
- load_tm->load = mavlink_msg_load_tm_get_load(msg);
- mavlink_msg_load_tm_get_sensor_name(msg, load_tm->sensor_name);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_LOAD_TM_LEN? msg->len : MAVLINK_MSG_ID_LOAD_TM_LEN;
- memset(load_tm, 0, MAVLINK_MSG_ID_LOAD_TM_LEN);
- memcpy(load_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_logger_tm.h b/mavlink_lib/gemini/mavlink_msg_logger_tm.h
deleted file mode 100644
index ac52b5a9d5faa26bb0047de6f0c67293ff6fe4f5..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_logger_tm.h
+++ /dev/null
@@ -1,463 +0,0 @@
-#pragma once
-// MESSAGE LOGGER_TM PACKING
-
-#define MAVLINK_MSG_ID_LOGGER_TM 202
-
-
-typedef struct __mavlink_logger_tm_t {
- uint64_t timestamp; /*< [us] Timestamp*/
- int32_t too_large_samples; /*< Number of dropped samples because too large*/
- int32_t dropped_samples; /*< Number of dropped samples due to fifo full*/
- int32_t queued_samples; /*< Number of samples written to buffer*/
- int32_t buffers_filled; /*< Number of buffers filled*/
- int32_t buffers_written; /*< Number of buffers written to disk*/
- int32_t writes_failed; /*< Number of fwrite() that failed*/
- int32_t last_write_error; /*< Error of the last fwrite() that failed*/
- int32_t average_write_time; /*< Average time to perform an fwrite() of a buffer*/
- int32_t max_write_time; /*< Max time to perform an fwrite() of a buffer*/
- int16_t log_number; /*< Currently active log file, -1 if the logger is inactive*/
-} mavlink_logger_tm_t;
-
-#define MAVLINK_MSG_ID_LOGGER_TM_LEN 46
-#define MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN 46
-#define MAVLINK_MSG_ID_202_LEN 46
-#define MAVLINK_MSG_ID_202_MIN_LEN 46
-
-#define MAVLINK_MSG_ID_LOGGER_TM_CRC 142
-#define MAVLINK_MSG_ID_202_CRC 142
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_LOGGER_TM { \
- 202, \
- "LOGGER_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_logger_tm_t, timestamp) }, \
- { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_logger_tm_t, log_number) }, \
- { "too_large_samples", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_logger_tm_t, too_large_samples) }, \
- { "dropped_samples", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_logger_tm_t, dropped_samples) }, \
- { "queued_samples", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_logger_tm_t, queued_samples) }, \
- { "buffers_filled", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_logger_tm_t, buffers_filled) }, \
- { "buffers_written", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_logger_tm_t, buffers_written) }, \
- { "writes_failed", NULL, MAVLINK_TYPE_INT32_T, 0, 28, offsetof(mavlink_logger_tm_t, writes_failed) }, \
- { "last_write_error", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_logger_tm_t, last_write_error) }, \
- { "average_write_time", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_logger_tm_t, average_write_time) }, \
- { "max_write_time", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_logger_tm_t, max_write_time) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_LOGGER_TM { \
- "LOGGER_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_logger_tm_t, timestamp) }, \
- { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_logger_tm_t, log_number) }, \
- { "too_large_samples", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_logger_tm_t, too_large_samples) }, \
- { "dropped_samples", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_logger_tm_t, dropped_samples) }, \
- { "queued_samples", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_logger_tm_t, queued_samples) }, \
- { "buffers_filled", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_logger_tm_t, buffers_filled) }, \
- { "buffers_written", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_logger_tm_t, buffers_written) }, \
- { "writes_failed", NULL, MAVLINK_TYPE_INT32_T, 0, 28, offsetof(mavlink_logger_tm_t, writes_failed) }, \
- { "last_write_error", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_logger_tm_t, last_write_error) }, \
- { "average_write_time", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_logger_tm_t, average_write_time) }, \
- { "max_write_time", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_logger_tm_t, max_write_time) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a logger_tm 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
- * @param log_number Currently active log file, -1 if the logger is inactive
- * @param too_large_samples Number of dropped samples because too large
- * @param dropped_samples Number of dropped samples due to fifo full
- * @param queued_samples Number of samples written to buffer
- * @param buffers_filled Number of buffers filled
- * @param buffers_written Number of buffers written to disk
- * @param writes_failed Number of fwrite() that failed
- * @param last_write_error Error of the last fwrite() that failed
- * @param average_write_time Average time to perform an fwrite() of a buffer
- * @param max_write_time Max time to perform an fwrite() of a buffer
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_logger_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, int16_t log_number, int32_t too_large_samples, int32_t dropped_samples, int32_t queued_samples, int32_t buffers_filled, int32_t buffers_written, int32_t writes_failed, int32_t last_write_error, int32_t average_write_time, int32_t max_write_time)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOGGER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 8, too_large_samples);
- _mav_put_int32_t(buf, 12, dropped_samples);
- _mav_put_int32_t(buf, 16, queued_samples);
- _mav_put_int32_t(buf, 20, buffers_filled);
- _mav_put_int32_t(buf, 24, buffers_written);
- _mav_put_int32_t(buf, 28, writes_failed);
- _mav_put_int32_t(buf, 32, last_write_error);
- _mav_put_int32_t(buf, 36, average_write_time);
- _mav_put_int32_t(buf, 40, max_write_time);
- _mav_put_int16_t(buf, 44, log_number);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGER_TM_LEN);
-#else
- mavlink_logger_tm_t packet;
- packet.timestamp = timestamp;
- packet.too_large_samples = too_large_samples;
- packet.dropped_samples = dropped_samples;
- packet.queued_samples = queued_samples;
- packet.buffers_filled = buffers_filled;
- packet.buffers_written = buffers_written;
- packet.writes_failed = writes_failed;
- packet.last_write_error = last_write_error;
- packet.average_write_time = average_write_time;
- packet.max_write_time = max_write_time;
- packet.log_number = log_number;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGER_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LOGGER_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-}
-
-/**
- * @brief Pack a logger_tm 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
- * @param log_number Currently active log file, -1 if the logger is inactive
- * @param too_large_samples Number of dropped samples because too large
- * @param dropped_samples Number of dropped samples due to fifo full
- * @param queued_samples Number of samples written to buffer
- * @param buffers_filled Number of buffers filled
- * @param buffers_written Number of buffers written to disk
- * @param writes_failed Number of fwrite() that failed
- * @param last_write_error Error of the last fwrite() that failed
- * @param average_write_time Average time to perform an fwrite() of a buffer
- * @param max_write_time Max time to perform an fwrite() of a buffer
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_logger_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,int16_t log_number,int32_t too_large_samples,int32_t dropped_samples,int32_t queued_samples,int32_t buffers_filled,int32_t buffers_written,int32_t writes_failed,int32_t last_write_error,int32_t average_write_time,int32_t max_write_time)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOGGER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 8, too_large_samples);
- _mav_put_int32_t(buf, 12, dropped_samples);
- _mav_put_int32_t(buf, 16, queued_samples);
- _mav_put_int32_t(buf, 20, buffers_filled);
- _mav_put_int32_t(buf, 24, buffers_written);
- _mav_put_int32_t(buf, 28, writes_failed);
- _mav_put_int32_t(buf, 32, last_write_error);
- _mav_put_int32_t(buf, 36, average_write_time);
- _mav_put_int32_t(buf, 40, max_write_time);
- _mav_put_int16_t(buf, 44, log_number);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGER_TM_LEN);
-#else
- mavlink_logger_tm_t packet;
- packet.timestamp = timestamp;
- packet.too_large_samples = too_large_samples;
- packet.dropped_samples = dropped_samples;
- packet.queued_samples = queued_samples;
- packet.buffers_filled = buffers_filled;
- packet.buffers_written = buffers_written;
- packet.writes_failed = writes_failed;
- packet.last_write_error = last_write_error;
- packet.average_write_time = average_write_time;
- packet.max_write_time = max_write_time;
- packet.log_number = log_number;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGER_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LOGGER_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-}
-
-/**
- * @brief Encode a logger_tm 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 logger_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_logger_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_logger_tm_t* logger_tm)
-{
- return mavlink_msg_logger_tm_pack(system_id, component_id, msg, logger_tm->timestamp, logger_tm->log_number, logger_tm->too_large_samples, logger_tm->dropped_samples, logger_tm->queued_samples, logger_tm->buffers_filled, logger_tm->buffers_written, logger_tm->writes_failed, logger_tm->last_write_error, logger_tm->average_write_time, logger_tm->max_write_time);
-}
-
-/**
- * @brief Encode a logger_tm 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 logger_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_logger_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_logger_tm_t* logger_tm)
-{
- return mavlink_msg_logger_tm_pack_chan(system_id, component_id, chan, msg, logger_tm->timestamp, logger_tm->log_number, logger_tm->too_large_samples, logger_tm->dropped_samples, logger_tm->queued_samples, logger_tm->buffers_filled, logger_tm->buffers_written, logger_tm->writes_failed, logger_tm->last_write_error, logger_tm->average_write_time, logger_tm->max_write_time);
-}
-
-/**
- * @brief Send a logger_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp
- * @param log_number Currently active log file, -1 if the logger is inactive
- * @param too_large_samples Number of dropped samples because too large
- * @param dropped_samples Number of dropped samples due to fifo full
- * @param queued_samples Number of samples written to buffer
- * @param buffers_filled Number of buffers filled
- * @param buffers_written Number of buffers written to disk
- * @param writes_failed Number of fwrite() that failed
- * @param last_write_error Error of the last fwrite() that failed
- * @param average_write_time Average time to perform an fwrite() of a buffer
- * @param max_write_time Max time to perform an fwrite() of a buffer
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_logger_tm_send(mavlink_channel_t chan, uint64_t timestamp, int16_t log_number, int32_t too_large_samples, int32_t dropped_samples, int32_t queued_samples, int32_t buffers_filled, int32_t buffers_written, int32_t writes_failed, int32_t last_write_error, int32_t average_write_time, int32_t max_write_time)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOGGER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 8, too_large_samples);
- _mav_put_int32_t(buf, 12, dropped_samples);
- _mav_put_int32_t(buf, 16, queued_samples);
- _mav_put_int32_t(buf, 20, buffers_filled);
- _mav_put_int32_t(buf, 24, buffers_written);
- _mav_put_int32_t(buf, 28, writes_failed);
- _mav_put_int32_t(buf, 32, last_write_error);
- _mav_put_int32_t(buf, 36, average_write_time);
- _mav_put_int32_t(buf, 40, max_write_time);
- _mav_put_int16_t(buf, 44, log_number);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, buf, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#else
- mavlink_logger_tm_t packet;
- packet.timestamp = timestamp;
- packet.too_large_samples = too_large_samples;
- packet.dropped_samples = dropped_samples;
- packet.queued_samples = queued_samples;
- packet.buffers_filled = buffers_filled;
- packet.buffers_written = buffers_written;
- packet.writes_failed = writes_failed;
- packet.last_write_error = last_write_error;
- packet.average_write_time = average_write_time;
- packet.max_write_time = max_write_time;
- packet.log_number = log_number;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, (const char *)&packet, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a logger_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_logger_tm_send_struct(mavlink_channel_t chan, const mavlink_logger_tm_t* logger_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_logger_tm_send(chan, logger_tm->timestamp, logger_tm->log_number, logger_tm->too_large_samples, logger_tm->dropped_samples, logger_tm->queued_samples, logger_tm->buffers_filled, logger_tm->buffers_written, logger_tm->writes_failed, logger_tm->last_write_error, logger_tm->average_write_time, logger_tm->max_write_time);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, (const char *)logger_tm, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_LOGGER_TM_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_logger_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, int16_t log_number, int32_t too_large_samples, int32_t dropped_samples, int32_t queued_samples, int32_t buffers_filled, int32_t buffers_written, int32_t writes_failed, int32_t last_write_error, int32_t average_write_time, int32_t max_write_time)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 8, too_large_samples);
- _mav_put_int32_t(buf, 12, dropped_samples);
- _mav_put_int32_t(buf, 16, queued_samples);
- _mav_put_int32_t(buf, 20, buffers_filled);
- _mav_put_int32_t(buf, 24, buffers_written);
- _mav_put_int32_t(buf, 28, writes_failed);
- _mav_put_int32_t(buf, 32, last_write_error);
- _mav_put_int32_t(buf, 36, average_write_time);
- _mav_put_int32_t(buf, 40, max_write_time);
- _mav_put_int16_t(buf, 44, log_number);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, buf, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#else
- mavlink_logger_tm_t *packet = (mavlink_logger_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->too_large_samples = too_large_samples;
- packet->dropped_samples = dropped_samples;
- packet->queued_samples = queued_samples;
- packet->buffers_filled = buffers_filled;
- packet->buffers_written = buffers_written;
- packet->writes_failed = writes_failed;
- packet->last_write_error = last_write_error;
- packet->average_write_time = average_write_time;
- packet->max_write_time = max_write_time;
- packet->log_number = log_number;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, (const char *)packet, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE LOGGER_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from logger_tm message
- *
- * @return [us] Timestamp
- */
-static inline uint64_t mavlink_msg_logger_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field log_number from logger_tm message
- *
- * @return Currently active log file, -1 if the logger is inactive
- */
-static inline int16_t mavlink_msg_logger_tm_get_log_number(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int16_t(msg, 44);
-}
-
-/**
- * @brief Get field too_large_samples from logger_tm message
- *
- * @return Number of dropped samples because too large
- */
-static inline int32_t mavlink_msg_logger_tm_get_too_large_samples(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 8);
-}
-
-/**
- * @brief Get field dropped_samples from logger_tm message
- *
- * @return Number of dropped samples due to fifo full
- */
-static inline int32_t mavlink_msg_logger_tm_get_dropped_samples(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 12);
-}
-
-/**
- * @brief Get field queued_samples from logger_tm message
- *
- * @return Number of samples written to buffer
- */
-static inline int32_t mavlink_msg_logger_tm_get_queued_samples(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 16);
-}
-
-/**
- * @brief Get field buffers_filled from logger_tm message
- *
- * @return Number of buffers filled
- */
-static inline int32_t mavlink_msg_logger_tm_get_buffers_filled(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 20);
-}
-
-/**
- * @brief Get field buffers_written from logger_tm message
- *
- * @return Number of buffers written to disk
- */
-static inline int32_t mavlink_msg_logger_tm_get_buffers_written(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 24);
-}
-
-/**
- * @brief Get field writes_failed from logger_tm message
- *
- * @return Number of fwrite() that failed
- */
-static inline int32_t mavlink_msg_logger_tm_get_writes_failed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 28);
-}
-
-/**
- * @brief Get field last_write_error from logger_tm message
- *
- * @return Error of the last fwrite() that failed
- */
-static inline int32_t mavlink_msg_logger_tm_get_last_write_error(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 32);
-}
-
-/**
- * @brief Get field average_write_time from logger_tm message
- *
- * @return Average time to perform an fwrite() of a buffer
- */
-static inline int32_t mavlink_msg_logger_tm_get_average_write_time(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 36);
-}
-
-/**
- * @brief Get field max_write_time from logger_tm message
- *
- * @return Max time to perform an fwrite() of a buffer
- */
-static inline int32_t mavlink_msg_logger_tm_get_max_write_time(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 40);
-}
-
-/**
- * @brief Decode a logger_tm message into a struct
- *
- * @param msg The message to decode
- * @param logger_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_logger_tm_decode(const mavlink_message_t* msg, mavlink_logger_tm_t* logger_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- logger_tm->timestamp = mavlink_msg_logger_tm_get_timestamp(msg);
- logger_tm->too_large_samples = mavlink_msg_logger_tm_get_too_large_samples(msg);
- logger_tm->dropped_samples = mavlink_msg_logger_tm_get_dropped_samples(msg);
- logger_tm->queued_samples = mavlink_msg_logger_tm_get_queued_samples(msg);
- logger_tm->buffers_filled = mavlink_msg_logger_tm_get_buffers_filled(msg);
- logger_tm->buffers_written = mavlink_msg_logger_tm_get_buffers_written(msg);
- logger_tm->writes_failed = mavlink_msg_logger_tm_get_writes_failed(msg);
- logger_tm->last_write_error = mavlink_msg_logger_tm_get_last_write_error(msg);
- logger_tm->average_write_time = mavlink_msg_logger_tm_get_average_write_time(msg);
- logger_tm->max_write_time = mavlink_msg_logger_tm_get_max_write_time(msg);
- logger_tm->log_number = mavlink_msg_logger_tm_get_log_number(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_LOGGER_TM_LEN? msg->len : MAVLINK_MSG_ID_LOGGER_TM_LEN;
- memset(logger_tm, 0, MAVLINK_MSG_ID_LOGGER_TM_LEN);
- memcpy(logger_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_mavlink_stats_tm.h b/mavlink_lib/gemini/mavlink_msg_mavlink_stats_tm.h
deleted file mode 100644
index ba89b5f0761bcadff4201e229880cd30f7b90358..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_mavlink_stats_tm.h
+++ /dev/null
@@ -1,513 +0,0 @@
-#pragma once
-// MESSAGE MAVLINK_STATS_TM PACKING
-
-#define MAVLINK_MSG_ID_MAVLINK_STATS_TM 203
-
-
-typedef struct __mavlink_mavlink_stats_tm_t {
- uint64_t timestamp; /*< [us] When was this logged */
- uint32_t parse_state; /*< Parsing state machine*/
- uint16_t n_send_queue; /*< Current len of the occupied portion of the queue*/
- uint16_t max_send_queue; /*< Max occupied len of the queue */
- uint16_t n_send_errors; /*< Number of packet not sent correctly by the TMTC*/
- uint16_t packet_rx_success_count; /*< Received packets*/
- uint16_t packet_rx_drop_count; /*< Number of packet drops */
- uint8_t msg_received; /*< Number of received messages*/
- uint8_t buffer_overrun; /*< Number of buffer overruns*/
- uint8_t parse_error; /*< Number of parse errors*/
- 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 */
-} mavlink_mavlink_stats_tm_t;
-
-#define MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN 28
-#define MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN 28
-#define MAVLINK_MSG_ID_203_LEN 28
-#define MAVLINK_MSG_ID_203_MIN_LEN 28
-
-#define MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC 108
-#define MAVLINK_MSG_ID_203_CRC 108
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM { \
- 203, \
- "MAVLINK_STATS_TM", \
- 13, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_mavlink_stats_tm_t, timestamp) }, \
- { "n_send_queue", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_mavlink_stats_tm_t, n_send_queue) }, \
- { "max_send_queue", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_mavlink_stats_tm_t, max_send_queue) }, \
- { "n_send_errors", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_mavlink_stats_tm_t, n_send_errors) }, \
- { "msg_received", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_mavlink_stats_tm_t, msg_received) }, \
- { "buffer_overrun", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_mavlink_stats_tm_t, buffer_overrun) }, \
- { "parse_error", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_mavlink_stats_tm_t, parse_error) }, \
- { "parse_state", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_mavlink_stats_tm_t, parse_state) }, \
- { "packet_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_mavlink_stats_tm_t, packet_idx) }, \
- { "current_rx_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_mavlink_stats_tm_t, current_rx_seq) }, \
- { "current_tx_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_mavlink_stats_tm_t, current_tx_seq) }, \
- { "packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_mavlink_stats_tm_t, packet_rx_success_count) }, \
- { "packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_mavlink_stats_tm_t, packet_rx_drop_count) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM { \
- "MAVLINK_STATS_TM", \
- 13, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_mavlink_stats_tm_t, timestamp) }, \
- { "n_send_queue", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_mavlink_stats_tm_t, n_send_queue) }, \
- { "max_send_queue", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_mavlink_stats_tm_t, max_send_queue) }, \
- { "n_send_errors", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_mavlink_stats_tm_t, n_send_errors) }, \
- { "msg_received", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_mavlink_stats_tm_t, msg_received) }, \
- { "buffer_overrun", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_mavlink_stats_tm_t, buffer_overrun) }, \
- { "parse_error", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_mavlink_stats_tm_t, parse_error) }, \
- { "parse_state", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_mavlink_stats_tm_t, parse_state) }, \
- { "packet_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_mavlink_stats_tm_t, packet_idx) }, \
- { "current_rx_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_mavlink_stats_tm_t, current_rx_seq) }, \
- { "current_tx_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_mavlink_stats_tm_t, current_tx_seq) }, \
- { "packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_mavlink_stats_tm_t, packet_rx_success_count) }, \
- { "packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_mavlink_stats_tm_t, packet_rx_drop_count) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a mavlink_stats_tm 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] When was this logged
- * @param n_send_queue Current len of the occupied portion of the queue
- * @param max_send_queue Max occupied len of the queue
- * @param n_send_errors Number of packet not sent correctly by the TMTC
- * @param msg_received Number of received messages
- * @param buffer_overrun Number of buffer overruns
- * @param parse_error Number of parse errors
- * @param parse_state Parsing state machine
- * @param packet_idx Index in current packet
- * @param current_rx_seq Sequence number of last packet received
- * @param current_tx_seq Sequence number of last packet sent
- * @param packet_rx_success_count Received packets
- * @param packet_rx_drop_count Number of packet drops
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint16_t n_send_queue, uint16_t max_send_queue, uint16_t n_send_errors, uint8_t msg_received, uint8_t buffer_overrun, uint8_t parse_error, uint32_t parse_state, uint8_t packet_idx, uint8_t current_rx_seq, uint8_t current_tx_seq, uint16_t packet_rx_success_count, uint16_t packet_rx_drop_count)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint32_t(buf, 8, parse_state);
- _mav_put_uint16_t(buf, 12, n_send_queue);
- _mav_put_uint16_t(buf, 14, max_send_queue);
- _mav_put_uint16_t(buf, 16, n_send_errors);
- _mav_put_uint16_t(buf, 18, packet_rx_success_count);
- _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
- _mav_put_uint8_t(buf, 22, msg_received);
- _mav_put_uint8_t(buf, 23, buffer_overrun);
- _mav_put_uint8_t(buf, 24, parse_error);
- _mav_put_uint8_t(buf, 25, packet_idx);
- _mav_put_uint8_t(buf, 26, current_rx_seq);
- _mav_put_uint8_t(buf, 27, current_tx_seq);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN);
-#else
- mavlink_mavlink_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.parse_state = parse_state;
- packet.n_send_queue = n_send_queue;
- packet.max_send_queue = max_send_queue;
- packet.n_send_errors = n_send_errors;
- packet.packet_rx_success_count = packet_rx_success_count;
- packet.packet_rx_drop_count = packet_rx_drop_count;
- packet.msg_received = msg_received;
- packet.buffer_overrun = buffer_overrun;
- packet.parse_error = parse_error;
- packet.packet_idx = packet_idx;
- packet.current_rx_seq = current_rx_seq;
- packet.current_tx_seq = current_tx_seq;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_MAVLINK_STATS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-}
-
-/**
- * @brief Pack a mavlink_stats_tm 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] When was this logged
- * @param n_send_queue Current len of the occupied portion of the queue
- * @param max_send_queue Max occupied len of the queue
- * @param n_send_errors Number of packet not sent correctly by the TMTC
- * @param msg_received Number of received messages
- * @param buffer_overrun Number of buffer overruns
- * @param parse_error Number of parse errors
- * @param parse_state Parsing state machine
- * @param packet_idx Index in current packet
- * @param current_rx_seq Sequence number of last packet received
- * @param current_tx_seq Sequence number of last packet sent
- * @param packet_rx_success_count Received packets
- * @param packet_rx_drop_count Number of packet drops
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint16_t n_send_queue,uint16_t max_send_queue,uint16_t n_send_errors,uint8_t msg_received,uint8_t buffer_overrun,uint8_t parse_error,uint32_t parse_state,uint8_t packet_idx,uint8_t current_rx_seq,uint8_t current_tx_seq,uint16_t packet_rx_success_count,uint16_t packet_rx_drop_count)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint32_t(buf, 8, parse_state);
- _mav_put_uint16_t(buf, 12, n_send_queue);
- _mav_put_uint16_t(buf, 14, max_send_queue);
- _mav_put_uint16_t(buf, 16, n_send_errors);
- _mav_put_uint16_t(buf, 18, packet_rx_success_count);
- _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
- _mav_put_uint8_t(buf, 22, msg_received);
- _mav_put_uint8_t(buf, 23, buffer_overrun);
- _mav_put_uint8_t(buf, 24, parse_error);
- _mav_put_uint8_t(buf, 25, packet_idx);
- _mav_put_uint8_t(buf, 26, current_rx_seq);
- _mav_put_uint8_t(buf, 27, current_tx_seq);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN);
-#else
- mavlink_mavlink_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.parse_state = parse_state;
- packet.n_send_queue = n_send_queue;
- packet.max_send_queue = max_send_queue;
- packet.n_send_errors = n_send_errors;
- packet.packet_rx_success_count = packet_rx_success_count;
- packet.packet_rx_drop_count = packet_rx_drop_count;
- packet.msg_received = msg_received;
- packet.buffer_overrun = buffer_overrun;
- packet.parse_error = parse_error;
- packet.packet_idx = packet_idx;
- packet.current_rx_seq = current_rx_seq;
- packet.current_tx_seq = current_tx_seq;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_MAVLINK_STATS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-}
-
-/**
- * @brief Encode a mavlink_stats_tm 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 mavlink_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mavlink_stats_tm_t* mavlink_stats_tm)
-{
- return mavlink_msg_mavlink_stats_tm_pack(system_id, component_id, msg, mavlink_stats_tm->timestamp, mavlink_stats_tm->n_send_queue, mavlink_stats_tm->max_send_queue, mavlink_stats_tm->n_send_errors, mavlink_stats_tm->msg_received, mavlink_stats_tm->buffer_overrun, mavlink_stats_tm->parse_error, mavlink_stats_tm->parse_state, mavlink_stats_tm->packet_idx, mavlink_stats_tm->current_rx_seq, mavlink_stats_tm->current_tx_seq, mavlink_stats_tm->packet_rx_success_count, mavlink_stats_tm->packet_rx_drop_count);
-}
-
-/**
- * @brief Encode a mavlink_stats_tm 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 mavlink_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mavlink_stats_tm_t* mavlink_stats_tm)
-{
- return mavlink_msg_mavlink_stats_tm_pack_chan(system_id, component_id, chan, msg, mavlink_stats_tm->timestamp, mavlink_stats_tm->n_send_queue, mavlink_stats_tm->max_send_queue, mavlink_stats_tm->n_send_errors, mavlink_stats_tm->msg_received, mavlink_stats_tm->buffer_overrun, mavlink_stats_tm->parse_error, mavlink_stats_tm->parse_state, mavlink_stats_tm->packet_idx, mavlink_stats_tm->current_rx_seq, mavlink_stats_tm->current_tx_seq, mavlink_stats_tm->packet_rx_success_count, mavlink_stats_tm->packet_rx_drop_count);
-}
-
-/**
- * @brief Send a mavlink_stats_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param n_send_queue Current len of the occupied portion of the queue
- * @param max_send_queue Max occupied len of the queue
- * @param n_send_errors Number of packet not sent correctly by the TMTC
- * @param msg_received Number of received messages
- * @param buffer_overrun Number of buffer overruns
- * @param parse_error Number of parse errors
- * @param parse_state Parsing state machine
- * @param packet_idx Index in current packet
- * @param current_rx_seq Sequence number of last packet received
- * @param current_tx_seq Sequence number of last packet sent
- * @param packet_rx_success_count Received packets
- * @param packet_rx_drop_count Number of packet drops
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_mavlink_stats_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint16_t n_send_queue, uint16_t max_send_queue, uint16_t n_send_errors, uint8_t msg_received, uint8_t buffer_overrun, uint8_t parse_error, uint32_t parse_state, uint8_t packet_idx, uint8_t current_rx_seq, uint8_t current_tx_seq, uint16_t packet_rx_success_count, uint16_t packet_rx_drop_count)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint32_t(buf, 8, parse_state);
- _mav_put_uint16_t(buf, 12, n_send_queue);
- _mav_put_uint16_t(buf, 14, max_send_queue);
- _mav_put_uint16_t(buf, 16, n_send_errors);
- _mav_put_uint16_t(buf, 18, packet_rx_success_count);
- _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
- _mav_put_uint8_t(buf, 22, msg_received);
- _mav_put_uint8_t(buf, 23, buffer_overrun);
- _mav_put_uint8_t(buf, 24, parse_error);
- _mav_put_uint8_t(buf, 25, packet_idx);
- _mav_put_uint8_t(buf, 26, current_rx_seq);
- _mav_put_uint8_t(buf, 27, current_tx_seq);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAVLINK_STATS_TM, buf, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-#else
- mavlink_mavlink_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.parse_state = parse_state;
- packet.n_send_queue = n_send_queue;
- packet.max_send_queue = max_send_queue;
- packet.n_send_errors = n_send_errors;
- packet.packet_rx_success_count = packet_rx_success_count;
- packet.packet_rx_drop_count = packet_rx_drop_count;
- packet.msg_received = msg_received;
- packet.buffer_overrun = buffer_overrun;
- packet.parse_error = parse_error;
- packet.packet_idx = packet_idx;
- packet.current_rx_seq = current_rx_seq;
- packet.current_tx_seq = current_tx_seq;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAVLINK_STATS_TM, (const char *)&packet, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a mavlink_stats_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_mavlink_stats_tm_send_struct(mavlink_channel_t chan, const mavlink_mavlink_stats_tm_t* mavlink_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_mavlink_stats_tm_send(chan, mavlink_stats_tm->timestamp, mavlink_stats_tm->n_send_queue, mavlink_stats_tm->max_send_queue, mavlink_stats_tm->n_send_errors, mavlink_stats_tm->msg_received, mavlink_stats_tm->buffer_overrun, mavlink_stats_tm->parse_error, mavlink_stats_tm->parse_state, mavlink_stats_tm->packet_idx, mavlink_stats_tm->current_rx_seq, mavlink_stats_tm->current_tx_seq, mavlink_stats_tm->packet_rx_success_count, mavlink_stats_tm->packet_rx_drop_count);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAVLINK_STATS_TM, (const char *)mavlink_stats_tm, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_MAVLINK_STATS_TM_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_mavlink_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint16_t n_send_queue, uint16_t max_send_queue, uint16_t n_send_errors, uint8_t msg_received, uint8_t buffer_overrun, uint8_t parse_error, uint32_t parse_state, uint8_t packet_idx, uint8_t current_rx_seq, uint8_t current_tx_seq, uint16_t packet_rx_success_count, uint16_t packet_rx_drop_count)
-{
-#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, parse_state);
- _mav_put_uint16_t(buf, 12, n_send_queue);
- _mav_put_uint16_t(buf, 14, max_send_queue);
- _mav_put_uint16_t(buf, 16, n_send_errors);
- _mav_put_uint16_t(buf, 18, packet_rx_success_count);
- _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
- _mav_put_uint8_t(buf, 22, msg_received);
- _mav_put_uint8_t(buf, 23, buffer_overrun);
- _mav_put_uint8_t(buf, 24, parse_error);
- _mav_put_uint8_t(buf, 25, packet_idx);
- _mav_put_uint8_t(buf, 26, current_rx_seq);
- _mav_put_uint8_t(buf, 27, current_tx_seq);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAVLINK_STATS_TM, buf, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-#else
- mavlink_mavlink_stats_tm_t *packet = (mavlink_mavlink_stats_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->parse_state = parse_state;
- packet->n_send_queue = n_send_queue;
- packet->max_send_queue = max_send_queue;
- packet->n_send_errors = n_send_errors;
- packet->packet_rx_success_count = packet_rx_success_count;
- packet->packet_rx_drop_count = packet_rx_drop_count;
- packet->msg_received = msg_received;
- packet->buffer_overrun = buffer_overrun;
- packet->parse_error = parse_error;
- packet->packet_idx = packet_idx;
- packet->current_rx_seq = current_rx_seq;
- packet->current_tx_seq = current_tx_seq;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAVLINK_STATS_TM, (const char *)packet, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE MAVLINK_STATS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from mavlink_stats_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_mavlink_stats_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field n_send_queue from mavlink_stats_tm message
- *
- * @return Current len of the occupied portion of the queue
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_get_n_send_queue(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 12);
-}
-
-/**
- * @brief Get field max_send_queue from mavlink_stats_tm message
- *
- * @return Max occupied len of the queue
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_get_max_send_queue(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 14);
-}
-
-/**
- * @brief Get field n_send_errors from mavlink_stats_tm message
- *
- * @return Number of packet not sent correctly by the TMTC
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_get_n_send_errors(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 16);
-}
-
-/**
- * @brief Get field msg_received from mavlink_stats_tm message
- *
- * @return Number of received messages
- */
-static inline uint8_t mavlink_msg_mavlink_stats_tm_get_msg_received(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 22);
-}
-
-/**
- * @brief Get field buffer_overrun from mavlink_stats_tm message
- *
- * @return Number of buffer overruns
- */
-static inline uint8_t mavlink_msg_mavlink_stats_tm_get_buffer_overrun(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 23);
-}
-
-/**
- * @brief Get field parse_error from mavlink_stats_tm message
- *
- * @return Number of parse errors
- */
-static inline uint8_t mavlink_msg_mavlink_stats_tm_get_parse_error(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 24);
-}
-
-/**
- * @brief Get field parse_state from mavlink_stats_tm message
- *
- * @return Parsing state machine
- */
-static inline uint32_t mavlink_msg_mavlink_stats_tm_get_parse_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 8);
-}
-
-/**
- * @brief Get field packet_idx from mavlink_stats_tm message
- *
- * @return Index in current packet
- */
-static inline uint8_t mavlink_msg_mavlink_stats_tm_get_packet_idx(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 25);
-}
-
-/**
- * @brief Get field current_rx_seq from mavlink_stats_tm message
- *
- * @return Sequence number of last packet received
- */
-static inline uint8_t mavlink_msg_mavlink_stats_tm_get_current_rx_seq(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 26);
-}
-
-/**
- * @brief Get field current_tx_seq from mavlink_stats_tm message
- *
- * @return Sequence number of last packet sent
- */
-static inline uint8_t mavlink_msg_mavlink_stats_tm_get_current_tx_seq(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 27);
-}
-
-/**
- * @brief Get field packet_rx_success_count from mavlink_stats_tm message
- *
- * @return Received packets
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_get_packet_rx_success_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 18);
-}
-
-/**
- * @brief Get field packet_rx_drop_count from mavlink_stats_tm message
- *
- * @return Number of packet drops
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_get_packet_rx_drop_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 20);
-}
-
-/**
- * @brief Decode a mavlink_stats_tm message into a struct
- *
- * @param msg The message to decode
- * @param mavlink_stats_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_mavlink_stats_tm_decode(const mavlink_message_t* msg, mavlink_mavlink_stats_tm_t* mavlink_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_stats_tm->timestamp = mavlink_msg_mavlink_stats_tm_get_timestamp(msg);
- mavlink_stats_tm->parse_state = mavlink_msg_mavlink_stats_tm_get_parse_state(msg);
- mavlink_stats_tm->n_send_queue = mavlink_msg_mavlink_stats_tm_get_n_send_queue(msg);
- mavlink_stats_tm->max_send_queue = mavlink_msg_mavlink_stats_tm_get_max_send_queue(msg);
- mavlink_stats_tm->n_send_errors = mavlink_msg_mavlink_stats_tm_get_n_send_errors(msg);
- mavlink_stats_tm->packet_rx_success_count = mavlink_msg_mavlink_stats_tm_get_packet_rx_success_count(msg);
- mavlink_stats_tm->packet_rx_drop_count = mavlink_msg_mavlink_stats_tm_get_packet_rx_drop_count(msg);
- mavlink_stats_tm->msg_received = mavlink_msg_mavlink_stats_tm_get_msg_received(msg);
- mavlink_stats_tm->buffer_overrun = mavlink_msg_mavlink_stats_tm_get_buffer_overrun(msg);
- mavlink_stats_tm->parse_error = mavlink_msg_mavlink_stats_tm_get_parse_error(msg);
- mavlink_stats_tm->packet_idx = mavlink_msg_mavlink_stats_tm_get_packet_idx(msg);
- mavlink_stats_tm->current_rx_seq = mavlink_msg_mavlink_stats_tm_get_current_rx_seq(msg);
- mavlink_stats_tm->current_tx_seq = mavlink_msg_mavlink_stats_tm_get_current_tx_seq(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN? msg->len : MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN;
- memset(mavlink_stats_tm, 0, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN);
- memcpy(mavlink_stats_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_mea_tm.h b/mavlink_lib/gemini/mavlink_msg_mea_tm.h
deleted file mode 100644
index a3887d7e6363b14616deca868632f1fc6c0d3b26..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_mea_tm.h
+++ /dev/null
@@ -1,363 +0,0 @@
-#pragma once
-// MESSAGE MEA_TM PACKING
-
-#define MAVLINK_MSG_ID_MEA_TM 207
-
-
-typedef struct __mavlink_mea_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float kalman_x0; /*< Kalman state variable 0 (corrected pressure)*/
- float kalman_x1; /*< Kalman state variable 1 */
- float kalman_x2; /*< Kalman state variable 2 (mass)*/
- float mass; /*< [kg] Mass estimated*/
- float corrected_pressure; /*< [kg] Corrected pressure*/
- uint8_t state; /*< MEA current state*/
-} mavlink_mea_tm_t;
-
-#define MAVLINK_MSG_ID_MEA_TM_LEN 29
-#define MAVLINK_MSG_ID_MEA_TM_MIN_LEN 29
-#define MAVLINK_MSG_ID_207_LEN 29
-#define MAVLINK_MSG_ID_207_MIN_LEN 29
-
-#define MAVLINK_MSG_ID_MEA_TM_CRC 11
-#define MAVLINK_MSG_ID_207_CRC 11
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_MEA_TM { \
- 207, \
- "MEA_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_mea_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_mea_tm_t, state) }, \
- { "kalman_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mea_tm_t, kalman_x0) }, \
- { "kalman_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mea_tm_t, kalman_x1) }, \
- { "kalman_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mea_tm_t, kalman_x2) }, \
- { "mass", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mea_tm_t, mass) }, \
- { "corrected_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mea_tm_t, corrected_pressure) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_MEA_TM { \
- "MEA_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_mea_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_mea_tm_t, state) }, \
- { "kalman_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mea_tm_t, kalman_x0) }, \
- { "kalman_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mea_tm_t, kalman_x1) }, \
- { "kalman_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mea_tm_t, kalman_x2) }, \
- { "mass", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mea_tm_t, mass) }, \
- { "corrected_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mea_tm_t, corrected_pressure) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a mea_tm 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] When was this logged
- * @param state MEA current state
- * @param kalman_x0 Kalman state variable 0 (corrected pressure)
- * @param kalman_x1 Kalman state variable 1
- * @param kalman_x2 Kalman state variable 2 (mass)
- * @param mass [kg] Mass estimated
- * @param corrected_pressure [kg] Corrected pressure
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_mea_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float mass, float corrected_pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MEA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, kalman_x0);
- _mav_put_float(buf, 12, kalman_x1);
- _mav_put_float(buf, 16, kalman_x2);
- _mav_put_float(buf, 20, mass);
- _mav_put_float(buf, 24, corrected_pressure);
- _mav_put_uint8_t(buf, 28, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEA_TM_LEN);
-#else
- mavlink_mea_tm_t packet;
- packet.timestamp = timestamp;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.mass = mass;
- packet.corrected_pressure = corrected_pressure;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEA_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_MEA_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
-}
-
-/**
- * @brief Pack a mea_tm 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] When was this logged
- * @param state MEA current state
- * @param kalman_x0 Kalman state variable 0 (corrected pressure)
- * @param kalman_x1 Kalman state variable 1
- * @param kalman_x2 Kalman state variable 2 (mass)
- * @param mass [kg] Mass estimated
- * @param corrected_pressure [kg] Corrected pressure
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_mea_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t state,float kalman_x0,float kalman_x1,float kalman_x2,float mass,float corrected_pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MEA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, kalman_x0);
- _mav_put_float(buf, 12, kalman_x1);
- _mav_put_float(buf, 16, kalman_x2);
- _mav_put_float(buf, 20, mass);
- _mav_put_float(buf, 24, corrected_pressure);
- _mav_put_uint8_t(buf, 28, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEA_TM_LEN);
-#else
- mavlink_mea_tm_t packet;
- packet.timestamp = timestamp;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.mass = mass;
- packet.corrected_pressure = corrected_pressure;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEA_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_MEA_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
-}
-
-/**
- * @brief Encode a mea_tm 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 mea_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_mea_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mea_tm_t* mea_tm)
-{
- return mavlink_msg_mea_tm_pack(system_id, component_id, msg, mea_tm->timestamp, mea_tm->state, mea_tm->kalman_x0, mea_tm->kalman_x1, mea_tm->kalman_x2, mea_tm->mass, mea_tm->corrected_pressure);
-}
-
-/**
- * @brief Encode a mea_tm 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 mea_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_mea_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mea_tm_t* mea_tm)
-{
- return mavlink_msg_mea_tm_pack_chan(system_id, component_id, chan, msg, mea_tm->timestamp, mea_tm->state, mea_tm->kalman_x0, mea_tm->kalman_x1, mea_tm->kalman_x2, mea_tm->mass, mea_tm->corrected_pressure);
-}
-
-/**
- * @brief Send a mea_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param state MEA current state
- * @param kalman_x0 Kalman state variable 0 (corrected pressure)
- * @param kalman_x1 Kalman state variable 1
- * @param kalman_x2 Kalman state variable 2 (mass)
- * @param mass [kg] Mass estimated
- * @param corrected_pressure [kg] Corrected pressure
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_mea_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float mass, float corrected_pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MEA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, kalman_x0);
- _mav_put_float(buf, 12, kalman_x1);
- _mav_put_float(buf, 16, kalman_x2);
- _mav_put_float(buf, 20, mass);
- _mav_put_float(buf, 24, corrected_pressure);
- _mav_put_uint8_t(buf, 28, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEA_TM, buf, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
-#else
- mavlink_mea_tm_t packet;
- packet.timestamp = timestamp;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.mass = mass;
- packet.corrected_pressure = corrected_pressure;
- packet.state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEA_TM, (const char *)&packet, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a mea_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_mea_tm_send_struct(mavlink_channel_t chan, const mavlink_mea_tm_t* mea_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_mea_tm_send(chan, mea_tm->timestamp, mea_tm->state, mea_tm->kalman_x0, mea_tm->kalman_x1, mea_tm->kalman_x2, mea_tm->mass, mea_tm->corrected_pressure);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEA_TM, (const char *)mea_tm, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_MEA_TM_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_mea_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float mass, float corrected_pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, kalman_x0);
- _mav_put_float(buf, 12, kalman_x1);
- _mav_put_float(buf, 16, kalman_x2);
- _mav_put_float(buf, 20, mass);
- _mav_put_float(buf, 24, corrected_pressure);
- _mav_put_uint8_t(buf, 28, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEA_TM, buf, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
-#else
- mavlink_mea_tm_t *packet = (mavlink_mea_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->kalman_x0 = kalman_x0;
- packet->kalman_x1 = kalman_x1;
- packet->kalman_x2 = kalman_x2;
- packet->mass = mass;
- packet->corrected_pressure = corrected_pressure;
- packet->state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEA_TM, (const char *)packet, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE MEA_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from mea_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_mea_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field state from mea_tm message
- *
- * @return MEA current state
- */
-static inline uint8_t mavlink_msg_mea_tm_get_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 28);
-}
-
-/**
- * @brief Get field kalman_x0 from mea_tm message
- *
- * @return Kalman state variable 0 (corrected pressure)
- */
-static inline float mavlink_msg_mea_tm_get_kalman_x0(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field kalman_x1 from mea_tm message
- *
- * @return Kalman state variable 1
- */
-static inline float mavlink_msg_mea_tm_get_kalman_x1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field kalman_x2 from mea_tm message
- *
- * @return Kalman state variable 2 (mass)
- */
-static inline float mavlink_msg_mea_tm_get_kalman_x2(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field mass from mea_tm message
- *
- * @return [kg] Mass estimated
- */
-static inline float mavlink_msg_mea_tm_get_mass(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field corrected_pressure from mea_tm message
- *
- * @return [kg] Corrected pressure
- */
-static inline float mavlink_msg_mea_tm_get_corrected_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Decode a mea_tm message into a struct
- *
- * @param msg The message to decode
- * @param mea_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_mea_tm_decode(const mavlink_message_t* msg, mavlink_mea_tm_t* mea_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mea_tm->timestamp = mavlink_msg_mea_tm_get_timestamp(msg);
- mea_tm->kalman_x0 = mavlink_msg_mea_tm_get_kalman_x0(msg);
- mea_tm->kalman_x1 = mavlink_msg_mea_tm_get_kalman_x1(msg);
- mea_tm->kalman_x2 = mavlink_msg_mea_tm_get_kalman_x2(msg);
- mea_tm->mass = mavlink_msg_mea_tm_get_mass(msg);
- mea_tm->corrected_pressure = mavlink_msg_mea_tm_get_corrected_pressure(msg);
- mea_tm->state = mavlink_msg_mea_tm_get_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_MEA_TM_LEN? msg->len : MAVLINK_MSG_ID_MEA_TM_LEN;
- memset(mea_tm, 0, MAVLINK_MSG_ID_MEA_TM_LEN);
- memcpy(mea_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_motor_tm.h b/mavlink_lib/gemini/mavlink_msg_motor_tm.h
deleted file mode 100644
index 25643d25c37da50e8d0f474b4649b81d103b7ab4..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_motor_tm.h
+++ /dev/null
@@ -1,438 +0,0 @@
-#pragma once
-// MESSAGE MOTOR_TM PACKING
-
-#define MAVLINK_MSG_ID_MOTOR_TM 213
-
-
-typedef struct __mavlink_motor_tm_t {
- uint64_t timestamp; /*< [us] Timestamp in microseconds*/
- float top_tank_pressure; /*< [Bar] Tank upper pressure*/
- float bottom_tank_pressure; /*< [Bar] Tank bottom pressure*/
- float combustion_chamber_pressure; /*< [Bar] Pressure inside the combustion chamber used for automatic shutdown*/
- float tank_temperature; /*< Tank temperature*/
- float battery_voltage; /*< [V] Battery voltage*/
- float current_consumption; /*< [A] Current drained from the battery*/
- uint8_t floating_level; /*< Floating level in tank*/
- uint8_t main_valve_state; /*< 1 If the main valve is open */
- uint8_t venting_valve_state; /*< 1 If the venting valve is open */
-} mavlink_motor_tm_t;
-
-#define MAVLINK_MSG_ID_MOTOR_TM_LEN 35
-#define MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN 35
-#define MAVLINK_MSG_ID_213_LEN 35
-#define MAVLINK_MSG_ID_213_MIN_LEN 35
-
-#define MAVLINK_MSG_ID_MOTOR_TM_CRC 79
-#define MAVLINK_MSG_ID_213_CRC 79
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_MOTOR_TM { \
- 213, \
- "MOTOR_TM", \
- 10, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_motor_tm_t, timestamp) }, \
- { "top_tank_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_motor_tm_t, top_tank_pressure) }, \
- { "bottom_tank_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_motor_tm_t, bottom_tank_pressure) }, \
- { "combustion_chamber_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_motor_tm_t, combustion_chamber_pressure) }, \
- { "floating_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_motor_tm_t, floating_level) }, \
- { "tank_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_motor_tm_t, tank_temperature) }, \
- { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_motor_tm_t, main_valve_state) }, \
- { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_motor_tm_t, venting_valve_state) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_motor_tm_t, battery_voltage) }, \
- { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_motor_tm_t, current_consumption) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_MOTOR_TM { \
- "MOTOR_TM", \
- 10, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_motor_tm_t, timestamp) }, \
- { "top_tank_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_motor_tm_t, top_tank_pressure) }, \
- { "bottom_tank_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_motor_tm_t, bottom_tank_pressure) }, \
- { "combustion_chamber_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_motor_tm_t, combustion_chamber_pressure) }, \
- { "floating_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_motor_tm_t, floating_level) }, \
- { "tank_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_motor_tm_t, tank_temperature) }, \
- { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_motor_tm_t, main_valve_state) }, \
- { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_motor_tm_t, venting_valve_state) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_motor_tm_t, battery_voltage) }, \
- { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_motor_tm_t, current_consumption) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a motor_tm 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 in microseconds
- * @param top_tank_pressure [Bar] Tank upper pressure
- * @param bottom_tank_pressure [Bar] Tank bottom pressure
- * @param combustion_chamber_pressure [Bar] Pressure inside the combustion chamber used for automatic shutdown
- * @param floating_level Floating level in tank
- * @param tank_temperature Tank temperature
- * @param main_valve_state 1 If the main valve is open
- * @param venting_valve_state 1 If the venting valve is open
- * @param battery_voltage [V] Battery voltage
- * @param current_consumption [A] Current drained from the battery
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_motor_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, uint8_t floating_level, float tank_temperature, uint8_t main_valve_state, uint8_t venting_valve_state, float battery_voltage, float current_consumption)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MOTOR_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, top_tank_pressure);
- _mav_put_float(buf, 12, bottom_tank_pressure);
- _mav_put_float(buf, 16, combustion_chamber_pressure);
- _mav_put_float(buf, 20, tank_temperature);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_float(buf, 28, current_consumption);
- _mav_put_uint8_t(buf, 32, floating_level);
- _mav_put_uint8_t(buf, 33, main_valve_state);
- _mav_put_uint8_t(buf, 34, venting_valve_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOTOR_TM_LEN);
-#else
- mavlink_motor_tm_t packet;
- packet.timestamp = timestamp;
- packet.top_tank_pressure = top_tank_pressure;
- packet.bottom_tank_pressure = bottom_tank_pressure;
- packet.combustion_chamber_pressure = combustion_chamber_pressure;
- packet.tank_temperature = tank_temperature;
- packet.battery_voltage = battery_voltage;
- packet.current_consumption = current_consumption;
- packet.floating_level = floating_level;
- packet.main_valve_state = main_valve_state;
- packet.venting_valve_state = venting_valve_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOTOR_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_MOTOR_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
-}
-
-/**
- * @brief Pack a motor_tm 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 in microseconds
- * @param top_tank_pressure [Bar] Tank upper pressure
- * @param bottom_tank_pressure [Bar] Tank bottom pressure
- * @param combustion_chamber_pressure [Bar] Pressure inside the combustion chamber used for automatic shutdown
- * @param floating_level Floating level in tank
- * @param tank_temperature Tank temperature
- * @param main_valve_state 1 If the main valve is open
- * @param venting_valve_state 1 If the venting valve is open
- * @param battery_voltage [V] Battery voltage
- * @param current_consumption [A] Current drained from the battery
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_motor_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,float top_tank_pressure,float bottom_tank_pressure,float combustion_chamber_pressure,uint8_t floating_level,float tank_temperature,uint8_t main_valve_state,uint8_t venting_valve_state,float battery_voltage,float current_consumption)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MOTOR_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, top_tank_pressure);
- _mav_put_float(buf, 12, bottom_tank_pressure);
- _mav_put_float(buf, 16, combustion_chamber_pressure);
- _mav_put_float(buf, 20, tank_temperature);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_float(buf, 28, current_consumption);
- _mav_put_uint8_t(buf, 32, floating_level);
- _mav_put_uint8_t(buf, 33, main_valve_state);
- _mav_put_uint8_t(buf, 34, venting_valve_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOTOR_TM_LEN);
-#else
- mavlink_motor_tm_t packet;
- packet.timestamp = timestamp;
- packet.top_tank_pressure = top_tank_pressure;
- packet.bottom_tank_pressure = bottom_tank_pressure;
- packet.combustion_chamber_pressure = combustion_chamber_pressure;
- packet.tank_temperature = tank_temperature;
- packet.battery_voltage = battery_voltage;
- packet.current_consumption = current_consumption;
- packet.floating_level = floating_level;
- packet.main_valve_state = main_valve_state;
- packet.venting_valve_state = venting_valve_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOTOR_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_MOTOR_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
-}
-
-/**
- * @brief Encode a motor_tm 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 motor_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_motor_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_motor_tm_t* motor_tm)
-{
- return mavlink_msg_motor_tm_pack(system_id, component_id, msg, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->floating_level, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->venting_valve_state, motor_tm->battery_voltage, motor_tm->current_consumption);
-}
-
-/**
- * @brief Encode a motor_tm 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 motor_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_motor_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_motor_tm_t* motor_tm)
-{
- return mavlink_msg_motor_tm_pack_chan(system_id, component_id, chan, msg, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->floating_level, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->venting_valve_state, motor_tm->battery_voltage, motor_tm->current_consumption);
-}
-
-/**
- * @brief Send a motor_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp in microseconds
- * @param top_tank_pressure [Bar] Tank upper pressure
- * @param bottom_tank_pressure [Bar] Tank bottom pressure
- * @param combustion_chamber_pressure [Bar] Pressure inside the combustion chamber used for automatic shutdown
- * @param floating_level Floating level in tank
- * @param tank_temperature Tank temperature
- * @param main_valve_state 1 If the main valve is open
- * @param venting_valve_state 1 If the venting valve is open
- * @param battery_voltage [V] Battery voltage
- * @param current_consumption [A] Current drained from the battery
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_motor_tm_send(mavlink_channel_t chan, uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, uint8_t floating_level, float tank_temperature, uint8_t main_valve_state, uint8_t venting_valve_state, float battery_voltage, float current_consumption)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MOTOR_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, top_tank_pressure);
- _mav_put_float(buf, 12, bottom_tank_pressure);
- _mav_put_float(buf, 16, combustion_chamber_pressure);
- _mav_put_float(buf, 20, tank_temperature);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_float(buf, 28, current_consumption);
- _mav_put_uint8_t(buf, 32, floating_level);
- _mav_put_uint8_t(buf, 33, main_valve_state);
- _mav_put_uint8_t(buf, 34, venting_valve_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOTOR_TM, buf, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
-#else
- mavlink_motor_tm_t packet;
- packet.timestamp = timestamp;
- packet.top_tank_pressure = top_tank_pressure;
- packet.bottom_tank_pressure = bottom_tank_pressure;
- packet.combustion_chamber_pressure = combustion_chamber_pressure;
- packet.tank_temperature = tank_temperature;
- packet.battery_voltage = battery_voltage;
- packet.current_consumption = current_consumption;
- packet.floating_level = floating_level;
- packet.main_valve_state = main_valve_state;
- packet.venting_valve_state = venting_valve_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOTOR_TM, (const char *)&packet, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a motor_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_motor_tm_send_struct(mavlink_channel_t chan, const mavlink_motor_tm_t* motor_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_motor_tm_send(chan, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->floating_level, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->venting_valve_state, motor_tm->battery_voltage, motor_tm->current_consumption);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOTOR_TM, (const char *)motor_tm, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_MOTOR_TM_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_motor_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, uint8_t floating_level, float tank_temperature, uint8_t main_valve_state, uint8_t venting_valve_state, float battery_voltage, float current_consumption)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, top_tank_pressure);
- _mav_put_float(buf, 12, bottom_tank_pressure);
- _mav_put_float(buf, 16, combustion_chamber_pressure);
- _mav_put_float(buf, 20, tank_temperature);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_float(buf, 28, current_consumption);
- _mav_put_uint8_t(buf, 32, floating_level);
- _mav_put_uint8_t(buf, 33, main_valve_state);
- _mav_put_uint8_t(buf, 34, venting_valve_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOTOR_TM, buf, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
-#else
- mavlink_motor_tm_t *packet = (mavlink_motor_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->top_tank_pressure = top_tank_pressure;
- packet->bottom_tank_pressure = bottom_tank_pressure;
- packet->combustion_chamber_pressure = combustion_chamber_pressure;
- packet->tank_temperature = tank_temperature;
- packet->battery_voltage = battery_voltage;
- packet->current_consumption = current_consumption;
- packet->floating_level = floating_level;
- packet->main_valve_state = main_valve_state;
- packet->venting_valve_state = venting_valve_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOTOR_TM, (const char *)packet, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE MOTOR_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from motor_tm message
- *
- * @return [us] Timestamp in microseconds
- */
-static inline uint64_t mavlink_msg_motor_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field top_tank_pressure from motor_tm message
- *
- * @return [Bar] Tank upper pressure
- */
-static inline float mavlink_msg_motor_tm_get_top_tank_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field bottom_tank_pressure from motor_tm message
- *
- * @return [Bar] Tank bottom pressure
- */
-static inline float mavlink_msg_motor_tm_get_bottom_tank_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field combustion_chamber_pressure from motor_tm message
- *
- * @return [Bar] Pressure inside the combustion chamber used for automatic shutdown
- */
-static inline float mavlink_msg_motor_tm_get_combustion_chamber_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field floating_level from motor_tm message
- *
- * @return Floating level in tank
- */
-static inline uint8_t mavlink_msg_motor_tm_get_floating_level(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 32);
-}
-
-/**
- * @brief Get field tank_temperature from motor_tm message
- *
- * @return Tank temperature
- */
-static inline float mavlink_msg_motor_tm_get_tank_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field main_valve_state from motor_tm message
- *
- * @return 1 If the main valve is open
- */
-static inline uint8_t mavlink_msg_motor_tm_get_main_valve_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 33);
-}
-
-/**
- * @brief Get field venting_valve_state from motor_tm message
- *
- * @return 1 If the venting valve is open
- */
-static inline uint8_t mavlink_msg_motor_tm_get_venting_valve_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 34);
-}
-
-/**
- * @brief Get field battery_voltage from motor_tm message
- *
- * @return [V] Battery voltage
- */
-static inline float mavlink_msg_motor_tm_get_battery_voltage(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field current_consumption from motor_tm message
- *
- * @return [A] Current drained from the battery
- */
-static inline float mavlink_msg_motor_tm_get_current_consumption(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Decode a motor_tm message into a struct
- *
- * @param msg The message to decode
- * @param motor_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_motor_tm_decode(const mavlink_message_t* msg, mavlink_motor_tm_t* motor_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- motor_tm->timestamp = mavlink_msg_motor_tm_get_timestamp(msg);
- motor_tm->top_tank_pressure = mavlink_msg_motor_tm_get_top_tank_pressure(msg);
- motor_tm->bottom_tank_pressure = mavlink_msg_motor_tm_get_bottom_tank_pressure(msg);
- motor_tm->combustion_chamber_pressure = mavlink_msg_motor_tm_get_combustion_chamber_pressure(msg);
- motor_tm->tank_temperature = mavlink_msg_motor_tm_get_tank_temperature(msg);
- motor_tm->battery_voltage = mavlink_msg_motor_tm_get_battery_voltage(msg);
- motor_tm->current_consumption = mavlink_msg_motor_tm_get_current_consumption(msg);
- motor_tm->floating_level = mavlink_msg_motor_tm_get_floating_level(msg);
- motor_tm->main_valve_state = mavlink_msg_motor_tm_get_main_valve_state(msg);
- motor_tm->venting_valve_state = mavlink_msg_motor_tm_get_venting_valve_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_MOTOR_TM_LEN? msg->len : MAVLINK_MSG_ID_MOTOR_TM_LEN;
- memset(motor_tm, 0, MAVLINK_MSG_ID_MOTOR_TM_LEN);
- memcpy(motor_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_nack_tm.h b/mavlink_lib/gemini/mavlink_msg_nack_tm.h
deleted file mode 100644
index 85abd048c50911cd99ded380f566cf5c34b29322..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_nack_tm.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE NACK_TM PACKING
-
-#define MAVLINK_MSG_ID_NACK_TM 101
-
-
-typedef struct __mavlink_nack_tm_t {
- uint8_t recv_msgid; /*< Message id of the received message*/
- uint8_t seq_ack; /*< Sequence number of the received message*/
-} mavlink_nack_tm_t;
-
-#define MAVLINK_MSG_ID_NACK_TM_LEN 2
-#define MAVLINK_MSG_ID_NACK_TM_MIN_LEN 2
-#define MAVLINK_MSG_ID_101_LEN 2
-#define MAVLINK_MSG_ID_101_MIN_LEN 2
-
-#define MAVLINK_MSG_ID_NACK_TM_CRC 146
-#define MAVLINK_MSG_ID_101_CRC 146
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_NACK_TM { \
- 101, \
- "NACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_nack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_nack_tm_t, seq_ack) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_NACK_TM { \
- "NACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_nack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_nack_tm_t, seq_ack) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a nack_tm 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 recv_msgid Message id of the received message
- * @param seq_ack Sequence number of the received message
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_nack_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NACK_TM_LEN);
-#else
- mavlink_nack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NACK_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-}
-
-/**
- * @brief Pack a nack_tm 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 recv_msgid Message id of the received message
- * @param seq_ack Sequence number of the received message
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_nack_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t recv_msgid,uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NACK_TM_LEN);
-#else
- mavlink_nack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NACK_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-}
-
-/**
- * @brief Encode a nack_tm 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 nack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_nack_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nack_tm_t* nack_tm)
-{
- return mavlink_msg_nack_tm_pack(system_id, component_id, msg, nack_tm->recv_msgid, nack_tm->seq_ack);
-}
-
-/**
- * @brief Encode a nack_tm 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 nack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_nack_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nack_tm_t* nack_tm)
-{
- return mavlink_msg_nack_tm_pack_chan(system_id, component_id, chan, msg, nack_tm->recv_msgid, nack_tm->seq_ack);
-}
-
-/**
- * @brief Send a nack_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param recv_msgid Message id of the received message
- * @param seq_ack Sequence number of the received message
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_nack_tm_send(mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, buf, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#else
- mavlink_nack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, (const char *)&packet, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a nack_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_nack_tm_send_struct(mavlink_channel_t chan, const mavlink_nack_tm_t* nack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_nack_tm_send(chan, nack_tm->recv_msgid, nack_tm->seq_ack);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, (const char *)nack_tm, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_NACK_TM_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_nack_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, buf, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#else
- mavlink_nack_tm_t *packet = (mavlink_nack_tm_t *)msgbuf;
- packet->recv_msgid = recv_msgid;
- packet->seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, (const char *)packet, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE NACK_TM UNPACKING
-
-
-/**
- * @brief Get field recv_msgid from nack_tm message
- *
- * @return Message id of the received message
- */
-static inline uint8_t mavlink_msg_nack_tm_get_recv_msgid(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field seq_ack from nack_tm message
- *
- * @return Sequence number of the received message
- */
-static inline uint8_t mavlink_msg_nack_tm_get_seq_ack(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Decode a nack_tm message into a struct
- *
- * @param msg The message to decode
- * @param nack_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_nack_tm_decode(const mavlink_message_t* msg, mavlink_nack_tm_t* nack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- nack_tm->recv_msgid = mavlink_msg_nack_tm_get_recv_msgid(msg);
- nack_tm->seq_ack = mavlink_msg_nack_tm_get_seq_ack(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_NACK_TM_LEN? msg->len : MAVLINK_MSG_ID_NACK_TM_LEN;
- memset(nack_tm, 0, MAVLINK_MSG_ID_NACK_TM_LEN);
- memcpy(nack_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_nas_tm.h b/mavlink_lib/gemini/mavlink_msg_nas_tm.h
deleted file mode 100644
index e91b837c04d4e2bc46c3226696f68c32890b9f08..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_nas_tm.h
+++ /dev/null
@@ -1,663 +0,0 @@
-#pragma once
-// MESSAGE NAS_TM PACKING
-
-#define MAVLINK_MSG_ID_NAS_TM 206
-
-
-typedef struct __mavlink_nas_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float nas_n; /*< [deg] Navigation system estimated noth position*/
- float nas_e; /*< [deg] Navigation system estimated east position*/
- float nas_d; /*< [m] Navigation system estimated down position*/
- float nas_vn; /*< [m/s] Navigation system estimated north velocity*/
- float nas_ve; /*< [m/s] Navigation system estimated east velocity*/
- float nas_vd; /*< [m/s] Navigation system estimated down velocity*/
- float nas_qx; /*< [deg] Navigation system estimated attitude (qx)*/
- float nas_qy; /*< [deg] Navigation system estimated attitude (qy)*/
- float nas_qz; /*< [deg] Navigation system estimated attitude (qz)*/
- float nas_qw; /*< [deg] Navigation system estimated attitude (qw)*/
- float nas_bias_x; /*< Navigation system gyroscope bias on x axis*/
- float nas_bias_y; /*< Navigation system gyroscope bias on y axis*/
- float nas_bias_z; /*< Navigation system gyroscope bias on z axis*/
- float ref_pressure; /*< [Pa] Calibration pressure*/
- float ref_temperature; /*< [degC] Calibration temperature*/
- float ref_latitude; /*< [deg] Calibration latitude*/
- float ref_longitude; /*< [deg] Calibration longitude*/
- uint8_t state; /*< NAS current state*/
-} mavlink_nas_tm_t;
-
-#define MAVLINK_MSG_ID_NAS_TM_LEN 77
-#define MAVLINK_MSG_ID_NAS_TM_MIN_LEN 77
-#define MAVLINK_MSG_ID_206_LEN 77
-#define MAVLINK_MSG_ID_206_MIN_LEN 77
-
-#define MAVLINK_MSG_ID_NAS_TM_CRC 66
-#define MAVLINK_MSG_ID_206_CRC 66
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_NAS_TM { \
- 206, \
- "NAS_TM", \
- 19, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_nas_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 76, offsetof(mavlink_nas_tm_t, state) }, \
- { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nas_tm_t, nas_n) }, \
- { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nas_tm_t, nas_e) }, \
- { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nas_tm_t, nas_d) }, \
- { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_nas_tm_t, nas_vn) }, \
- { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_nas_tm_t, nas_ve) }, \
- { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_nas_tm_t, nas_vd) }, \
- { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_nas_tm_t, nas_qx) }, \
- { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_nas_tm_t, nas_qy) }, \
- { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_nas_tm_t, nas_qz) }, \
- { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_nas_tm_t, nas_qw) }, \
- { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_nas_tm_t, nas_bias_x) }, \
- { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_nas_tm_t, nas_bias_y) }, \
- { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_nas_tm_t, nas_bias_z) }, \
- { "ref_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_nas_tm_t, ref_pressure) }, \
- { "ref_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_nas_tm_t, ref_temperature) }, \
- { "ref_latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_nas_tm_t, ref_latitude) }, \
- { "ref_longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_nas_tm_t, ref_longitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_NAS_TM { \
- "NAS_TM", \
- 19, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_nas_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 76, offsetof(mavlink_nas_tm_t, state) }, \
- { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nas_tm_t, nas_n) }, \
- { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nas_tm_t, nas_e) }, \
- { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nas_tm_t, nas_d) }, \
- { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_nas_tm_t, nas_vn) }, \
- { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_nas_tm_t, nas_ve) }, \
- { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_nas_tm_t, nas_vd) }, \
- { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_nas_tm_t, nas_qx) }, \
- { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_nas_tm_t, nas_qy) }, \
- { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_nas_tm_t, nas_qz) }, \
- { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_nas_tm_t, nas_qw) }, \
- { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_nas_tm_t, nas_bias_x) }, \
- { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_nas_tm_t, nas_bias_y) }, \
- { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_nas_tm_t, nas_bias_z) }, \
- { "ref_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_nas_tm_t, ref_pressure) }, \
- { "ref_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_nas_tm_t, ref_temperature) }, \
- { "ref_latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_nas_tm_t, ref_latitude) }, \
- { "ref_longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_nas_tm_t, ref_longitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a nas_tm 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] When was this logged
- * @param state NAS current state
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on y axis
- * @param nas_bias_z Navigation system gyroscope bias on z axis
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_temperature [degC] Calibration temperature
- * @param ref_latitude [deg] Calibration latitude
- * @param ref_longitude [deg] Calibration longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_nas_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t state, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float ref_pressure, float ref_temperature, float ref_latitude, float ref_longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NAS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, nas_n);
- _mav_put_float(buf, 12, nas_e);
- _mav_put_float(buf, 16, nas_d);
- _mav_put_float(buf, 20, nas_vn);
- _mav_put_float(buf, 24, nas_ve);
- _mav_put_float(buf, 28, nas_vd);
- _mav_put_float(buf, 32, nas_qx);
- _mav_put_float(buf, 36, nas_qy);
- _mav_put_float(buf, 40, nas_qz);
- _mav_put_float(buf, 44, nas_qw);
- _mav_put_float(buf, 48, nas_bias_x);
- _mav_put_float(buf, 52, nas_bias_y);
- _mav_put_float(buf, 56, nas_bias_z);
- _mav_put_float(buf, 60, ref_pressure);
- _mav_put_float(buf, 64, ref_temperature);
- _mav_put_float(buf, 68, ref_latitude);
- _mav_put_float(buf, 72, ref_longitude);
- _mav_put_uint8_t(buf, 76, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAS_TM_LEN);
-#else
- mavlink_nas_tm_t packet;
- packet.timestamp = timestamp;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.ref_pressure = ref_pressure;
- packet.ref_temperature = ref_temperature;
- packet.ref_latitude = ref_latitude;
- packet.ref_longitude = ref_longitude;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NAS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-}
-
-/**
- * @brief Pack a nas_tm 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] When was this logged
- * @param state NAS current state
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on y axis
- * @param nas_bias_z Navigation system gyroscope bias on z axis
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_temperature [degC] Calibration temperature
- * @param ref_latitude [deg] Calibration latitude
- * @param ref_longitude [deg] Calibration longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_nas_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t state,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,float ref_pressure,float ref_temperature,float ref_latitude,float ref_longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NAS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, nas_n);
- _mav_put_float(buf, 12, nas_e);
- _mav_put_float(buf, 16, nas_d);
- _mav_put_float(buf, 20, nas_vn);
- _mav_put_float(buf, 24, nas_ve);
- _mav_put_float(buf, 28, nas_vd);
- _mav_put_float(buf, 32, nas_qx);
- _mav_put_float(buf, 36, nas_qy);
- _mav_put_float(buf, 40, nas_qz);
- _mav_put_float(buf, 44, nas_qw);
- _mav_put_float(buf, 48, nas_bias_x);
- _mav_put_float(buf, 52, nas_bias_y);
- _mav_put_float(buf, 56, nas_bias_z);
- _mav_put_float(buf, 60, ref_pressure);
- _mav_put_float(buf, 64, ref_temperature);
- _mav_put_float(buf, 68, ref_latitude);
- _mav_put_float(buf, 72, ref_longitude);
- _mav_put_uint8_t(buf, 76, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAS_TM_LEN);
-#else
- mavlink_nas_tm_t packet;
- packet.timestamp = timestamp;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.ref_pressure = ref_pressure;
- packet.ref_temperature = ref_temperature;
- packet.ref_latitude = ref_latitude;
- packet.ref_longitude = ref_longitude;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NAS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-}
-
-/**
- * @brief Encode a nas_tm 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 nas_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_nas_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nas_tm_t* nas_tm)
-{
- return mavlink_msg_nas_tm_pack(system_id, component_id, msg, nas_tm->timestamp, nas_tm->state, nas_tm->nas_n, nas_tm->nas_e, nas_tm->nas_d, nas_tm->nas_vn, nas_tm->nas_ve, nas_tm->nas_vd, nas_tm->nas_qx, nas_tm->nas_qy, nas_tm->nas_qz, nas_tm->nas_qw, nas_tm->nas_bias_x, nas_tm->nas_bias_y, nas_tm->nas_bias_z, nas_tm->ref_pressure, nas_tm->ref_temperature, nas_tm->ref_latitude, nas_tm->ref_longitude);
-}
-
-/**
- * @brief Encode a nas_tm 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 nas_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_nas_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nas_tm_t* nas_tm)
-{
- return mavlink_msg_nas_tm_pack_chan(system_id, component_id, chan, msg, nas_tm->timestamp, nas_tm->state, nas_tm->nas_n, nas_tm->nas_e, nas_tm->nas_d, nas_tm->nas_vn, nas_tm->nas_ve, nas_tm->nas_vd, nas_tm->nas_qx, nas_tm->nas_qy, nas_tm->nas_qz, nas_tm->nas_qw, nas_tm->nas_bias_x, nas_tm->nas_bias_y, nas_tm->nas_bias_z, nas_tm->ref_pressure, nas_tm->ref_temperature, nas_tm->ref_latitude, nas_tm->ref_longitude);
-}
-
-/**
- * @brief Send a nas_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param state NAS current state
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on y axis
- * @param nas_bias_z Navigation system gyroscope bias on z axis
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_temperature [degC] Calibration temperature
- * @param ref_latitude [deg] Calibration latitude
- * @param ref_longitude [deg] Calibration longitude
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_nas_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float ref_pressure, float ref_temperature, float ref_latitude, float ref_longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NAS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, nas_n);
- _mav_put_float(buf, 12, nas_e);
- _mav_put_float(buf, 16, nas_d);
- _mav_put_float(buf, 20, nas_vn);
- _mav_put_float(buf, 24, nas_ve);
- _mav_put_float(buf, 28, nas_vd);
- _mav_put_float(buf, 32, nas_qx);
- _mav_put_float(buf, 36, nas_qy);
- _mav_put_float(buf, 40, nas_qz);
- _mav_put_float(buf, 44, nas_qw);
- _mav_put_float(buf, 48, nas_bias_x);
- _mav_put_float(buf, 52, nas_bias_y);
- _mav_put_float(buf, 56, nas_bias_z);
- _mav_put_float(buf, 60, ref_pressure);
- _mav_put_float(buf, 64, ref_temperature);
- _mav_put_float(buf, 68, ref_latitude);
- _mav_put_float(buf, 72, ref_longitude);
- _mav_put_uint8_t(buf, 76, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAS_TM, buf, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-#else
- mavlink_nas_tm_t packet;
- packet.timestamp = timestamp;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.ref_pressure = ref_pressure;
- packet.ref_temperature = ref_temperature;
- packet.ref_latitude = ref_latitude;
- packet.ref_longitude = ref_longitude;
- packet.state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAS_TM, (const char *)&packet, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a nas_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_nas_tm_send_struct(mavlink_channel_t chan, const mavlink_nas_tm_t* nas_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_nas_tm_send(chan, nas_tm->timestamp, nas_tm->state, nas_tm->nas_n, nas_tm->nas_e, nas_tm->nas_d, nas_tm->nas_vn, nas_tm->nas_ve, nas_tm->nas_vd, nas_tm->nas_qx, nas_tm->nas_qy, nas_tm->nas_qz, nas_tm->nas_qw, nas_tm->nas_bias_x, nas_tm->nas_bias_y, nas_tm->nas_bias_z, nas_tm->ref_pressure, nas_tm->ref_temperature, nas_tm->ref_latitude, nas_tm->ref_longitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAS_TM, (const char *)nas_tm, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_NAS_TM_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_nas_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float ref_pressure, float ref_temperature, float ref_latitude, float ref_longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, nas_n);
- _mav_put_float(buf, 12, nas_e);
- _mav_put_float(buf, 16, nas_d);
- _mav_put_float(buf, 20, nas_vn);
- _mav_put_float(buf, 24, nas_ve);
- _mav_put_float(buf, 28, nas_vd);
- _mav_put_float(buf, 32, nas_qx);
- _mav_put_float(buf, 36, nas_qy);
- _mav_put_float(buf, 40, nas_qz);
- _mav_put_float(buf, 44, nas_qw);
- _mav_put_float(buf, 48, nas_bias_x);
- _mav_put_float(buf, 52, nas_bias_y);
- _mav_put_float(buf, 56, nas_bias_z);
- _mav_put_float(buf, 60, ref_pressure);
- _mav_put_float(buf, 64, ref_temperature);
- _mav_put_float(buf, 68, ref_latitude);
- _mav_put_float(buf, 72, ref_longitude);
- _mav_put_uint8_t(buf, 76, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAS_TM, buf, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-#else
- mavlink_nas_tm_t *packet = (mavlink_nas_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->nas_n = nas_n;
- packet->nas_e = nas_e;
- packet->nas_d = nas_d;
- packet->nas_vn = nas_vn;
- packet->nas_ve = nas_ve;
- packet->nas_vd = nas_vd;
- packet->nas_qx = nas_qx;
- packet->nas_qy = nas_qy;
- packet->nas_qz = nas_qz;
- packet->nas_qw = nas_qw;
- packet->nas_bias_x = nas_bias_x;
- packet->nas_bias_y = nas_bias_y;
- packet->nas_bias_z = nas_bias_z;
- packet->ref_pressure = ref_pressure;
- packet->ref_temperature = ref_temperature;
- packet->ref_latitude = ref_latitude;
- packet->ref_longitude = ref_longitude;
- packet->state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAS_TM, (const char *)packet, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE NAS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from nas_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_nas_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field state from nas_tm message
- *
- * @return NAS current state
- */
-static inline uint8_t mavlink_msg_nas_tm_get_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 76);
-}
-
-/**
- * @brief Get field nas_n from nas_tm message
- *
- * @return [deg] Navigation system estimated noth position
- */
-static inline float mavlink_msg_nas_tm_get_nas_n(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field nas_e from nas_tm message
- *
- * @return [deg] Navigation system estimated east position
- */
-static inline float mavlink_msg_nas_tm_get_nas_e(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field nas_d from nas_tm message
- *
- * @return [m] Navigation system estimated down position
- */
-static inline float mavlink_msg_nas_tm_get_nas_d(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field nas_vn from nas_tm message
- *
- * @return [m/s] Navigation system estimated north velocity
- */
-static inline float mavlink_msg_nas_tm_get_nas_vn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field nas_ve from nas_tm message
- *
- * @return [m/s] Navigation system estimated east velocity
- */
-static inline float mavlink_msg_nas_tm_get_nas_ve(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field nas_vd from nas_tm message
- *
- * @return [m/s] Navigation system estimated down velocity
- */
-static inline float mavlink_msg_nas_tm_get_nas_vd(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field nas_qx from nas_tm message
- *
- * @return [deg] Navigation system estimated attitude (qx)
- */
-static inline float mavlink_msg_nas_tm_get_nas_qx(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field nas_qy from nas_tm message
- *
- * @return [deg] Navigation system estimated attitude (qy)
- */
-static inline float mavlink_msg_nas_tm_get_nas_qy(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field nas_qz from nas_tm message
- *
- * @return [deg] Navigation system estimated attitude (qz)
- */
-static inline float mavlink_msg_nas_tm_get_nas_qz(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field nas_qw from nas_tm message
- *
- * @return [deg] Navigation system estimated attitude (qw)
- */
-static inline float mavlink_msg_nas_tm_get_nas_qw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field nas_bias_x from nas_tm message
- *
- * @return Navigation system gyroscope bias on x axis
- */
-static inline float mavlink_msg_nas_tm_get_nas_bias_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field nas_bias_y from nas_tm message
- *
- * @return Navigation system gyroscope bias on y axis
- */
-static inline float mavlink_msg_nas_tm_get_nas_bias_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field nas_bias_z from nas_tm message
- *
- * @return Navigation system gyroscope bias on z axis
- */
-static inline float mavlink_msg_nas_tm_get_nas_bias_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field ref_pressure from nas_tm message
- *
- * @return [Pa] Calibration pressure
- */
-static inline float mavlink_msg_nas_tm_get_ref_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field ref_temperature from nas_tm message
- *
- * @return [degC] Calibration temperature
- */
-static inline float mavlink_msg_nas_tm_get_ref_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field ref_latitude from nas_tm message
- *
- * @return [deg] Calibration latitude
- */
-static inline float mavlink_msg_nas_tm_get_ref_latitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field ref_longitude from nas_tm message
- *
- * @return [deg] Calibration longitude
- */
-static inline float mavlink_msg_nas_tm_get_ref_longitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 72);
-}
-
-/**
- * @brief Decode a nas_tm message into a struct
- *
- * @param msg The message to decode
- * @param nas_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_nas_tm_decode(const mavlink_message_t* msg, mavlink_nas_tm_t* nas_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- nas_tm->timestamp = mavlink_msg_nas_tm_get_timestamp(msg);
- nas_tm->nas_n = mavlink_msg_nas_tm_get_nas_n(msg);
- nas_tm->nas_e = mavlink_msg_nas_tm_get_nas_e(msg);
- nas_tm->nas_d = mavlink_msg_nas_tm_get_nas_d(msg);
- nas_tm->nas_vn = mavlink_msg_nas_tm_get_nas_vn(msg);
- nas_tm->nas_ve = mavlink_msg_nas_tm_get_nas_ve(msg);
- nas_tm->nas_vd = mavlink_msg_nas_tm_get_nas_vd(msg);
- nas_tm->nas_qx = mavlink_msg_nas_tm_get_nas_qx(msg);
- nas_tm->nas_qy = mavlink_msg_nas_tm_get_nas_qy(msg);
- nas_tm->nas_qz = mavlink_msg_nas_tm_get_nas_qz(msg);
- nas_tm->nas_qw = mavlink_msg_nas_tm_get_nas_qw(msg);
- nas_tm->nas_bias_x = mavlink_msg_nas_tm_get_nas_bias_x(msg);
- nas_tm->nas_bias_y = mavlink_msg_nas_tm_get_nas_bias_y(msg);
- nas_tm->nas_bias_z = mavlink_msg_nas_tm_get_nas_bias_z(msg);
- nas_tm->ref_pressure = mavlink_msg_nas_tm_get_ref_pressure(msg);
- nas_tm->ref_temperature = mavlink_msg_nas_tm_get_ref_temperature(msg);
- nas_tm->ref_latitude = mavlink_msg_nas_tm_get_ref_latitude(msg);
- nas_tm->ref_longitude = mavlink_msg_nas_tm_get_ref_longitude(msg);
- nas_tm->state = mavlink_msg_nas_tm_get_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_NAS_TM_LEN? msg->len : MAVLINK_MSG_ID_NAS_TM_LEN;
- memset(nas_tm, 0, MAVLINK_MSG_ID_NAS_TM_LEN);
- memcpy(nas_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_payload_flight_tm.h b/mavlink_lib/gemini/mavlink_msg_payload_flight_tm.h
deleted file mode 100644
index bfe077c3582106f59cfe4d17c86e22f178d0d299..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_payload_flight_tm.h
+++ /dev/null
@@ -1,1313 +0,0 @@
-#pragma once
-// MESSAGE PAYLOAD_FLIGHT_TM PACKING
-
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM 209
-
-
-typedef struct __mavlink_payload_flight_tm_t {
- uint64_t timestamp; /*< [us] Timestamp in microseconds*/
- float pressure_digi; /*< [Pa] Pressure from digital sensor*/
- float pressure_static; /*< [Pa] Pressure from static port*/
- float airspeed_pitot; /*< [m/s] Pitot airspeed*/
- float altitude_agl; /*< [m] Altitude above ground level*/
- float acc_x; /*< [m/s^2] Acceleration on X axis (body)*/
- float acc_y; /*< [m/s^2] Acceleration on Y axis (body)*/
- float acc_z; /*< [m/s^2] Acceleration on Z axis (body)*/
- float gyro_x; /*< [rad/s] Angular speed on X axis (body)*/
- float gyro_y; /*< [rad/s] Angular speed on Y axis (body)*/
- float gyro_z; /*< [rad/s] Angular speed on Z axis (body)*/
- float mag_x; /*< [uT] Magnetic field on X axis (body)*/
- float mag_y; /*< [uT] Magnetic field on Y axis (body)*/
- float mag_z; /*< [uT] Magnetic field on Z axis (body)*/
- float gps_lat; /*< [deg] Latitude*/
- float gps_lon; /*< [deg] Longitude*/
- float gps_alt; /*< [m] GPS Altitude*/
- float left_servo_angle; /*< [deg] Left servo motor angle*/
- float right_servo_angle; /*< [deg] Right servo motor angle*/
- float nas_n; /*< [deg] Navigation system estimated noth position*/
- float nas_e; /*< [deg] Navigation system estimated east position*/
- float nas_d; /*< [m] Navigation system estimated down position*/
- float nas_vn; /*< [m/s] Navigation system estimated north velocity*/
- float nas_ve; /*< [m/s] Navigation system estimated east velocity*/
- float nas_vd; /*< [m/s] Navigation system estimated down velocity*/
- float nas_qx; /*< [deg] Navigation system estimated attitude (qx)*/
- float nas_qy; /*< [deg] Navigation system estimated attitude (qy)*/
- float nas_qz; /*< [deg] Navigation system estimated attitude (qz)*/
- float nas_qw; /*< [deg] Navigation system estimated attitude (qw)*/
- float nas_bias_x; /*< Navigation system gyroscope bias on x axis*/
- float nas_bias_y; /*< Navigation system gyroscope bias on y axis*/
- float nas_bias_z; /*< Navigation system gyroscope bias on z axis*/
- float wes_n; /*< [m/s] Wind estimated north velocity*/
- float wes_e; /*< [m/s] Wind estimated east velocity*/
- float battery_voltage; /*< [V] Battery voltage*/
- float cam_battery_voltage; /*< [V] Camera battery voltage*/
- float current_consumption; /*< [A] Battery current*/
- float temperature; /*< [degC] Temperature*/
- uint8_t fmm_state; /*< Flight Mode Manager State*/
- uint8_t nas_state; /*< Navigation System FSM State*/
- uint8_t wes_state; /*< Wind Estimation System FSM State*/
- uint8_t gps_fix; /*< GPS fix (1 = fix, 0 = no fix)*/
- uint8_t pin_nosecone; /*< Nosecone pin status (1 = connected, 0 = disconnected)*/
- uint8_t cutter_presence; /*< Cutter presence status (1 = present, 0 = missing)*/
- int8_t logger_error; /*< Logger error (0 = no error)*/
-} mavlink_payload_flight_tm_t;
-
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN 163
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN 163
-#define MAVLINK_MSG_ID_209_LEN 163
-#define MAVLINK_MSG_ID_209_MIN_LEN 163
-
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC 84
-#define MAVLINK_MSG_ID_209_CRC 84
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM { \
- 209, \
- "PAYLOAD_FLIGHT_TM", \
- 45, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_flight_tm_t, timestamp) }, \
- { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \
- { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_payload_flight_tm_t, nas_state) }, \
- { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_payload_flight_tm_t, wes_state) }, \
- { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_payload_flight_tm_t, pressure_digi) }, \
- { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_payload_flight_tm_t, pressure_static) }, \
- { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_payload_flight_tm_t, airspeed_pitot) }, \
- { "altitude_agl", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_payload_flight_tm_t, altitude_agl) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_payload_flight_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_payload_flight_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_payload_flight_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_payload_flight_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_payload_flight_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_payload_flight_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_payload_flight_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_payload_flight_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_payload_flight_tm_t, mag_z) }, \
- { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \
- { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_flight_tm_t, gps_lat) }, \
- { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_flight_tm_t, gps_lon) }, \
- { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_flight_tm_t, gps_alt) }, \
- { "left_servo_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_payload_flight_tm_t, left_servo_angle) }, \
- { "right_servo_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_payload_flight_tm_t, right_servo_angle) }, \
- { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_payload_flight_tm_t, nas_n) }, \
- { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_payload_flight_tm_t, nas_e) }, \
- { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_payload_flight_tm_t, nas_d) }, \
- { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_payload_flight_tm_t, nas_vn) }, \
- { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_payload_flight_tm_t, nas_ve) }, \
- { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_payload_flight_tm_t, nas_vd) }, \
- { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_payload_flight_tm_t, nas_qx) }, \
- { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_payload_flight_tm_t, nas_qy) }, \
- { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_payload_flight_tm_t, nas_qz) }, \
- { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_payload_flight_tm_t, nas_qw) }, \
- { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_payload_flight_tm_t, nas_bias_x) }, \
- { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_payload_flight_tm_t, nas_bias_y) }, \
- { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_payload_flight_tm_t, nas_bias_z) }, \
- { "wes_n", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_payload_flight_tm_t, wes_n) }, \
- { "wes_e", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_payload_flight_tm_t, wes_e) }, \
- { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_payload_flight_tm_t, battery_voltage) }, \
- { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_flight_tm_t, cam_battery_voltage) }, \
- { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, current_consumption) }, \
- { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_payload_flight_tm_t, cutter_presence) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
- { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 162, offsetof(mavlink_payload_flight_tm_t, logger_error) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM { \
- "PAYLOAD_FLIGHT_TM", \
- 45, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_flight_tm_t, timestamp) }, \
- { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \
- { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_payload_flight_tm_t, nas_state) }, \
- { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_payload_flight_tm_t, wes_state) }, \
- { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_payload_flight_tm_t, pressure_digi) }, \
- { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_payload_flight_tm_t, pressure_static) }, \
- { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_payload_flight_tm_t, airspeed_pitot) }, \
- { "altitude_agl", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_payload_flight_tm_t, altitude_agl) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_payload_flight_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_payload_flight_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_payload_flight_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_payload_flight_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_payload_flight_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_payload_flight_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_payload_flight_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_payload_flight_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_payload_flight_tm_t, mag_z) }, \
- { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \
- { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_flight_tm_t, gps_lat) }, \
- { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_flight_tm_t, gps_lon) }, \
- { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_flight_tm_t, gps_alt) }, \
- { "left_servo_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_payload_flight_tm_t, left_servo_angle) }, \
- { "right_servo_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_payload_flight_tm_t, right_servo_angle) }, \
- { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_payload_flight_tm_t, nas_n) }, \
- { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_payload_flight_tm_t, nas_e) }, \
- { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_payload_flight_tm_t, nas_d) }, \
- { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_payload_flight_tm_t, nas_vn) }, \
- { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_payload_flight_tm_t, nas_ve) }, \
- { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_payload_flight_tm_t, nas_vd) }, \
- { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_payload_flight_tm_t, nas_qx) }, \
- { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_payload_flight_tm_t, nas_qy) }, \
- { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_payload_flight_tm_t, nas_qz) }, \
- { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_payload_flight_tm_t, nas_qw) }, \
- { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_payload_flight_tm_t, nas_bias_x) }, \
- { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_payload_flight_tm_t, nas_bias_y) }, \
- { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_payload_flight_tm_t, nas_bias_z) }, \
- { "wes_n", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_payload_flight_tm_t, wes_n) }, \
- { "wes_e", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_payload_flight_tm_t, wes_e) }, \
- { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_payload_flight_tm_t, battery_voltage) }, \
- { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_flight_tm_t, cam_battery_voltage) }, \
- { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, current_consumption) }, \
- { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_payload_flight_tm_t, cutter_presence) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
- { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 162, offsetof(mavlink_payload_flight_tm_t, logger_error) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a payload_flight_tm 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 in microseconds
- * @param fmm_state Flight Mode Manager State
- * @param nas_state Navigation System FSM State
- * @param wes_state Wind Estimation System FSM State
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param altitude_agl [m] Altitude above ground level
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param left_servo_angle [deg] Left servo motor angle
- * @param right_servo_angle [deg] Right servo motor angle
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on y axis
- * @param nas_bias_z Navigation system gyroscope bias on z axis
- * @param wes_n [m/s] Wind estimated north velocity
- * @param wes_e [m/s] Wind estimated east velocity
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param battery_voltage [V] Battery voltage
- * @param cam_battery_voltage [V] Camera battery voltage
- * @param current_consumption [A] Battery current
- * @param cutter_presence Cutter presence status (1 = present, 0 = missing)
- * @param temperature [degC] Temperature
- * @param logger_error Logger error (0 = no error)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float battery_voltage, float cam_battery_voltage, float current_consumption, uint8_t cutter_presence, float temperature, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_digi);
- _mav_put_float(buf, 12, pressure_static);
- _mav_put_float(buf, 16, airspeed_pitot);
- _mav_put_float(buf, 20, altitude_agl);
- _mav_put_float(buf, 24, acc_x);
- _mav_put_float(buf, 28, acc_y);
- _mav_put_float(buf, 32, acc_z);
- _mav_put_float(buf, 36, gyro_x);
- _mav_put_float(buf, 40, gyro_y);
- _mav_put_float(buf, 44, gyro_z);
- _mav_put_float(buf, 48, mag_x);
- _mav_put_float(buf, 52, mag_y);
- _mav_put_float(buf, 56, mag_z);
- _mav_put_float(buf, 60, gps_lat);
- _mav_put_float(buf, 64, gps_lon);
- _mav_put_float(buf, 68, gps_alt);
- _mav_put_float(buf, 72, left_servo_angle);
- _mav_put_float(buf, 76, right_servo_angle);
- _mav_put_float(buf, 80, nas_n);
- _mav_put_float(buf, 84, nas_e);
- _mav_put_float(buf, 88, nas_d);
- _mav_put_float(buf, 92, nas_vn);
- _mav_put_float(buf, 96, nas_ve);
- _mav_put_float(buf, 100, nas_vd);
- _mav_put_float(buf, 104, nas_qx);
- _mav_put_float(buf, 108, nas_qy);
- _mav_put_float(buf, 112, nas_qz);
- _mav_put_float(buf, 116, nas_qw);
- _mav_put_float(buf, 120, nas_bias_x);
- _mav_put_float(buf, 124, nas_bias_y);
- _mav_put_float(buf, 128, nas_bias_z);
- _mav_put_float(buf, 132, wes_n);
- _mav_put_float(buf, 136, wes_e);
- _mav_put_float(buf, 140, battery_voltage);
- _mav_put_float(buf, 144, cam_battery_voltage);
- _mav_put_float(buf, 148, current_consumption);
- _mav_put_float(buf, 152, temperature);
- _mav_put_uint8_t(buf, 156, fmm_state);
- _mav_put_uint8_t(buf, 157, nas_state);
- _mav_put_uint8_t(buf, 158, wes_state);
- _mav_put_uint8_t(buf, 159, gps_fix);
- _mav_put_uint8_t(buf, 160, pin_nosecone);
- _mav_put_uint8_t(buf, 161, cutter_presence);
- _mav_put_int8_t(buf, 162, logger_error);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
-#else
- mavlink_payload_flight_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.airspeed_pitot = airspeed_pitot;
- packet.altitude_agl = altitude_agl;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.left_servo_angle = left_servo_angle;
- packet.right_servo_angle = right_servo_angle;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.wes_n = wes_n;
- packet.wes_e = wes_e;
- packet.battery_voltage = battery_voltage;
- packet.cam_battery_voltage = cam_battery_voltage;
- packet.current_consumption = current_consumption;
- packet.temperature = temperature;
- packet.fmm_state = fmm_state;
- packet.nas_state = nas_state;
- packet.wes_state = wes_state;
- packet.gps_fix = gps_fix;
- packet.pin_nosecone = pin_nosecone;
- packet.cutter_presence = cutter_presence;
- packet.logger_error = logger_error;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-}
-
-/**
- * @brief Pack a payload_flight_tm 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 in microseconds
- * @param fmm_state Flight Mode Manager State
- * @param nas_state Navigation System FSM State
- * @param wes_state Wind Estimation System FSM State
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param altitude_agl [m] Altitude above ground level
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param left_servo_angle [deg] Left servo motor angle
- * @param right_servo_angle [deg] Right servo motor angle
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on y axis
- * @param nas_bias_z Navigation system gyroscope bias on z axis
- * @param wes_n [m/s] Wind estimated north velocity
- * @param wes_e [m/s] Wind estimated east velocity
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param battery_voltage [V] Battery voltage
- * @param cam_battery_voltage [V] Camera battery voltage
- * @param current_consumption [A] Battery current
- * @param cutter_presence Cutter presence status (1 = present, 0 = missing)
- * @param temperature [degC] Temperature
- * @param logger_error Logger error (0 = no error)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_payload_flight_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t fmm_state,uint8_t nas_state,uint8_t wes_state,float pressure_digi,float pressure_static,float airspeed_pitot,float altitude_agl,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float left_servo_angle,float right_servo_angle,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,float wes_n,float wes_e,uint8_t pin_nosecone,float battery_voltage,float cam_battery_voltage,float current_consumption,uint8_t cutter_presence,float temperature,int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_digi);
- _mav_put_float(buf, 12, pressure_static);
- _mav_put_float(buf, 16, airspeed_pitot);
- _mav_put_float(buf, 20, altitude_agl);
- _mav_put_float(buf, 24, acc_x);
- _mav_put_float(buf, 28, acc_y);
- _mav_put_float(buf, 32, acc_z);
- _mav_put_float(buf, 36, gyro_x);
- _mav_put_float(buf, 40, gyro_y);
- _mav_put_float(buf, 44, gyro_z);
- _mav_put_float(buf, 48, mag_x);
- _mav_put_float(buf, 52, mag_y);
- _mav_put_float(buf, 56, mag_z);
- _mav_put_float(buf, 60, gps_lat);
- _mav_put_float(buf, 64, gps_lon);
- _mav_put_float(buf, 68, gps_alt);
- _mav_put_float(buf, 72, left_servo_angle);
- _mav_put_float(buf, 76, right_servo_angle);
- _mav_put_float(buf, 80, nas_n);
- _mav_put_float(buf, 84, nas_e);
- _mav_put_float(buf, 88, nas_d);
- _mav_put_float(buf, 92, nas_vn);
- _mav_put_float(buf, 96, nas_ve);
- _mav_put_float(buf, 100, nas_vd);
- _mav_put_float(buf, 104, nas_qx);
- _mav_put_float(buf, 108, nas_qy);
- _mav_put_float(buf, 112, nas_qz);
- _mav_put_float(buf, 116, nas_qw);
- _mav_put_float(buf, 120, nas_bias_x);
- _mav_put_float(buf, 124, nas_bias_y);
- _mav_put_float(buf, 128, nas_bias_z);
- _mav_put_float(buf, 132, wes_n);
- _mav_put_float(buf, 136, wes_e);
- _mav_put_float(buf, 140, battery_voltage);
- _mav_put_float(buf, 144, cam_battery_voltage);
- _mav_put_float(buf, 148, current_consumption);
- _mav_put_float(buf, 152, temperature);
- _mav_put_uint8_t(buf, 156, fmm_state);
- _mav_put_uint8_t(buf, 157, nas_state);
- _mav_put_uint8_t(buf, 158, wes_state);
- _mav_put_uint8_t(buf, 159, gps_fix);
- _mav_put_uint8_t(buf, 160, pin_nosecone);
- _mav_put_uint8_t(buf, 161, cutter_presence);
- _mav_put_int8_t(buf, 162, logger_error);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
-#else
- mavlink_payload_flight_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.airspeed_pitot = airspeed_pitot;
- packet.altitude_agl = altitude_agl;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.left_servo_angle = left_servo_angle;
- packet.right_servo_angle = right_servo_angle;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.wes_n = wes_n;
- packet.wes_e = wes_e;
- packet.battery_voltage = battery_voltage;
- packet.cam_battery_voltage = cam_battery_voltage;
- packet.current_consumption = current_consumption;
- packet.temperature = temperature;
- packet.fmm_state = fmm_state;
- packet.nas_state = nas_state;
- packet.wes_state = wes_state;
- packet.gps_fix = gps_fix;
- packet.pin_nosecone = pin_nosecone;
- packet.cutter_presence = cutter_presence;
- packet.logger_error = logger_error;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-}
-
-/**
- * @brief Encode a payload_flight_tm 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 payload_flight_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_payload_flight_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_payload_flight_tm_t* payload_flight_tm)
-{
- return mavlink_msg_payload_flight_tm_pack(system_id, component_id, msg, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->current_consumption, payload_flight_tm->cutter_presence, payload_flight_tm->temperature, payload_flight_tm->logger_error);
-}
-
-/**
- * @brief Encode a payload_flight_tm 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 payload_flight_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_payload_flight_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_payload_flight_tm_t* payload_flight_tm)
-{
- return mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, chan, msg, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->current_consumption, payload_flight_tm->cutter_presence, payload_flight_tm->temperature, payload_flight_tm->logger_error);
-}
-
-/**
- * @brief Send a payload_flight_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp in microseconds
- * @param fmm_state Flight Mode Manager State
- * @param nas_state Navigation System FSM State
- * @param wes_state Wind Estimation System FSM State
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param altitude_agl [m] Altitude above ground level
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param left_servo_angle [deg] Left servo motor angle
- * @param right_servo_angle [deg] Right servo motor angle
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on y axis
- * @param nas_bias_z Navigation system gyroscope bias on z axis
- * @param wes_n [m/s] Wind estimated north velocity
- * @param wes_e [m/s] Wind estimated east velocity
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param battery_voltage [V] Battery voltage
- * @param cam_battery_voltage [V] Camera battery voltage
- * @param current_consumption [A] Battery current
- * @param cutter_presence Cutter presence status (1 = present, 0 = missing)
- * @param temperature [degC] Temperature
- * @param logger_error Logger error (0 = no error)
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float battery_voltage, float cam_battery_voltage, float current_consumption, uint8_t cutter_presence, float temperature, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_digi);
- _mav_put_float(buf, 12, pressure_static);
- _mav_put_float(buf, 16, airspeed_pitot);
- _mav_put_float(buf, 20, altitude_agl);
- _mav_put_float(buf, 24, acc_x);
- _mav_put_float(buf, 28, acc_y);
- _mav_put_float(buf, 32, acc_z);
- _mav_put_float(buf, 36, gyro_x);
- _mav_put_float(buf, 40, gyro_y);
- _mav_put_float(buf, 44, gyro_z);
- _mav_put_float(buf, 48, mag_x);
- _mav_put_float(buf, 52, mag_y);
- _mav_put_float(buf, 56, mag_z);
- _mav_put_float(buf, 60, gps_lat);
- _mav_put_float(buf, 64, gps_lon);
- _mav_put_float(buf, 68, gps_alt);
- _mav_put_float(buf, 72, left_servo_angle);
- _mav_put_float(buf, 76, right_servo_angle);
- _mav_put_float(buf, 80, nas_n);
- _mav_put_float(buf, 84, nas_e);
- _mav_put_float(buf, 88, nas_d);
- _mav_put_float(buf, 92, nas_vn);
- _mav_put_float(buf, 96, nas_ve);
- _mav_put_float(buf, 100, nas_vd);
- _mav_put_float(buf, 104, nas_qx);
- _mav_put_float(buf, 108, nas_qy);
- _mav_put_float(buf, 112, nas_qz);
- _mav_put_float(buf, 116, nas_qw);
- _mav_put_float(buf, 120, nas_bias_x);
- _mav_put_float(buf, 124, nas_bias_y);
- _mav_put_float(buf, 128, nas_bias_z);
- _mav_put_float(buf, 132, wes_n);
- _mav_put_float(buf, 136, wes_e);
- _mav_put_float(buf, 140, battery_voltage);
- _mav_put_float(buf, 144, cam_battery_voltage);
- _mav_put_float(buf, 148, current_consumption);
- _mav_put_float(buf, 152, temperature);
- _mav_put_uint8_t(buf, 156, fmm_state);
- _mav_put_uint8_t(buf, 157, nas_state);
- _mav_put_uint8_t(buf, 158, wes_state);
- _mav_put_uint8_t(buf, 159, gps_fix);
- _mav_put_uint8_t(buf, 160, pin_nosecone);
- _mav_put_uint8_t(buf, 161, cutter_presence);
- _mav_put_int8_t(buf, 162, logger_error);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-#else
- mavlink_payload_flight_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.airspeed_pitot = airspeed_pitot;
- packet.altitude_agl = altitude_agl;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.left_servo_angle = left_servo_angle;
- packet.right_servo_angle = right_servo_angle;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.wes_n = wes_n;
- packet.wes_e = wes_e;
- packet.battery_voltage = battery_voltage;
- packet.cam_battery_voltage = cam_battery_voltage;
- packet.current_consumption = current_consumption;
- packet.temperature = temperature;
- packet.fmm_state = fmm_state;
- packet.nas_state = nas_state;
- packet.wes_state = wes_state;
- packet.gps_fix = gps_fix;
- packet.pin_nosecone = pin_nosecone;
- packet.cutter_presence = cutter_presence;
- packet.logger_error = logger_error;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, (const char *)&packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a payload_flight_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_payload_flight_tm_send_struct(mavlink_channel_t chan, const mavlink_payload_flight_tm_t* payload_flight_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_payload_flight_tm_send(chan, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->current_consumption, payload_flight_tm->cutter_presence, payload_flight_tm->temperature, payload_flight_tm->logger_error);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, (const char *)payload_flight_tm, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_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_payload_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float battery_voltage, float cam_battery_voltage, float current_consumption, uint8_t cutter_presence, float temperature, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_digi);
- _mav_put_float(buf, 12, pressure_static);
- _mav_put_float(buf, 16, airspeed_pitot);
- _mav_put_float(buf, 20, altitude_agl);
- _mav_put_float(buf, 24, acc_x);
- _mav_put_float(buf, 28, acc_y);
- _mav_put_float(buf, 32, acc_z);
- _mav_put_float(buf, 36, gyro_x);
- _mav_put_float(buf, 40, gyro_y);
- _mav_put_float(buf, 44, gyro_z);
- _mav_put_float(buf, 48, mag_x);
- _mav_put_float(buf, 52, mag_y);
- _mav_put_float(buf, 56, mag_z);
- _mav_put_float(buf, 60, gps_lat);
- _mav_put_float(buf, 64, gps_lon);
- _mav_put_float(buf, 68, gps_alt);
- _mav_put_float(buf, 72, left_servo_angle);
- _mav_put_float(buf, 76, right_servo_angle);
- _mav_put_float(buf, 80, nas_n);
- _mav_put_float(buf, 84, nas_e);
- _mav_put_float(buf, 88, nas_d);
- _mav_put_float(buf, 92, nas_vn);
- _mav_put_float(buf, 96, nas_ve);
- _mav_put_float(buf, 100, nas_vd);
- _mav_put_float(buf, 104, nas_qx);
- _mav_put_float(buf, 108, nas_qy);
- _mav_put_float(buf, 112, nas_qz);
- _mav_put_float(buf, 116, nas_qw);
- _mav_put_float(buf, 120, nas_bias_x);
- _mav_put_float(buf, 124, nas_bias_y);
- _mav_put_float(buf, 128, nas_bias_z);
- _mav_put_float(buf, 132, wes_n);
- _mav_put_float(buf, 136, wes_e);
- _mav_put_float(buf, 140, battery_voltage);
- _mav_put_float(buf, 144, cam_battery_voltage);
- _mav_put_float(buf, 148, current_consumption);
- _mav_put_float(buf, 152, temperature);
- _mav_put_uint8_t(buf, 156, fmm_state);
- _mav_put_uint8_t(buf, 157, nas_state);
- _mav_put_uint8_t(buf, 158, wes_state);
- _mav_put_uint8_t(buf, 159, gps_fix);
- _mav_put_uint8_t(buf, 160, pin_nosecone);
- _mav_put_uint8_t(buf, 161, cutter_presence);
- _mav_put_int8_t(buf, 162, logger_error);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-#else
- mavlink_payload_flight_tm_t *packet = (mavlink_payload_flight_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->pressure_digi = pressure_digi;
- packet->pressure_static = pressure_static;
- packet->airspeed_pitot = airspeed_pitot;
- packet->altitude_agl = altitude_agl;
- packet->acc_x = acc_x;
- packet->acc_y = acc_y;
- packet->acc_z = acc_z;
- packet->gyro_x = gyro_x;
- packet->gyro_y = gyro_y;
- packet->gyro_z = gyro_z;
- packet->mag_x = mag_x;
- packet->mag_y = mag_y;
- packet->mag_z = mag_z;
- packet->gps_lat = gps_lat;
- packet->gps_lon = gps_lon;
- packet->gps_alt = gps_alt;
- packet->left_servo_angle = left_servo_angle;
- packet->right_servo_angle = right_servo_angle;
- packet->nas_n = nas_n;
- packet->nas_e = nas_e;
- packet->nas_d = nas_d;
- packet->nas_vn = nas_vn;
- packet->nas_ve = nas_ve;
- packet->nas_vd = nas_vd;
- packet->nas_qx = nas_qx;
- packet->nas_qy = nas_qy;
- packet->nas_qz = nas_qz;
- packet->nas_qw = nas_qw;
- packet->nas_bias_x = nas_bias_x;
- packet->nas_bias_y = nas_bias_y;
- packet->nas_bias_z = nas_bias_z;
- packet->wes_n = wes_n;
- packet->wes_e = wes_e;
- packet->battery_voltage = battery_voltage;
- packet->cam_battery_voltage = cam_battery_voltage;
- packet->current_consumption = current_consumption;
- packet->temperature = temperature;
- packet->fmm_state = fmm_state;
- packet->nas_state = nas_state;
- packet->wes_state = wes_state;
- packet->gps_fix = gps_fix;
- packet->pin_nosecone = pin_nosecone;
- packet->cutter_presence = cutter_presence;
- packet->logger_error = logger_error;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, (const char *)packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE PAYLOAD_FLIGHT_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from payload_flight_tm message
- *
- * @return [us] Timestamp in microseconds
- */
-static inline uint64_t mavlink_msg_payload_flight_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field fmm_state from payload_flight_tm message
- *
- * @return Flight Mode Manager State
- */
-static inline uint8_t mavlink_msg_payload_flight_tm_get_fmm_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 156);
-}
-
-/**
- * @brief Get field nas_state from payload_flight_tm message
- *
- * @return Navigation System FSM State
- */
-static inline uint8_t mavlink_msg_payload_flight_tm_get_nas_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 157);
-}
-
-/**
- * @brief Get field wes_state from payload_flight_tm message
- *
- * @return Wind Estimation System FSM State
- */
-static inline uint8_t mavlink_msg_payload_flight_tm_get_wes_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 158);
-}
-
-/**
- * @brief Get field pressure_digi from payload_flight_tm message
- *
- * @return [Pa] Pressure from digital sensor
- */
-static inline float mavlink_msg_payload_flight_tm_get_pressure_digi(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field pressure_static from payload_flight_tm message
- *
- * @return [Pa] Pressure from static port
- */
-static inline float mavlink_msg_payload_flight_tm_get_pressure_static(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field airspeed_pitot from payload_flight_tm message
- *
- * @return [m/s] Pitot airspeed
- */
-static inline float mavlink_msg_payload_flight_tm_get_airspeed_pitot(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field altitude_agl from payload_flight_tm message
- *
- * @return [m] Altitude above ground level
- */
-static inline float mavlink_msg_payload_flight_tm_get_altitude_agl(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field acc_x from payload_flight_tm message
- *
- * @return [m/s^2] Acceleration on X axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_acc_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field acc_y from payload_flight_tm message
- *
- * @return [m/s^2] Acceleration on Y axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_acc_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field acc_z from payload_flight_tm message
- *
- * @return [m/s^2] Acceleration on Z axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_acc_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field gyro_x from payload_flight_tm message
- *
- * @return [rad/s] Angular speed on X axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_gyro_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field gyro_y from payload_flight_tm message
- *
- * @return [rad/s] Angular speed on Y axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_gyro_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field gyro_z from payload_flight_tm message
- *
- * @return [rad/s] Angular speed on Z axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_gyro_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field mag_x from payload_flight_tm message
- *
- * @return [uT] Magnetic field on X axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_mag_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field mag_y from payload_flight_tm message
- *
- * @return [uT] Magnetic field on Y axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_mag_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field mag_z from payload_flight_tm message
- *
- * @return [uT] Magnetic field on Z axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_mag_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field gps_fix from payload_flight_tm message
- *
- * @return GPS fix (1 = fix, 0 = no fix)
- */
-static inline uint8_t mavlink_msg_payload_flight_tm_get_gps_fix(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 159);
-}
-
-/**
- * @brief Get field gps_lat from payload_flight_tm message
- *
- * @return [deg] Latitude
- */
-static inline float mavlink_msg_payload_flight_tm_get_gps_lat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field gps_lon from payload_flight_tm message
- *
- * @return [deg] Longitude
- */
-static inline float mavlink_msg_payload_flight_tm_get_gps_lon(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field gps_alt from payload_flight_tm message
- *
- * @return [m] GPS Altitude
- */
-static inline float mavlink_msg_payload_flight_tm_get_gps_alt(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field left_servo_angle from payload_flight_tm message
- *
- * @return [deg] Left servo motor angle
- */
-static inline float mavlink_msg_payload_flight_tm_get_left_servo_angle(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 72);
-}
-
-/**
- * @brief Get field right_servo_angle from payload_flight_tm message
- *
- * @return [deg] Right servo motor angle
- */
-static inline float mavlink_msg_payload_flight_tm_get_right_servo_angle(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 76);
-}
-
-/**
- * @brief Get field nas_n from payload_flight_tm message
- *
- * @return [deg] Navigation system estimated noth position
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_n(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 80);
-}
-
-/**
- * @brief Get field nas_e from payload_flight_tm message
- *
- * @return [deg] Navigation system estimated east position
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_e(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 84);
-}
-
-/**
- * @brief Get field nas_d from payload_flight_tm message
- *
- * @return [m] Navigation system estimated down position
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_d(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 88);
-}
-
-/**
- * @brief Get field nas_vn from payload_flight_tm message
- *
- * @return [m/s] Navigation system estimated north velocity
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_vn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 92);
-}
-
-/**
- * @brief Get field nas_ve from payload_flight_tm message
- *
- * @return [m/s] Navigation system estimated east velocity
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_ve(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 96);
-}
-
-/**
- * @brief Get field nas_vd from payload_flight_tm message
- *
- * @return [m/s] Navigation system estimated down velocity
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_vd(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 100);
-}
-
-/**
- * @brief Get field nas_qx from payload_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qx)
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_qx(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 104);
-}
-
-/**
- * @brief Get field nas_qy from payload_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qy)
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_qy(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 108);
-}
-
-/**
- * @brief Get field nas_qz from payload_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qz)
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_qz(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 112);
-}
-
-/**
- * @brief Get field nas_qw from payload_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qw)
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_qw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 116);
-}
-
-/**
- * @brief Get field nas_bias_x from payload_flight_tm message
- *
- * @return Navigation system gyroscope bias on x axis
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_bias_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 120);
-}
-
-/**
- * @brief Get field nas_bias_y from payload_flight_tm message
- *
- * @return Navigation system gyroscope bias on y axis
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_bias_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 124);
-}
-
-/**
- * @brief Get field nas_bias_z from payload_flight_tm message
- *
- * @return Navigation system gyroscope bias on z axis
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_bias_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 128);
-}
-
-/**
- * @brief Get field wes_n from payload_flight_tm message
- *
- * @return [m/s] Wind estimated north velocity
- */
-static inline float mavlink_msg_payload_flight_tm_get_wes_n(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 132);
-}
-
-/**
- * @brief Get field wes_e from payload_flight_tm message
- *
- * @return [m/s] Wind estimated east velocity
- */
-static inline float mavlink_msg_payload_flight_tm_get_wes_e(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 136);
-}
-
-/**
- * @brief Get field pin_nosecone from payload_flight_tm message
- *
- * @return Nosecone pin status (1 = connected, 0 = disconnected)
- */
-static inline uint8_t mavlink_msg_payload_flight_tm_get_pin_nosecone(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 160);
-}
-
-/**
- * @brief Get field battery_voltage from payload_flight_tm message
- *
- * @return [V] Battery voltage
- */
-static inline float mavlink_msg_payload_flight_tm_get_battery_voltage(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 140);
-}
-
-/**
- * @brief Get field cam_battery_voltage from payload_flight_tm message
- *
- * @return [V] Camera battery voltage
- */
-static inline float mavlink_msg_payload_flight_tm_get_cam_battery_voltage(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 144);
-}
-
-/**
- * @brief Get field current_consumption from payload_flight_tm message
- *
- * @return [A] Battery current
- */
-static inline float mavlink_msg_payload_flight_tm_get_current_consumption(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 148);
-}
-
-/**
- * @brief Get field cutter_presence from payload_flight_tm message
- *
- * @return Cutter presence status (1 = present, 0 = missing)
- */
-static inline uint8_t mavlink_msg_payload_flight_tm_get_cutter_presence(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 161);
-}
-
-/**
- * @brief Get field temperature from payload_flight_tm message
- *
- * @return [degC] Temperature
- */
-static inline float mavlink_msg_payload_flight_tm_get_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 152);
-}
-
-/**
- * @brief Get field logger_error from payload_flight_tm message
- *
- * @return Logger error (0 = no error)
- */
-static inline int8_t mavlink_msg_payload_flight_tm_get_logger_error(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int8_t(msg, 162);
-}
-
-/**
- * @brief Decode a payload_flight_tm message into a struct
- *
- * @param msg The message to decode
- * @param payload_flight_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_payload_flight_tm_decode(const mavlink_message_t* msg, mavlink_payload_flight_tm_t* payload_flight_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- payload_flight_tm->timestamp = mavlink_msg_payload_flight_tm_get_timestamp(msg);
- payload_flight_tm->pressure_digi = mavlink_msg_payload_flight_tm_get_pressure_digi(msg);
- payload_flight_tm->pressure_static = mavlink_msg_payload_flight_tm_get_pressure_static(msg);
- payload_flight_tm->airspeed_pitot = mavlink_msg_payload_flight_tm_get_airspeed_pitot(msg);
- payload_flight_tm->altitude_agl = mavlink_msg_payload_flight_tm_get_altitude_agl(msg);
- payload_flight_tm->acc_x = mavlink_msg_payload_flight_tm_get_acc_x(msg);
- payload_flight_tm->acc_y = mavlink_msg_payload_flight_tm_get_acc_y(msg);
- payload_flight_tm->acc_z = mavlink_msg_payload_flight_tm_get_acc_z(msg);
- payload_flight_tm->gyro_x = mavlink_msg_payload_flight_tm_get_gyro_x(msg);
- payload_flight_tm->gyro_y = mavlink_msg_payload_flight_tm_get_gyro_y(msg);
- payload_flight_tm->gyro_z = mavlink_msg_payload_flight_tm_get_gyro_z(msg);
- payload_flight_tm->mag_x = mavlink_msg_payload_flight_tm_get_mag_x(msg);
- payload_flight_tm->mag_y = mavlink_msg_payload_flight_tm_get_mag_y(msg);
- payload_flight_tm->mag_z = mavlink_msg_payload_flight_tm_get_mag_z(msg);
- payload_flight_tm->gps_lat = mavlink_msg_payload_flight_tm_get_gps_lat(msg);
- payload_flight_tm->gps_lon = mavlink_msg_payload_flight_tm_get_gps_lon(msg);
- payload_flight_tm->gps_alt = mavlink_msg_payload_flight_tm_get_gps_alt(msg);
- payload_flight_tm->left_servo_angle = mavlink_msg_payload_flight_tm_get_left_servo_angle(msg);
- payload_flight_tm->right_servo_angle = mavlink_msg_payload_flight_tm_get_right_servo_angle(msg);
- payload_flight_tm->nas_n = mavlink_msg_payload_flight_tm_get_nas_n(msg);
- payload_flight_tm->nas_e = mavlink_msg_payload_flight_tm_get_nas_e(msg);
- payload_flight_tm->nas_d = mavlink_msg_payload_flight_tm_get_nas_d(msg);
- payload_flight_tm->nas_vn = mavlink_msg_payload_flight_tm_get_nas_vn(msg);
- payload_flight_tm->nas_ve = mavlink_msg_payload_flight_tm_get_nas_ve(msg);
- payload_flight_tm->nas_vd = mavlink_msg_payload_flight_tm_get_nas_vd(msg);
- payload_flight_tm->nas_qx = mavlink_msg_payload_flight_tm_get_nas_qx(msg);
- payload_flight_tm->nas_qy = mavlink_msg_payload_flight_tm_get_nas_qy(msg);
- payload_flight_tm->nas_qz = mavlink_msg_payload_flight_tm_get_nas_qz(msg);
- payload_flight_tm->nas_qw = mavlink_msg_payload_flight_tm_get_nas_qw(msg);
- payload_flight_tm->nas_bias_x = mavlink_msg_payload_flight_tm_get_nas_bias_x(msg);
- payload_flight_tm->nas_bias_y = mavlink_msg_payload_flight_tm_get_nas_bias_y(msg);
- payload_flight_tm->nas_bias_z = mavlink_msg_payload_flight_tm_get_nas_bias_z(msg);
- payload_flight_tm->wes_n = mavlink_msg_payload_flight_tm_get_wes_n(msg);
- payload_flight_tm->wes_e = mavlink_msg_payload_flight_tm_get_wes_e(msg);
- payload_flight_tm->battery_voltage = mavlink_msg_payload_flight_tm_get_battery_voltage(msg);
- payload_flight_tm->cam_battery_voltage = mavlink_msg_payload_flight_tm_get_cam_battery_voltage(msg);
- payload_flight_tm->current_consumption = mavlink_msg_payload_flight_tm_get_current_consumption(msg);
- payload_flight_tm->temperature = mavlink_msg_payload_flight_tm_get_temperature(msg);
- payload_flight_tm->fmm_state = mavlink_msg_payload_flight_tm_get_fmm_state(msg);
- payload_flight_tm->nas_state = mavlink_msg_payload_flight_tm_get_nas_state(msg);
- payload_flight_tm->wes_state = mavlink_msg_payload_flight_tm_get_wes_state(msg);
- payload_flight_tm->gps_fix = mavlink_msg_payload_flight_tm_get_gps_fix(msg);
- payload_flight_tm->pin_nosecone = mavlink_msg_payload_flight_tm_get_pin_nosecone(msg);
- payload_flight_tm->cutter_presence = mavlink_msg_payload_flight_tm_get_cutter_presence(msg);
- payload_flight_tm->logger_error = mavlink_msg_payload_flight_tm_get_logger_error(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN? msg->len : MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN;
- memset(payload_flight_tm, 0, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
- memcpy(payload_flight_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_payload_stats_tm.h b/mavlink_lib/gemini/mavlink_msg_payload_stats_tm.h
deleted file mode 100644
index 3b945c4692aa2e834689fd0617809d5f5be22970..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_payload_stats_tm.h
+++ /dev/null
@@ -1,563 +0,0 @@
-#pragma once
-// MESSAGE PAYLOAD_STATS_TM PACKING
-
-#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM 211
-
-
-typedef struct __mavlink_payload_stats_tm_t {
- uint64_t liftoff_max_acc_ts; /*< [us] System clock at the maximum liftoff acceleration*/
- uint64_t dpl_ts; /*< [us] System clock at drouge deployment*/
- uint64_t max_z_speed_ts; /*< [us] System clock at max vertical speed*/
- uint64_t apogee_ts; /*< [us] System clock at apogee*/
- float liftoff_max_acc; /*< [m/s2] Maximum liftoff acceleration*/
- float dpl_max_acc; /*< [m/s2] Max acceleration during drouge deployment*/
- float max_z_speed; /*< [m/s] Max measured vertical speed*/
- float max_airspeed_pitot; /*< [m/s] Max speed read by the pitot tube*/
- float max_speed_altitude; /*< [m] Altitude at max speed*/
- float apogee_lat; /*< [deg] Apogee latitude*/
- float apogee_lon; /*< [deg] Apogee longitude*/
- float apogee_alt; /*< [m] Apogee altitude*/
- float min_pressure; /*< [Pa] Apogee pressure - Digital barometer*/
- float cpu_load; /*< CPU load in percentage*/
- uint32_t free_heap; /*< Amount of available heap in memory*/
-} mavlink_payload_stats_tm_t;
-
-#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN 76
-#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN 76
-#define MAVLINK_MSG_ID_211_LEN 76
-#define MAVLINK_MSG_ID_211_MIN_LEN 76
-
-#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC 115
-#define MAVLINK_MSG_ID_211_CRC 115
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM { \
- 211, \
- "PAYLOAD_STATS_TM", \
- 15, \
- { { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc_ts) }, \
- { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc) }, \
- { "dpl_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_payload_stats_tm_t, dpl_ts) }, \
- { "dpl_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_payload_stats_tm_t, dpl_max_acc) }, \
- { "max_z_speed_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_payload_stats_tm_t, max_z_speed_ts) }, \
- { "max_z_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_payload_stats_tm_t, max_z_speed) }, \
- { "max_airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_payload_stats_tm_t, max_airspeed_pitot) }, \
- { "max_speed_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_payload_stats_tm_t, max_speed_altitude) }, \
- { "apogee_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 24, offsetof(mavlink_payload_stats_tm_t, apogee_ts) }, \
- { "apogee_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_payload_stats_tm_t, apogee_lat) }, \
- { "apogee_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_payload_stats_tm_t, apogee_lon) }, \
- { "apogee_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_stats_tm_t, apogee_alt) }, \
- { "min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_stats_tm_t, min_pressure) }, \
- { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_stats_tm_t, cpu_load) }, \
- { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 72, offsetof(mavlink_payload_stats_tm_t, free_heap) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM { \
- "PAYLOAD_STATS_TM", \
- 15, \
- { { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc_ts) }, \
- { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc) }, \
- { "dpl_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_payload_stats_tm_t, dpl_ts) }, \
- { "dpl_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_payload_stats_tm_t, dpl_max_acc) }, \
- { "max_z_speed_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_payload_stats_tm_t, max_z_speed_ts) }, \
- { "max_z_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_payload_stats_tm_t, max_z_speed) }, \
- { "max_airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_payload_stats_tm_t, max_airspeed_pitot) }, \
- { "max_speed_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_payload_stats_tm_t, max_speed_altitude) }, \
- { "apogee_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 24, offsetof(mavlink_payload_stats_tm_t, apogee_ts) }, \
- { "apogee_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_payload_stats_tm_t, apogee_lat) }, \
- { "apogee_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_payload_stats_tm_t, apogee_lon) }, \
- { "apogee_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_stats_tm_t, apogee_alt) }, \
- { "min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_stats_tm_t, min_pressure) }, \
- { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_stats_tm_t, cpu_load) }, \
- { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 72, offsetof(mavlink_payload_stats_tm_t, free_heap) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a payload_stats_tm 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 liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param dpl_ts [us] System clock at drouge deployment
- * @param dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param max_z_speed_ts [us] System clock at max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [us] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param apogee_alt [m] Apogee altitude
- * @param min_pressure [Pa] Apogee pressure - Digital barometer
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_payload_stats_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 8, dpl_ts);
- _mav_put_uint64_t(buf, 16, max_z_speed_ts);
- _mav_put_uint64_t(buf, 24, apogee_ts);
- _mav_put_float(buf, 32, liftoff_max_acc);
- _mav_put_float(buf, 36, dpl_max_acc);
- _mav_put_float(buf, 40, max_z_speed);
- _mav_put_float(buf, 44, max_airspeed_pitot);
- _mav_put_float(buf, 48, max_speed_altitude);
- _mav_put_float(buf, 52, apogee_lat);
- _mav_put_float(buf, 56, apogee_lon);
- _mav_put_float(buf, 60, apogee_alt);
- _mav_put_float(buf, 64, min_pressure);
- _mav_put_float(buf, 68, cpu_load);
- _mav_put_uint32_t(buf, 72, free_heap);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
-#else
- mavlink_payload_stats_tm_t packet;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.dpl_ts = dpl_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.dpl_max_acc = dpl_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.apogee_alt = apogee_alt;
- packet.min_pressure = min_pressure;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PAYLOAD_STATS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-}
-
-/**
- * @brief Pack a payload_stats_tm 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 liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param dpl_ts [us] System clock at drouge deployment
- * @param dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param max_z_speed_ts [us] System clock at max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [us] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param apogee_alt [m] Apogee altitude
- * @param min_pressure [Pa] Apogee pressure - Digital barometer
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_payload_stats_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t liftoff_max_acc_ts,float liftoff_max_acc,uint64_t dpl_ts,float dpl_max_acc,uint64_t max_z_speed_ts,float max_z_speed,float max_airspeed_pitot,float max_speed_altitude,uint64_t apogee_ts,float apogee_lat,float apogee_lon,float apogee_alt,float min_pressure,float cpu_load,uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 8, dpl_ts);
- _mav_put_uint64_t(buf, 16, max_z_speed_ts);
- _mav_put_uint64_t(buf, 24, apogee_ts);
- _mav_put_float(buf, 32, liftoff_max_acc);
- _mav_put_float(buf, 36, dpl_max_acc);
- _mav_put_float(buf, 40, max_z_speed);
- _mav_put_float(buf, 44, max_airspeed_pitot);
- _mav_put_float(buf, 48, max_speed_altitude);
- _mav_put_float(buf, 52, apogee_lat);
- _mav_put_float(buf, 56, apogee_lon);
- _mav_put_float(buf, 60, apogee_alt);
- _mav_put_float(buf, 64, min_pressure);
- _mav_put_float(buf, 68, cpu_load);
- _mav_put_uint32_t(buf, 72, free_heap);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
-#else
- mavlink_payload_stats_tm_t packet;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.dpl_ts = dpl_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.dpl_max_acc = dpl_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.apogee_alt = apogee_alt;
- packet.min_pressure = min_pressure;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PAYLOAD_STATS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-}
-
-/**
- * @brief Encode a payload_stats_tm 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 payload_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_payload_stats_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_payload_stats_tm_t* payload_stats_tm)
-{
- return mavlink_msg_payload_stats_tm_pack(system_id, component_id, msg, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->max_z_speed_ts, payload_stats_tm->max_z_speed, payload_stats_tm->max_airspeed_pitot, payload_stats_tm->max_speed_altitude, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap);
-}
-
-/**
- * @brief Encode a payload_stats_tm 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 payload_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_payload_stats_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_payload_stats_tm_t* payload_stats_tm)
-{
- return mavlink_msg_payload_stats_tm_pack_chan(system_id, component_id, chan, msg, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->max_z_speed_ts, payload_stats_tm->max_z_speed, payload_stats_tm->max_airspeed_pitot, payload_stats_tm->max_speed_altitude, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap);
-}
-
-/**
- * @brief Send a payload_stats_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param dpl_ts [us] System clock at drouge deployment
- * @param dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param max_z_speed_ts [us] System clock at max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [us] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param apogee_alt [m] Apogee altitude
- * @param min_pressure [Pa] Apogee pressure - Digital barometer
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_payload_stats_tm_send(mavlink_channel_t chan, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 8, dpl_ts);
- _mav_put_uint64_t(buf, 16, max_z_speed_ts);
- _mav_put_uint64_t(buf, 24, apogee_ts);
- _mav_put_float(buf, 32, liftoff_max_acc);
- _mav_put_float(buf, 36, dpl_max_acc);
- _mav_put_float(buf, 40, max_z_speed);
- _mav_put_float(buf, 44, max_airspeed_pitot);
- _mav_put_float(buf, 48, max_speed_altitude);
- _mav_put_float(buf, 52, apogee_lat);
- _mav_put_float(buf, 56, apogee_lon);
- _mav_put_float(buf, 60, apogee_alt);
- _mav_put_float(buf, 64, min_pressure);
- _mav_put_float(buf, 68, cpu_load);
- _mav_put_uint32_t(buf, 72, free_heap);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM, buf, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-#else
- mavlink_payload_stats_tm_t packet;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.dpl_ts = dpl_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.dpl_max_acc = dpl_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.apogee_alt = apogee_alt;
- packet.min_pressure = min_pressure;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM, (const char *)&packet, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a payload_stats_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_payload_stats_tm_send_struct(mavlink_channel_t chan, const mavlink_payload_stats_tm_t* payload_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_payload_stats_tm_send(chan, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->max_z_speed_ts, payload_stats_tm->max_z_speed, payload_stats_tm->max_airspeed_pitot, payload_stats_tm->max_speed_altitude, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM, (const char *)payload_stats_tm, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_PAYLOAD_STATS_TM_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_payload_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 8, dpl_ts);
- _mav_put_uint64_t(buf, 16, max_z_speed_ts);
- _mav_put_uint64_t(buf, 24, apogee_ts);
- _mav_put_float(buf, 32, liftoff_max_acc);
- _mav_put_float(buf, 36, dpl_max_acc);
- _mav_put_float(buf, 40, max_z_speed);
- _mav_put_float(buf, 44, max_airspeed_pitot);
- _mav_put_float(buf, 48, max_speed_altitude);
- _mav_put_float(buf, 52, apogee_lat);
- _mav_put_float(buf, 56, apogee_lon);
- _mav_put_float(buf, 60, apogee_alt);
- _mav_put_float(buf, 64, min_pressure);
- _mav_put_float(buf, 68, cpu_load);
- _mav_put_uint32_t(buf, 72, free_heap);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM, buf, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-#else
- mavlink_payload_stats_tm_t *packet = (mavlink_payload_stats_tm_t *)msgbuf;
- packet->liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet->dpl_ts = dpl_ts;
- packet->max_z_speed_ts = max_z_speed_ts;
- packet->apogee_ts = apogee_ts;
- packet->liftoff_max_acc = liftoff_max_acc;
- packet->dpl_max_acc = dpl_max_acc;
- packet->max_z_speed = max_z_speed;
- packet->max_airspeed_pitot = max_airspeed_pitot;
- packet->max_speed_altitude = max_speed_altitude;
- packet->apogee_lat = apogee_lat;
- packet->apogee_lon = apogee_lon;
- packet->apogee_alt = apogee_alt;
- packet->min_pressure = min_pressure;
- packet->cpu_load = cpu_load;
- packet->free_heap = free_heap;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM, (const char *)packet, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE PAYLOAD_STATS_TM UNPACKING
-
-
-/**
- * @brief Get field liftoff_max_acc_ts from payload_stats_tm message
- *
- * @return [us] System clock at the maximum liftoff acceleration
- */
-static inline uint64_t mavlink_msg_payload_stats_tm_get_liftoff_max_acc_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field liftoff_max_acc from payload_stats_tm message
- *
- * @return [m/s2] Maximum liftoff acceleration
- */
-static inline float mavlink_msg_payload_stats_tm_get_liftoff_max_acc(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field dpl_ts from payload_stats_tm message
- *
- * @return [us] System clock at drouge deployment
- */
-static inline uint64_t mavlink_msg_payload_stats_tm_get_dpl_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 8);
-}
-
-/**
- * @brief Get field dpl_max_acc from payload_stats_tm message
- *
- * @return [m/s2] Max acceleration during drouge deployment
- */
-static inline float mavlink_msg_payload_stats_tm_get_dpl_max_acc(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field max_z_speed_ts from payload_stats_tm message
- *
- * @return [us] System clock at max vertical speed
- */
-static inline uint64_t mavlink_msg_payload_stats_tm_get_max_z_speed_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 16);
-}
-
-/**
- * @brief Get field max_z_speed from payload_stats_tm message
- *
- * @return [m/s] Max measured vertical speed
- */
-static inline float mavlink_msg_payload_stats_tm_get_max_z_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field max_airspeed_pitot from payload_stats_tm message
- *
- * @return [m/s] Max speed read by the pitot tube
- */
-static inline float mavlink_msg_payload_stats_tm_get_max_airspeed_pitot(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field max_speed_altitude from payload_stats_tm message
- *
- * @return [m] Altitude at max speed
- */
-static inline float mavlink_msg_payload_stats_tm_get_max_speed_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field apogee_ts from payload_stats_tm message
- *
- * @return [us] System clock at apogee
- */
-static inline uint64_t mavlink_msg_payload_stats_tm_get_apogee_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 24);
-}
-
-/**
- * @brief Get field apogee_lat from payload_stats_tm message
- *
- * @return [deg] Apogee latitude
- */
-static inline float mavlink_msg_payload_stats_tm_get_apogee_lat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field apogee_lon from payload_stats_tm message
- *
- * @return [deg] Apogee longitude
- */
-static inline float mavlink_msg_payload_stats_tm_get_apogee_lon(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field apogee_alt from payload_stats_tm message
- *
- * @return [m] Apogee altitude
- */
-static inline float mavlink_msg_payload_stats_tm_get_apogee_alt(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field min_pressure from payload_stats_tm message
- *
- * @return [Pa] Apogee pressure - Digital barometer
- */
-static inline float mavlink_msg_payload_stats_tm_get_min_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field cpu_load from payload_stats_tm message
- *
- * @return CPU load in percentage
- */
-static inline float mavlink_msg_payload_stats_tm_get_cpu_load(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field free_heap from payload_stats_tm message
- *
- * @return Amount of available heap in memory
- */
-static inline uint32_t mavlink_msg_payload_stats_tm_get_free_heap(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 72);
-}
-
-/**
- * @brief Decode a payload_stats_tm message into a struct
- *
- * @param msg The message to decode
- * @param payload_stats_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_payload_stats_tm_decode(const mavlink_message_t* msg, mavlink_payload_stats_tm_t* payload_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- payload_stats_tm->liftoff_max_acc_ts = mavlink_msg_payload_stats_tm_get_liftoff_max_acc_ts(msg);
- payload_stats_tm->dpl_ts = mavlink_msg_payload_stats_tm_get_dpl_ts(msg);
- payload_stats_tm->max_z_speed_ts = mavlink_msg_payload_stats_tm_get_max_z_speed_ts(msg);
- payload_stats_tm->apogee_ts = mavlink_msg_payload_stats_tm_get_apogee_ts(msg);
- payload_stats_tm->liftoff_max_acc = mavlink_msg_payload_stats_tm_get_liftoff_max_acc(msg);
- payload_stats_tm->dpl_max_acc = mavlink_msg_payload_stats_tm_get_dpl_max_acc(msg);
- payload_stats_tm->max_z_speed = mavlink_msg_payload_stats_tm_get_max_z_speed(msg);
- payload_stats_tm->max_airspeed_pitot = mavlink_msg_payload_stats_tm_get_max_airspeed_pitot(msg);
- payload_stats_tm->max_speed_altitude = mavlink_msg_payload_stats_tm_get_max_speed_altitude(msg);
- payload_stats_tm->apogee_lat = mavlink_msg_payload_stats_tm_get_apogee_lat(msg);
- payload_stats_tm->apogee_lon = mavlink_msg_payload_stats_tm_get_apogee_lon(msg);
- payload_stats_tm->apogee_alt = mavlink_msg_payload_stats_tm_get_apogee_alt(msg);
- payload_stats_tm->min_pressure = mavlink_msg_payload_stats_tm_get_min_pressure(msg);
- payload_stats_tm->cpu_load = mavlink_msg_payload_stats_tm_get_cpu_load(msg);
- payload_stats_tm->free_heap = mavlink_msg_payload_stats_tm_get_free_heap(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN? msg->len : MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN;
- memset(payload_stats_tm, 0, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
- memcpy(payload_stats_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_pin_tm.h b/mavlink_lib/gemini/mavlink_msg_pin_tm.h
deleted file mode 100644
index 80cc7d6547bd54d6257b5450532274f2c13126ac..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_pin_tm.h
+++ /dev/null
@@ -1,313 +0,0 @@
-#pragma once
-// MESSAGE PIN_TM PACKING
-
-#define MAVLINK_MSG_ID_PIN_TM 113
-
-
-typedef struct __mavlink_pin_tm_t {
- uint64_t timestamp; /*< [us] Timestamp*/
- uint64_t last_change_timestamp; /*< Last change timestamp of pin*/
- uint8_t pin_id; /*< A member of the PinsList enum*/
- uint8_t changes_counter; /*< Number of changes of pin*/
- uint8_t current_state; /*< Current state of pin*/
-} mavlink_pin_tm_t;
-
-#define MAVLINK_MSG_ID_PIN_TM_LEN 19
-#define MAVLINK_MSG_ID_PIN_TM_MIN_LEN 19
-#define MAVLINK_MSG_ID_113_LEN 19
-#define MAVLINK_MSG_ID_113_MIN_LEN 19
-
-#define MAVLINK_MSG_ID_PIN_TM_CRC 255
-#define MAVLINK_MSG_ID_113_CRC 255
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_PIN_TM { \
- 113, \
- "PIN_TM", \
- 5, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_pin_tm_t, timestamp) }, \
- { "pin_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_pin_tm_t, pin_id) }, \
- { "last_change_timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_pin_tm_t, last_change_timestamp) }, \
- { "changes_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_pin_tm_t, changes_counter) }, \
- { "current_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_pin_tm_t, current_state) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_PIN_TM { \
- "PIN_TM", \
- 5, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_pin_tm_t, timestamp) }, \
- { "pin_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_pin_tm_t, pin_id) }, \
- { "last_change_timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_pin_tm_t, last_change_timestamp) }, \
- { "changes_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_pin_tm_t, changes_counter) }, \
- { "current_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_pin_tm_t, current_state) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a pin_tm 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
- * @param pin_id A member of the PinsList enum
- * @param last_change_timestamp Last change timestamp of pin
- * @param changes_counter Number of changes of pin
- * @param current_state Current state of pin
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_pin_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t pin_id, uint64_t last_change_timestamp, uint8_t changes_counter, uint8_t current_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PIN_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, last_change_timestamp);
- _mav_put_uint8_t(buf, 16, pin_id);
- _mav_put_uint8_t(buf, 17, changes_counter);
- _mav_put_uint8_t(buf, 18, current_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PIN_TM_LEN);
-#else
- mavlink_pin_tm_t packet;
- packet.timestamp = timestamp;
- packet.last_change_timestamp = last_change_timestamp;
- packet.pin_id = pin_id;
- packet.changes_counter = changes_counter;
- packet.current_state = current_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PIN_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PIN_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-}
-
-/**
- * @brief Pack a pin_tm 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
- * @param pin_id A member of the PinsList enum
- * @param last_change_timestamp Last change timestamp of pin
- * @param changes_counter Number of changes of pin
- * @param current_state Current state of pin
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_pin_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t pin_id,uint64_t last_change_timestamp,uint8_t changes_counter,uint8_t current_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PIN_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, last_change_timestamp);
- _mav_put_uint8_t(buf, 16, pin_id);
- _mav_put_uint8_t(buf, 17, changes_counter);
- _mav_put_uint8_t(buf, 18, current_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PIN_TM_LEN);
-#else
- mavlink_pin_tm_t packet;
- packet.timestamp = timestamp;
- packet.last_change_timestamp = last_change_timestamp;
- packet.pin_id = pin_id;
- packet.changes_counter = changes_counter;
- packet.current_state = current_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PIN_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PIN_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-}
-
-/**
- * @brief Encode a pin_tm 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 pin_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_pin_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pin_tm_t* pin_tm)
-{
- return mavlink_msg_pin_tm_pack(system_id, component_id, msg, pin_tm->timestamp, pin_tm->pin_id, pin_tm->last_change_timestamp, pin_tm->changes_counter, pin_tm->current_state);
-}
-
-/**
- * @brief Encode a pin_tm 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 pin_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_pin_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_pin_tm_t* pin_tm)
-{
- return mavlink_msg_pin_tm_pack_chan(system_id, component_id, chan, msg, pin_tm->timestamp, pin_tm->pin_id, pin_tm->last_change_timestamp, pin_tm->changes_counter, pin_tm->current_state);
-}
-
-/**
- * @brief Send a pin_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp
- * @param pin_id A member of the PinsList enum
- * @param last_change_timestamp Last change timestamp of pin
- * @param changes_counter Number of changes of pin
- * @param current_state Current state of pin
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_pin_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t pin_id, uint64_t last_change_timestamp, uint8_t changes_counter, uint8_t current_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PIN_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, last_change_timestamp);
- _mav_put_uint8_t(buf, 16, pin_id);
- _mav_put_uint8_t(buf, 17, changes_counter);
- _mav_put_uint8_t(buf, 18, current_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PIN_TM, buf, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-#else
- mavlink_pin_tm_t packet;
- packet.timestamp = timestamp;
- packet.last_change_timestamp = last_change_timestamp;
- packet.pin_id = pin_id;
- packet.changes_counter = changes_counter;
- packet.current_state = current_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PIN_TM, (const char *)&packet, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a pin_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_pin_tm_send_struct(mavlink_channel_t chan, const mavlink_pin_tm_t* pin_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_pin_tm_send(chan, pin_tm->timestamp, pin_tm->pin_id, pin_tm->last_change_timestamp, pin_tm->changes_counter, pin_tm->current_state);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PIN_TM, (const char *)pin_tm, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_PIN_TM_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_pin_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t pin_id, uint64_t last_change_timestamp, uint8_t changes_counter, uint8_t current_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, last_change_timestamp);
- _mav_put_uint8_t(buf, 16, pin_id);
- _mav_put_uint8_t(buf, 17, changes_counter);
- _mav_put_uint8_t(buf, 18, current_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PIN_TM, buf, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-#else
- mavlink_pin_tm_t *packet = (mavlink_pin_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->last_change_timestamp = last_change_timestamp;
- packet->pin_id = pin_id;
- packet->changes_counter = changes_counter;
- packet->current_state = current_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PIN_TM, (const char *)packet, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE PIN_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from pin_tm message
- *
- * @return [us] Timestamp
- */
-static inline uint64_t mavlink_msg_pin_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field pin_id from pin_tm message
- *
- * @return A member of the PinsList enum
- */
-static inline uint8_t mavlink_msg_pin_tm_get_pin_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 16);
-}
-
-/**
- * @brief Get field last_change_timestamp from pin_tm message
- *
- * @return Last change timestamp of pin
- */
-static inline uint64_t mavlink_msg_pin_tm_get_last_change_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 8);
-}
-
-/**
- * @brief Get field changes_counter from pin_tm message
- *
- * @return Number of changes of pin
- */
-static inline uint8_t mavlink_msg_pin_tm_get_changes_counter(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 17);
-}
-
-/**
- * @brief Get field current_state from pin_tm message
- *
- * @return Current state of pin
- */
-static inline uint8_t mavlink_msg_pin_tm_get_current_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 18);
-}
-
-/**
- * @brief Decode a pin_tm message into a struct
- *
- * @param msg The message to decode
- * @param pin_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_pin_tm_decode(const mavlink_message_t* msg, mavlink_pin_tm_t* pin_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- pin_tm->timestamp = mavlink_msg_pin_tm_get_timestamp(msg);
- pin_tm->last_change_timestamp = mavlink_msg_pin_tm_get_last_change_timestamp(msg);
- pin_tm->pin_id = mavlink_msg_pin_tm_get_pin_id(msg);
- pin_tm->changes_counter = mavlink_msg_pin_tm_get_changes_counter(msg);
- pin_tm->current_state = mavlink_msg_pin_tm_get_current_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_PIN_TM_LEN? msg->len : MAVLINK_MSG_ID_PIN_TM_LEN;
- memset(pin_tm, 0, MAVLINK_MSG_ID_PIN_TM_LEN);
- memcpy(pin_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_ping_tc.h b/mavlink_lib/gemini/mavlink_msg_ping_tc.h
deleted file mode 100644
index 99a2895f9933675f201a98a080067ebf3b33bb66..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_ping_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE PING_TC PACKING
-
-#define MAVLINK_MSG_ID_PING_TC 1
-
-
-typedef struct __mavlink_ping_tc_t {
- uint64_t timestamp; /*< Timestamp to identify when it was sent*/
-} mavlink_ping_tc_t;
-
-#define MAVLINK_MSG_ID_PING_TC_LEN 8
-#define MAVLINK_MSG_ID_PING_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_1_LEN 8
-#define MAVLINK_MSG_ID_1_MIN_LEN 8
-
-#define MAVLINK_MSG_ID_PING_TC_CRC 136
-#define MAVLINK_MSG_ID_1_CRC 136
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_PING_TC { \
- 1, \
- "PING_TC", \
- 1, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_tc_t, timestamp) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_PING_TC { \
- "PING_TC", \
- 1, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_tc_t, timestamp) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ping_tc 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 Timestamp to identify when it was sent
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ping_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_TC_LEN);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PING_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-}
-
-/**
- * @brief Pack a ping_tc 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 Timestamp to identify when it was sent
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ping_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_TC_LEN);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PING_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-}
-
-/**
- * @brief Encode a ping_tc 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_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ping_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_tc_t* ping_tc)
-{
- return mavlink_msg_ping_tc_pack(system_id, component_id, msg, ping_tc->timestamp);
-}
-
-/**
- * @brief Encode a ping_tc 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_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ping_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ping_tc_t* ping_tc)
-{
- return mavlink_msg_ping_tc_pack_chan(system_id, component_id, chan, msg, ping_tc->timestamp);
-}
-
-/**
- * @brief Send a ping_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp Timestamp to identify when it was sent
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ping_tc_send(mavlink_channel_t chan, uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, buf, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)&packet, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a ping_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ping_tc_send_struct(mavlink_channel_t chan, const mavlink_ping_tc_t* ping_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ping_tc_send(chan, ping_tc->timestamp);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)ping_tc, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_PING_TC_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_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, buf, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#else
- mavlink_ping_tc_t *packet = (mavlink_ping_tc_t *)msgbuf;
- packet->timestamp = timestamp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)packet, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE PING_TC UNPACKING
-
-
-/**
- * @brief Get field timestamp from ping_tc message
- *
- * @return Timestamp to identify when it was sent
- */
-static inline uint64_t mavlink_msg_ping_tc_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Decode a ping_tc message into a struct
- *
- * @param msg The message to decode
- * @param ping_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ping_tc_decode(const mavlink_message_t* msg, mavlink_ping_tc_t* ping_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ping_tc->timestamp = mavlink_msg_ping_tc_get_timestamp(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_PING_TC_LEN? msg->len : MAVLINK_MSG_ID_PING_TC_LEN;
- memset(ping_tc, 0, MAVLINK_MSG_ID_PING_TC_LEN);
- memcpy(ping_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_pressure_tm.h b/mavlink_lib/gemini/mavlink_msg_pressure_tm.h
deleted file mode 100644
index 8291d6e36b4c63ac30cc308ca496ad3c1d1ad4a6..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_pressure_tm.h
+++ /dev/null
@@ -1,255 +0,0 @@
-#pragma once
-// MESSAGE PRESSURE_TM PACKING
-
-#define MAVLINK_MSG_ID_PRESSURE_TM 104
-
-
-typedef struct __mavlink_pressure_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float pressure; /*< [Pa] Pressure of the digital barometer*/
- char sensor_name[20]; /*< Sensor name*/
-} mavlink_pressure_tm_t;
-
-#define MAVLINK_MSG_ID_PRESSURE_TM_LEN 32
-#define MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_104_LEN 32
-#define MAVLINK_MSG_ID_104_MIN_LEN 32
-
-#define MAVLINK_MSG_ID_PRESSURE_TM_CRC 87
-#define MAVLINK_MSG_ID_104_CRC 87
-
-#define MAVLINK_MSG_PRESSURE_TM_FIELD_SENSOR_NAME_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_PRESSURE_TM { \
- 104, \
- "PRESSURE_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_pressure_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_pressure_tm_t, sensor_name) }, \
- { "pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_pressure_tm_t, pressure) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_PRESSURE_TM { \
- "PRESSURE_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_pressure_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_pressure_tm_t, sensor_name) }, \
- { "pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_pressure_tm_t, pressure) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a pressure_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param pressure [Pa] Pressure of the digital barometer
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_pressure_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_name, float pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PRESSURE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PRESSURE_TM_LEN);
-#else
- mavlink_pressure_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure = pressure;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PRESSURE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PRESSURE_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-}
-
-/**
- * @brief Pack a pressure_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param pressure [Pa] Pressure of the digital barometer
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_pressure_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_name,float pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PRESSURE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PRESSURE_TM_LEN);
-#else
- mavlink_pressure_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure = pressure;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PRESSURE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PRESSURE_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-}
-
-/**
- * @brief Encode a pressure_tm 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 pressure_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_pressure_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pressure_tm_t* pressure_tm)
-{
- return mavlink_msg_pressure_tm_pack(system_id, component_id, msg, pressure_tm->timestamp, pressure_tm->sensor_name, pressure_tm->pressure);
-}
-
-/**
- * @brief Encode a pressure_tm 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 pressure_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_pressure_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_pressure_tm_t* pressure_tm)
-{
- return mavlink_msg_pressure_tm_pack_chan(system_id, component_id, chan, msg, pressure_tm->timestamp, pressure_tm->sensor_name, pressure_tm->pressure);
-}
-
-/**
- * @brief Send a pressure_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_name Sensor name
- * @param pressure [Pa] Pressure of the digital barometer
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_pressure_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PRESSURE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PRESSURE_TM, buf, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-#else
- mavlink_pressure_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure = pressure;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PRESSURE_TM, (const char *)&packet, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a pressure_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_pressure_tm_send_struct(mavlink_channel_t chan, const mavlink_pressure_tm_t* pressure_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_pressure_tm_send(chan, pressure_tm->timestamp, pressure_tm->sensor_name, pressure_tm->pressure);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PRESSURE_TM, (const char *)pressure_tm, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_PRESSURE_TM_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_pressure_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PRESSURE_TM, buf, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-#else
- mavlink_pressure_tm_t *packet = (mavlink_pressure_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->pressure = pressure;
- mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PRESSURE_TM, (const char *)packet, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE PRESSURE_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from pressure_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_pressure_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_name from pressure_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_pressure_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
-{
- return _MAV_RETURN_char_array(msg, sensor_name, 20, 12);
-}
-
-/**
- * @brief Get field pressure from pressure_tm message
- *
- * @return [Pa] Pressure of the digital barometer
- */
-static inline float mavlink_msg_pressure_tm_get_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Decode a pressure_tm message into a struct
- *
- * @param msg The message to decode
- * @param pressure_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_pressure_tm_decode(const mavlink_message_t* msg, mavlink_pressure_tm_t* pressure_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- pressure_tm->timestamp = mavlink_msg_pressure_tm_get_timestamp(msg);
- pressure_tm->pressure = mavlink_msg_pressure_tm_get_pressure(msg);
- mavlink_msg_pressure_tm_get_sensor_name(msg, pressure_tm->sensor_name);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_PRESSURE_TM_LEN? msg->len : MAVLINK_MSG_ID_PRESSURE_TM_LEN;
- memset(pressure_tm, 0, MAVLINK_MSG_ID_PRESSURE_TM_LEN);
- memcpy(pressure_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_raw_event_tc.h b/mavlink_lib/gemini/mavlink_msg_raw_event_tc.h
deleted file mode 100644
index fe6d60a1b38e429fc0f0049aa21234613d3c8e99..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_raw_event_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE RAW_EVENT_TC PACKING
-
-#define MAVLINK_MSG_ID_RAW_EVENT_TC 13
-
-
-typedef struct __mavlink_raw_event_tc_t {
- uint8_t topic_id; /*< Id of the topic to which the event should be posted*/
- uint8_t event_id; /*< Id of the event to be posted*/
-} mavlink_raw_event_tc_t;
-
-#define MAVLINK_MSG_ID_RAW_EVENT_TC_LEN 2
-#define MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN 2
-#define MAVLINK_MSG_ID_13_LEN 2
-#define MAVLINK_MSG_ID_13_MIN_LEN 2
-
-#define MAVLINK_MSG_ID_RAW_EVENT_TC_CRC 218
-#define MAVLINK_MSG_ID_13_CRC 218
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_RAW_EVENT_TC { \
- 13, \
- "RAW_EVENT_TC", \
- 2, \
- { { "topic_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_raw_event_tc_t, topic_id) }, \
- { "event_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_raw_event_tc_t, event_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_RAW_EVENT_TC { \
- "RAW_EVENT_TC", \
- 2, \
- { { "topic_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_raw_event_tc_t, topic_id) }, \
- { "event_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_raw_event_tc_t, event_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a raw_event_tc 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 topic_id Id of the topic to which the event should be posted
- * @param event_id Id of the event to be posted
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_raw_event_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t topic_id, uint8_t event_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_EVENT_TC_LEN];
- _mav_put_uint8_t(buf, 0, topic_id);
- _mav_put_uint8_t(buf, 1, event_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#else
- mavlink_raw_event_tc_t packet;
- packet.topic_id = topic_id;
- packet.event_id = event_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RAW_EVENT_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-}
-
-/**
- * @brief Pack a raw_event_tc 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 topic_id Id of the topic to which the event should be posted
- * @param event_id Id of the event to be posted
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_raw_event_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t topic_id,uint8_t event_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_EVENT_TC_LEN];
- _mav_put_uint8_t(buf, 0, topic_id);
- _mav_put_uint8_t(buf, 1, event_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#else
- mavlink_raw_event_tc_t packet;
- packet.topic_id = topic_id;
- packet.event_id = event_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RAW_EVENT_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-}
-
-/**
- * @brief Encode a raw_event_tc 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_event_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_raw_event_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_event_tc_t* raw_event_tc)
-{
- return mavlink_msg_raw_event_tc_pack(system_id, component_id, msg, raw_event_tc->topic_id, raw_event_tc->event_id);
-}
-
-/**
- * @brief Encode a raw_event_tc 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_event_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_raw_event_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_event_tc_t* raw_event_tc)
-{
- return mavlink_msg_raw_event_tc_pack_chan(system_id, component_id, chan, msg, raw_event_tc->topic_id, raw_event_tc->event_id);
-}
-
-/**
- * @brief Send a raw_event_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param topic_id Id of the topic to which the event should be posted
- * @param event_id Id of the event to be posted
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_raw_event_tc_send(mavlink_channel_t chan, uint8_t topic_id, uint8_t event_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_EVENT_TC_LEN];
- _mav_put_uint8_t(buf, 0, topic_id);
- _mav_put_uint8_t(buf, 1, event_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, buf, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#else
- mavlink_raw_event_tc_t packet;
- packet.topic_id = topic_id;
- packet.event_id = event_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, (const char *)&packet, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a raw_event_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_raw_event_tc_send_struct(mavlink_channel_t chan, const mavlink_raw_event_tc_t* raw_event_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_raw_event_tc_send(chan, raw_event_tc->topic_id, raw_event_tc->event_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, (const char *)raw_event_tc, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_RAW_EVENT_TC_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_event_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t topic_id, uint8_t event_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, topic_id);
- _mav_put_uint8_t(buf, 1, event_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, buf, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#else
- mavlink_raw_event_tc_t *packet = (mavlink_raw_event_tc_t *)msgbuf;
- packet->topic_id = topic_id;
- packet->event_id = event_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, (const char *)packet, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE RAW_EVENT_TC UNPACKING
-
-
-/**
- * @brief Get field topic_id from raw_event_tc message
- *
- * @return Id of the topic to which the event should be posted
- */
-static inline uint8_t mavlink_msg_raw_event_tc_get_topic_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field event_id from raw_event_tc message
- *
- * @return Id of the event to be posted
- */
-static inline uint8_t mavlink_msg_raw_event_tc_get_event_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Decode a raw_event_tc message into a struct
- *
- * @param msg The message to decode
- * @param raw_event_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_raw_event_tc_decode(const mavlink_message_t* msg, mavlink_raw_event_tc_t* raw_event_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- raw_event_tc->topic_id = mavlink_msg_raw_event_tc_get_topic_id(msg);
- raw_event_tc->event_id = mavlink_msg_raw_event_tc_get_event_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_RAW_EVENT_TC_LEN? msg->len : MAVLINK_MSG_ID_RAW_EVENT_TC_LEN;
- memset(raw_event_tc, 0, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
- memcpy(raw_event_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_receiver_tm.h b/mavlink_lib/gemini/mavlink_msg_receiver_tm.h
deleted file mode 100644
index d87647ee1d1ad1a8b59605721d6fca6469887093..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_receiver_tm.h
+++ /dev/null
@@ -1,688 +0,0 @@
-#pragma once
-// MESSAGE RECEIVER_TM PACKING
-
-#define MAVLINK_MSG_ID_RECEIVER_TM 150
-
-
-typedef struct __mavlink_receiver_tm_t {
- uint64_t timestamp; /*< [us] Timestamp*/
- float main_rx_rssi; /*< [dBm] Receive RSSI*/
- float main_rx_fei; /*< [Hz] Receive frequency error index*/
- float payload_rx_rssi; /*< [dBm] Receive RSSI*/
- float payload_rx_fei; /*< [Hz] Receive frequency error index*/
- float battery_voltage; /*< [V] Battery voltage*/
- uint16_t main_packet_tx_error_count; /*< Number of errors during send*/
- uint16_t main_tx_bitrate; /*< [b/s] Send bitrate*/
- uint16_t main_packet_rx_success_count; /*< Number of succesfull received mavlink packets*/
- uint16_t main_packet_rx_drop_count; /*< Number of dropped mavlink packets*/
- uint16_t main_rx_bitrate; /*< [b/s] Receive bitrate*/
- uint16_t payload_packet_tx_error_count; /*< Number of errors during send*/
- uint16_t payload_tx_bitrate; /*< [b/s] Send bitrate*/
- uint16_t payload_packet_rx_success_count; /*< Number of succesfull received mavlink packets*/
- uint16_t payload_packet_rx_drop_count; /*< Number of dropped mavlink packets*/
- uint16_t payload_rx_bitrate; /*< [b/s] Receive bitrate*/
- uint8_t main_radio_present; /*< Boolean indicating the presence of the main radio*/
- uint8_t payload_radio_present; /*< Boolean indicating the presence of the payload radio*/
- uint8_t ethernet_present; /*< Boolean indicating the presence of the ethernet module*/
- uint8_t ethernet_status; /*< Status flag indicating the status of the ethernet PHY*/
-} mavlink_receiver_tm_t;
-
-#define MAVLINK_MSG_ID_RECEIVER_TM_LEN 52
-#define MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN 52
-#define MAVLINK_MSG_ID_150_LEN 52
-#define MAVLINK_MSG_ID_150_MIN_LEN 52
-
-#define MAVLINK_MSG_ID_RECEIVER_TM_CRC 117
-#define MAVLINK_MSG_ID_150_CRC 117
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_RECEIVER_TM { \
- 150, \
- "RECEIVER_TM", \
- 20, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_receiver_tm_t, timestamp) }, \
- { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_receiver_tm_t, main_radio_present) }, \
- { "main_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_receiver_tm_t, main_packet_tx_error_count) }, \
- { "main_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_receiver_tm_t, main_tx_bitrate) }, \
- { "main_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_receiver_tm_t, main_packet_rx_success_count) }, \
- { "main_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_receiver_tm_t, main_packet_rx_drop_count) }, \
- { "main_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_receiver_tm_t, main_rx_bitrate) }, \
- { "main_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_receiver_tm_t, main_rx_rssi) }, \
- { "main_rx_fei", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_receiver_tm_t, main_rx_fei) }, \
- { "payload_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_receiver_tm_t, payload_radio_present) }, \
- { "payload_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_receiver_tm_t, payload_packet_tx_error_count) }, \
- { "payload_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_receiver_tm_t, payload_tx_bitrate) }, \
- { "payload_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 42, offsetof(mavlink_receiver_tm_t, payload_packet_rx_success_count) }, \
- { "payload_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_receiver_tm_t, payload_packet_rx_drop_count) }, \
- { "payload_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 46, offsetof(mavlink_receiver_tm_t, payload_rx_bitrate) }, \
- { "payload_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_receiver_tm_t, payload_rx_rssi) }, \
- { "payload_rx_fei", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_receiver_tm_t, payload_rx_fei) }, \
- { "ethernet_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_receiver_tm_t, ethernet_present) }, \
- { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_receiver_tm_t, ethernet_status) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_receiver_tm_t, battery_voltage) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_RECEIVER_TM { \
- "RECEIVER_TM", \
- 20, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_receiver_tm_t, timestamp) }, \
- { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_receiver_tm_t, main_radio_present) }, \
- { "main_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_receiver_tm_t, main_packet_tx_error_count) }, \
- { "main_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_receiver_tm_t, main_tx_bitrate) }, \
- { "main_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_receiver_tm_t, main_packet_rx_success_count) }, \
- { "main_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_receiver_tm_t, main_packet_rx_drop_count) }, \
- { "main_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_receiver_tm_t, main_rx_bitrate) }, \
- { "main_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_receiver_tm_t, main_rx_rssi) }, \
- { "main_rx_fei", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_receiver_tm_t, main_rx_fei) }, \
- { "payload_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_receiver_tm_t, payload_radio_present) }, \
- { "payload_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_receiver_tm_t, payload_packet_tx_error_count) }, \
- { "payload_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_receiver_tm_t, payload_tx_bitrate) }, \
- { "payload_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 42, offsetof(mavlink_receiver_tm_t, payload_packet_rx_success_count) }, \
- { "payload_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_receiver_tm_t, payload_packet_rx_drop_count) }, \
- { "payload_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 46, offsetof(mavlink_receiver_tm_t, payload_rx_bitrate) }, \
- { "payload_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_receiver_tm_t, payload_rx_rssi) }, \
- { "payload_rx_fei", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_receiver_tm_t, payload_rx_fei) }, \
- { "ethernet_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_receiver_tm_t, ethernet_present) }, \
- { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_receiver_tm_t, ethernet_status) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_receiver_tm_t, battery_voltage) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a receiver_tm 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
- * @param main_radio_present Boolean indicating the presence of the main radio
- * @param main_packet_tx_error_count Number of errors during send
- * @param main_tx_bitrate [b/s] Send bitrate
- * @param main_packet_rx_success_count Number of succesfull received mavlink packets
- * @param main_packet_rx_drop_count Number of dropped mavlink packets
- * @param main_rx_bitrate [b/s] Receive bitrate
- * @param main_rx_rssi [dBm] Receive RSSI
- * @param main_rx_fei [Hz] Receive frequency error index
- * @param payload_radio_present Boolean indicating the presence of the payload radio
- * @param payload_packet_tx_error_count Number of errors during send
- * @param payload_tx_bitrate [b/s] Send bitrate
- * @param payload_packet_rx_success_count Number of succesfull received mavlink packets
- * @param payload_packet_rx_drop_count Number of dropped mavlink packets
- * @param payload_rx_bitrate [b/s] Receive bitrate
- * @param payload_rx_rssi [dBm] Receive RSSI
- * @param payload_rx_fei [Hz] Receive frequency error index
- * @param ethernet_present Boolean indicating the presence of the ethernet module
- * @param ethernet_status Status flag indicating the status of the ethernet PHY
- * @param battery_voltage [V] Battery voltage
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_receiver_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, float main_rx_fei, uint8_t payload_radio_present, uint16_t payload_packet_tx_error_count, uint16_t payload_tx_bitrate, uint16_t payload_packet_rx_success_count, uint16_t payload_packet_rx_drop_count, uint16_t payload_rx_bitrate, float payload_rx_rssi, float payload_rx_fei, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RECEIVER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, main_rx_rssi);
- _mav_put_float(buf, 12, main_rx_fei);
- _mav_put_float(buf, 16, payload_rx_rssi);
- _mav_put_float(buf, 20, payload_rx_fei);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_uint16_t(buf, 28, main_packet_tx_error_count);
- _mav_put_uint16_t(buf, 30, main_tx_bitrate);
- _mav_put_uint16_t(buf, 32, main_packet_rx_success_count);
- _mav_put_uint16_t(buf, 34, main_packet_rx_drop_count);
- _mav_put_uint16_t(buf, 36, main_rx_bitrate);
- _mav_put_uint16_t(buf, 38, payload_packet_tx_error_count);
- _mav_put_uint16_t(buf, 40, payload_tx_bitrate);
- _mav_put_uint16_t(buf, 42, payload_packet_rx_success_count);
- _mav_put_uint16_t(buf, 44, payload_packet_rx_drop_count);
- _mav_put_uint16_t(buf, 46, payload_rx_bitrate);
- _mav_put_uint8_t(buf, 48, main_radio_present);
- _mav_put_uint8_t(buf, 49, payload_radio_present);
- _mav_put_uint8_t(buf, 50, ethernet_present);
- _mav_put_uint8_t(buf, 51, ethernet_status);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
-#else
- mavlink_receiver_tm_t packet;
- packet.timestamp = timestamp;
- packet.main_rx_rssi = main_rx_rssi;
- packet.main_rx_fei = main_rx_fei;
- packet.payload_rx_rssi = payload_rx_rssi;
- packet.payload_rx_fei = payload_rx_fei;
- packet.battery_voltage = battery_voltage;
- packet.main_packet_tx_error_count = main_packet_tx_error_count;
- packet.main_tx_bitrate = main_tx_bitrate;
- packet.main_packet_rx_success_count = main_packet_rx_success_count;
- packet.main_packet_rx_drop_count = main_packet_rx_drop_count;
- packet.main_rx_bitrate = main_rx_bitrate;
- packet.payload_packet_tx_error_count = payload_packet_tx_error_count;
- packet.payload_tx_bitrate = payload_tx_bitrate;
- packet.payload_packet_rx_success_count = payload_packet_rx_success_count;
- packet.payload_packet_rx_drop_count = payload_packet_rx_drop_count;
- packet.payload_rx_bitrate = payload_rx_bitrate;
- packet.main_radio_present = main_radio_present;
- packet.payload_radio_present = payload_radio_present;
- packet.ethernet_present = ethernet_present;
- packet.ethernet_status = ethernet_status;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RECEIVER_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-}
-
-/**
- * @brief Pack a receiver_tm 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
- * @param main_radio_present Boolean indicating the presence of the main radio
- * @param main_packet_tx_error_count Number of errors during send
- * @param main_tx_bitrate [b/s] Send bitrate
- * @param main_packet_rx_success_count Number of succesfull received mavlink packets
- * @param main_packet_rx_drop_count Number of dropped mavlink packets
- * @param main_rx_bitrate [b/s] Receive bitrate
- * @param main_rx_rssi [dBm] Receive RSSI
- * @param main_rx_fei [Hz] Receive frequency error index
- * @param payload_radio_present Boolean indicating the presence of the payload radio
- * @param payload_packet_tx_error_count Number of errors during send
- * @param payload_tx_bitrate [b/s] Send bitrate
- * @param payload_packet_rx_success_count Number of succesfull received mavlink packets
- * @param payload_packet_rx_drop_count Number of dropped mavlink packets
- * @param payload_rx_bitrate [b/s] Receive bitrate
- * @param payload_rx_rssi [dBm] Receive RSSI
- * @param payload_rx_fei [Hz] Receive frequency error index
- * @param ethernet_present Boolean indicating the presence of the ethernet module
- * @param ethernet_status Status flag indicating the status of the ethernet PHY
- * @param battery_voltage [V] Battery voltage
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_receiver_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t main_radio_present,uint16_t main_packet_tx_error_count,uint16_t main_tx_bitrate,uint16_t main_packet_rx_success_count,uint16_t main_packet_rx_drop_count,uint16_t main_rx_bitrate,float main_rx_rssi,float main_rx_fei,uint8_t payload_radio_present,uint16_t payload_packet_tx_error_count,uint16_t payload_tx_bitrate,uint16_t payload_packet_rx_success_count,uint16_t payload_packet_rx_drop_count,uint16_t payload_rx_bitrate,float payload_rx_rssi,float payload_rx_fei,uint8_t ethernet_present,uint8_t ethernet_status,float battery_voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RECEIVER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, main_rx_rssi);
- _mav_put_float(buf, 12, main_rx_fei);
- _mav_put_float(buf, 16, payload_rx_rssi);
- _mav_put_float(buf, 20, payload_rx_fei);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_uint16_t(buf, 28, main_packet_tx_error_count);
- _mav_put_uint16_t(buf, 30, main_tx_bitrate);
- _mav_put_uint16_t(buf, 32, main_packet_rx_success_count);
- _mav_put_uint16_t(buf, 34, main_packet_rx_drop_count);
- _mav_put_uint16_t(buf, 36, main_rx_bitrate);
- _mav_put_uint16_t(buf, 38, payload_packet_tx_error_count);
- _mav_put_uint16_t(buf, 40, payload_tx_bitrate);
- _mav_put_uint16_t(buf, 42, payload_packet_rx_success_count);
- _mav_put_uint16_t(buf, 44, payload_packet_rx_drop_count);
- _mav_put_uint16_t(buf, 46, payload_rx_bitrate);
- _mav_put_uint8_t(buf, 48, main_radio_present);
- _mav_put_uint8_t(buf, 49, payload_radio_present);
- _mav_put_uint8_t(buf, 50, ethernet_present);
- _mav_put_uint8_t(buf, 51, ethernet_status);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
-#else
- mavlink_receiver_tm_t packet;
- packet.timestamp = timestamp;
- packet.main_rx_rssi = main_rx_rssi;
- packet.main_rx_fei = main_rx_fei;
- packet.payload_rx_rssi = payload_rx_rssi;
- packet.payload_rx_fei = payload_rx_fei;
- packet.battery_voltage = battery_voltage;
- packet.main_packet_tx_error_count = main_packet_tx_error_count;
- packet.main_tx_bitrate = main_tx_bitrate;
- packet.main_packet_rx_success_count = main_packet_rx_success_count;
- packet.main_packet_rx_drop_count = main_packet_rx_drop_count;
- packet.main_rx_bitrate = main_rx_bitrate;
- packet.payload_packet_tx_error_count = payload_packet_tx_error_count;
- packet.payload_tx_bitrate = payload_tx_bitrate;
- packet.payload_packet_rx_success_count = payload_packet_rx_success_count;
- packet.payload_packet_rx_drop_count = payload_packet_rx_drop_count;
- packet.payload_rx_bitrate = payload_rx_bitrate;
- packet.main_radio_present = main_radio_present;
- packet.payload_radio_present = payload_radio_present;
- packet.ethernet_present = ethernet_present;
- packet.ethernet_status = ethernet_status;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RECEIVER_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-}
-
-/**
- * @brief Encode a receiver_tm 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 receiver_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_receiver_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_receiver_tm_t* receiver_tm)
-{
- return mavlink_msg_receiver_tm_pack(system_id, component_id, msg, receiver_tm->timestamp, receiver_tm->main_radio_present, receiver_tm->main_packet_tx_error_count, receiver_tm->main_tx_bitrate, receiver_tm->main_packet_rx_success_count, receiver_tm->main_packet_rx_drop_count, receiver_tm->main_rx_bitrate, receiver_tm->main_rx_rssi, receiver_tm->main_rx_fei, receiver_tm->payload_radio_present, receiver_tm->payload_packet_tx_error_count, receiver_tm->payload_tx_bitrate, receiver_tm->payload_packet_rx_success_count, receiver_tm->payload_packet_rx_drop_count, receiver_tm->payload_rx_bitrate, receiver_tm->payload_rx_rssi, receiver_tm->payload_rx_fei, receiver_tm->ethernet_present, receiver_tm->ethernet_status, receiver_tm->battery_voltage);
-}
-
-/**
- * @brief Encode a receiver_tm 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 receiver_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_receiver_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_receiver_tm_t* receiver_tm)
-{
- return mavlink_msg_receiver_tm_pack_chan(system_id, component_id, chan, msg, receiver_tm->timestamp, receiver_tm->main_radio_present, receiver_tm->main_packet_tx_error_count, receiver_tm->main_tx_bitrate, receiver_tm->main_packet_rx_success_count, receiver_tm->main_packet_rx_drop_count, receiver_tm->main_rx_bitrate, receiver_tm->main_rx_rssi, receiver_tm->main_rx_fei, receiver_tm->payload_radio_present, receiver_tm->payload_packet_tx_error_count, receiver_tm->payload_tx_bitrate, receiver_tm->payload_packet_rx_success_count, receiver_tm->payload_packet_rx_drop_count, receiver_tm->payload_rx_bitrate, receiver_tm->payload_rx_rssi, receiver_tm->payload_rx_fei, receiver_tm->ethernet_present, receiver_tm->ethernet_status, receiver_tm->battery_voltage);
-}
-
-/**
- * @brief Send a receiver_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp
- * @param main_radio_present Boolean indicating the presence of the main radio
- * @param main_packet_tx_error_count Number of errors during send
- * @param main_tx_bitrate [b/s] Send bitrate
- * @param main_packet_rx_success_count Number of succesfull received mavlink packets
- * @param main_packet_rx_drop_count Number of dropped mavlink packets
- * @param main_rx_bitrate [b/s] Receive bitrate
- * @param main_rx_rssi [dBm] Receive RSSI
- * @param main_rx_fei [Hz] Receive frequency error index
- * @param payload_radio_present Boolean indicating the presence of the payload radio
- * @param payload_packet_tx_error_count Number of errors during send
- * @param payload_tx_bitrate [b/s] Send bitrate
- * @param payload_packet_rx_success_count Number of succesfull received mavlink packets
- * @param payload_packet_rx_drop_count Number of dropped mavlink packets
- * @param payload_rx_bitrate [b/s] Receive bitrate
- * @param payload_rx_rssi [dBm] Receive RSSI
- * @param payload_rx_fei [Hz] Receive frequency error index
- * @param ethernet_present Boolean indicating the presence of the ethernet module
- * @param ethernet_status Status flag indicating the status of the ethernet PHY
- * @param battery_voltage [V] Battery voltage
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_receiver_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, float main_rx_fei, uint8_t payload_radio_present, uint16_t payload_packet_tx_error_count, uint16_t payload_tx_bitrate, uint16_t payload_packet_rx_success_count, uint16_t payload_packet_rx_drop_count, uint16_t payload_rx_bitrate, float payload_rx_rssi, float payload_rx_fei, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RECEIVER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, main_rx_rssi);
- _mav_put_float(buf, 12, main_rx_fei);
- _mav_put_float(buf, 16, payload_rx_rssi);
- _mav_put_float(buf, 20, payload_rx_fei);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_uint16_t(buf, 28, main_packet_tx_error_count);
- _mav_put_uint16_t(buf, 30, main_tx_bitrate);
- _mav_put_uint16_t(buf, 32, main_packet_rx_success_count);
- _mav_put_uint16_t(buf, 34, main_packet_rx_drop_count);
- _mav_put_uint16_t(buf, 36, main_rx_bitrate);
- _mav_put_uint16_t(buf, 38, payload_packet_tx_error_count);
- _mav_put_uint16_t(buf, 40, payload_tx_bitrate);
- _mav_put_uint16_t(buf, 42, payload_packet_rx_success_count);
- _mav_put_uint16_t(buf, 44, payload_packet_rx_drop_count);
- _mav_put_uint16_t(buf, 46, payload_rx_bitrate);
- _mav_put_uint8_t(buf, 48, main_radio_present);
- _mav_put_uint8_t(buf, 49, payload_radio_present);
- _mav_put_uint8_t(buf, 50, ethernet_present);
- _mav_put_uint8_t(buf, 51, ethernet_status);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, buf, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-#else
- mavlink_receiver_tm_t packet;
- packet.timestamp = timestamp;
- packet.main_rx_rssi = main_rx_rssi;
- packet.main_rx_fei = main_rx_fei;
- packet.payload_rx_rssi = payload_rx_rssi;
- packet.payload_rx_fei = payload_rx_fei;
- packet.battery_voltage = battery_voltage;
- packet.main_packet_tx_error_count = main_packet_tx_error_count;
- packet.main_tx_bitrate = main_tx_bitrate;
- packet.main_packet_rx_success_count = main_packet_rx_success_count;
- packet.main_packet_rx_drop_count = main_packet_rx_drop_count;
- packet.main_rx_bitrate = main_rx_bitrate;
- packet.payload_packet_tx_error_count = payload_packet_tx_error_count;
- packet.payload_tx_bitrate = payload_tx_bitrate;
- packet.payload_packet_rx_success_count = payload_packet_rx_success_count;
- packet.payload_packet_rx_drop_count = payload_packet_rx_drop_count;
- packet.payload_rx_bitrate = payload_rx_bitrate;
- packet.main_radio_present = main_radio_present;
- packet.payload_radio_present = payload_radio_present;
- packet.ethernet_present = ethernet_present;
- packet.ethernet_status = ethernet_status;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, (const char *)&packet, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a receiver_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_receiver_tm_send_struct(mavlink_channel_t chan, const mavlink_receiver_tm_t* receiver_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_receiver_tm_send(chan, receiver_tm->timestamp, receiver_tm->main_radio_present, receiver_tm->main_packet_tx_error_count, receiver_tm->main_tx_bitrate, receiver_tm->main_packet_rx_success_count, receiver_tm->main_packet_rx_drop_count, receiver_tm->main_rx_bitrate, receiver_tm->main_rx_rssi, receiver_tm->main_rx_fei, receiver_tm->payload_radio_present, receiver_tm->payload_packet_tx_error_count, receiver_tm->payload_tx_bitrate, receiver_tm->payload_packet_rx_success_count, receiver_tm->payload_packet_rx_drop_count, receiver_tm->payload_rx_bitrate, receiver_tm->payload_rx_rssi, receiver_tm->payload_rx_fei, receiver_tm->ethernet_present, receiver_tm->ethernet_status, receiver_tm->battery_voltage);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, (const char *)receiver_tm, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_RECEIVER_TM_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_receiver_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, float main_rx_fei, uint8_t payload_radio_present, uint16_t payload_packet_tx_error_count, uint16_t payload_tx_bitrate, uint16_t payload_packet_rx_success_count, uint16_t payload_packet_rx_drop_count, uint16_t payload_rx_bitrate, float payload_rx_rssi, float payload_rx_fei, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, main_rx_rssi);
- _mav_put_float(buf, 12, main_rx_fei);
- _mav_put_float(buf, 16, payload_rx_rssi);
- _mav_put_float(buf, 20, payload_rx_fei);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_uint16_t(buf, 28, main_packet_tx_error_count);
- _mav_put_uint16_t(buf, 30, main_tx_bitrate);
- _mav_put_uint16_t(buf, 32, main_packet_rx_success_count);
- _mav_put_uint16_t(buf, 34, main_packet_rx_drop_count);
- _mav_put_uint16_t(buf, 36, main_rx_bitrate);
- _mav_put_uint16_t(buf, 38, payload_packet_tx_error_count);
- _mav_put_uint16_t(buf, 40, payload_tx_bitrate);
- _mav_put_uint16_t(buf, 42, payload_packet_rx_success_count);
- _mav_put_uint16_t(buf, 44, payload_packet_rx_drop_count);
- _mav_put_uint16_t(buf, 46, payload_rx_bitrate);
- _mav_put_uint8_t(buf, 48, main_radio_present);
- _mav_put_uint8_t(buf, 49, payload_radio_present);
- _mav_put_uint8_t(buf, 50, ethernet_present);
- _mav_put_uint8_t(buf, 51, ethernet_status);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, buf, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-#else
- mavlink_receiver_tm_t *packet = (mavlink_receiver_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->main_rx_rssi = main_rx_rssi;
- packet->main_rx_fei = main_rx_fei;
- packet->payload_rx_rssi = payload_rx_rssi;
- packet->payload_rx_fei = payload_rx_fei;
- packet->battery_voltage = battery_voltage;
- packet->main_packet_tx_error_count = main_packet_tx_error_count;
- packet->main_tx_bitrate = main_tx_bitrate;
- packet->main_packet_rx_success_count = main_packet_rx_success_count;
- packet->main_packet_rx_drop_count = main_packet_rx_drop_count;
- packet->main_rx_bitrate = main_rx_bitrate;
- packet->payload_packet_tx_error_count = payload_packet_tx_error_count;
- packet->payload_tx_bitrate = payload_tx_bitrate;
- packet->payload_packet_rx_success_count = payload_packet_rx_success_count;
- packet->payload_packet_rx_drop_count = payload_packet_rx_drop_count;
- packet->payload_rx_bitrate = payload_rx_bitrate;
- packet->main_radio_present = main_radio_present;
- packet->payload_radio_present = payload_radio_present;
- packet->ethernet_present = ethernet_present;
- packet->ethernet_status = ethernet_status;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, (const char *)packet, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE RECEIVER_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from receiver_tm message
- *
- * @return [us] Timestamp
- */
-static inline uint64_t mavlink_msg_receiver_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field main_radio_present from receiver_tm message
- *
- * @return Boolean indicating the presence of the main radio
- */
-static inline uint8_t mavlink_msg_receiver_tm_get_main_radio_present(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 48);
-}
-
-/**
- * @brief Get field main_packet_tx_error_count from receiver_tm message
- *
- * @return Number of errors during send
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_main_packet_tx_error_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 28);
-}
-
-/**
- * @brief Get field main_tx_bitrate from receiver_tm message
- *
- * @return [b/s] Send bitrate
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_main_tx_bitrate(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 30);
-}
-
-/**
- * @brief Get field main_packet_rx_success_count from receiver_tm message
- *
- * @return Number of succesfull received mavlink packets
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_main_packet_rx_success_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 32);
-}
-
-/**
- * @brief Get field main_packet_rx_drop_count from receiver_tm message
- *
- * @return Number of dropped mavlink packets
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_main_packet_rx_drop_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 34);
-}
-
-/**
- * @brief Get field main_rx_bitrate from receiver_tm message
- *
- * @return [b/s] Receive bitrate
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_main_rx_bitrate(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 36);
-}
-
-/**
- * @brief Get field main_rx_rssi from receiver_tm message
- *
- * @return [dBm] Receive RSSI
- */
-static inline float mavlink_msg_receiver_tm_get_main_rx_rssi(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field main_rx_fei from receiver_tm message
- *
- * @return [Hz] Receive frequency error index
- */
-static inline float mavlink_msg_receiver_tm_get_main_rx_fei(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field payload_radio_present from receiver_tm message
- *
- * @return Boolean indicating the presence of the payload radio
- */
-static inline uint8_t mavlink_msg_receiver_tm_get_payload_radio_present(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 49);
-}
-
-/**
- * @brief Get field payload_packet_tx_error_count from receiver_tm message
- *
- * @return Number of errors during send
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_payload_packet_tx_error_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 38);
-}
-
-/**
- * @brief Get field payload_tx_bitrate from receiver_tm message
- *
- * @return [b/s] Send bitrate
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_payload_tx_bitrate(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 40);
-}
-
-/**
- * @brief Get field payload_packet_rx_success_count from receiver_tm message
- *
- * @return Number of succesfull received mavlink packets
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_payload_packet_rx_success_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 42);
-}
-
-/**
- * @brief Get field payload_packet_rx_drop_count from receiver_tm message
- *
- * @return Number of dropped mavlink packets
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_payload_packet_rx_drop_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 44);
-}
-
-/**
- * @brief Get field payload_rx_bitrate from receiver_tm message
- *
- * @return [b/s] Receive bitrate
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_payload_rx_bitrate(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 46);
-}
-
-/**
- * @brief Get field payload_rx_rssi from receiver_tm message
- *
- * @return [dBm] Receive RSSI
- */
-static inline float mavlink_msg_receiver_tm_get_payload_rx_rssi(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field payload_rx_fei from receiver_tm message
- *
- * @return [Hz] Receive frequency error index
- */
-static inline float mavlink_msg_receiver_tm_get_payload_rx_fei(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field ethernet_present from receiver_tm message
- *
- * @return Boolean indicating the presence of the ethernet module
- */
-static inline uint8_t mavlink_msg_receiver_tm_get_ethernet_present(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 50);
-}
-
-/**
- * @brief Get field ethernet_status from receiver_tm message
- *
- * @return Status flag indicating the status of the ethernet PHY
- */
-static inline uint8_t mavlink_msg_receiver_tm_get_ethernet_status(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 51);
-}
-
-/**
- * @brief Get field battery_voltage from receiver_tm message
- *
- * @return [V] Battery voltage
- */
-static inline float mavlink_msg_receiver_tm_get_battery_voltage(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Decode a receiver_tm message into a struct
- *
- * @param msg The message to decode
- * @param receiver_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_receiver_tm_decode(const mavlink_message_t* msg, mavlink_receiver_tm_t* receiver_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- receiver_tm->timestamp = mavlink_msg_receiver_tm_get_timestamp(msg);
- receiver_tm->main_rx_rssi = mavlink_msg_receiver_tm_get_main_rx_rssi(msg);
- receiver_tm->main_rx_fei = mavlink_msg_receiver_tm_get_main_rx_fei(msg);
- receiver_tm->payload_rx_rssi = mavlink_msg_receiver_tm_get_payload_rx_rssi(msg);
- receiver_tm->payload_rx_fei = mavlink_msg_receiver_tm_get_payload_rx_fei(msg);
- receiver_tm->battery_voltage = mavlink_msg_receiver_tm_get_battery_voltage(msg);
- receiver_tm->main_packet_tx_error_count = mavlink_msg_receiver_tm_get_main_packet_tx_error_count(msg);
- receiver_tm->main_tx_bitrate = mavlink_msg_receiver_tm_get_main_tx_bitrate(msg);
- receiver_tm->main_packet_rx_success_count = mavlink_msg_receiver_tm_get_main_packet_rx_success_count(msg);
- receiver_tm->main_packet_rx_drop_count = mavlink_msg_receiver_tm_get_main_packet_rx_drop_count(msg);
- receiver_tm->main_rx_bitrate = mavlink_msg_receiver_tm_get_main_rx_bitrate(msg);
- receiver_tm->payload_packet_tx_error_count = mavlink_msg_receiver_tm_get_payload_packet_tx_error_count(msg);
- receiver_tm->payload_tx_bitrate = mavlink_msg_receiver_tm_get_payload_tx_bitrate(msg);
- receiver_tm->payload_packet_rx_success_count = mavlink_msg_receiver_tm_get_payload_packet_rx_success_count(msg);
- receiver_tm->payload_packet_rx_drop_count = mavlink_msg_receiver_tm_get_payload_packet_rx_drop_count(msg);
- receiver_tm->payload_rx_bitrate = mavlink_msg_receiver_tm_get_payload_rx_bitrate(msg);
- receiver_tm->main_radio_present = mavlink_msg_receiver_tm_get_main_radio_present(msg);
- receiver_tm->payload_radio_present = mavlink_msg_receiver_tm_get_payload_radio_present(msg);
- receiver_tm->ethernet_present = mavlink_msg_receiver_tm_get_ethernet_present(msg);
- receiver_tm->ethernet_status = mavlink_msg_receiver_tm_get_ethernet_status(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_RECEIVER_TM_LEN? msg->len : MAVLINK_MSG_ID_RECEIVER_TM_LEN;
- memset(receiver_tm, 0, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
- memcpy(receiver_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_reset_servo_tc.h b/mavlink_lib/gemini/mavlink_msg_reset_servo_tc.h
deleted file mode 100644
index 3194a30241ddfb4d40efc96b727240c69f4842ac..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_reset_servo_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE RESET_SERVO_TC PACKING
-
-#define MAVLINK_MSG_ID_RESET_SERVO_TC 8
-
-
-typedef struct __mavlink_reset_servo_tc_t {
- uint8_t servo_id; /*< A member of the ServosList enum*/
-} mavlink_reset_servo_tc_t;
-
-#define MAVLINK_MSG_ID_RESET_SERVO_TC_LEN 1
-#define MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_8_LEN 1
-#define MAVLINK_MSG_ID_8_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_RESET_SERVO_TC_CRC 226
-#define MAVLINK_MSG_ID_8_CRC 226
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_RESET_SERVO_TC { \
- 8, \
- "RESET_SERVO_TC", \
- 1, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_reset_servo_tc_t, servo_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_RESET_SERVO_TC { \
- "RESET_SERVO_TC", \
- 1, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_reset_servo_tc_t, servo_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a reset_servo_tc 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 servo_id A member of the ServosList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_reset_servo_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RESET_SERVO_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN);
-#else
- mavlink_reset_servo_tc_t packet;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RESET_SERVO_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-}
-
-/**
- * @brief Pack a reset_servo_tc 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 servo_id A member of the ServosList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_reset_servo_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RESET_SERVO_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN);
-#else
- mavlink_reset_servo_tc_t packet;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RESET_SERVO_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-}
-
-/**
- * @brief Encode a reset_servo_tc 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 reset_servo_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_reset_servo_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_reset_servo_tc_t* reset_servo_tc)
-{
- return mavlink_msg_reset_servo_tc_pack(system_id, component_id, msg, reset_servo_tc->servo_id);
-}
-
-/**
- * @brief Encode a reset_servo_tc 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 reset_servo_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_reset_servo_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_reset_servo_tc_t* reset_servo_tc)
-{
- return mavlink_msg_reset_servo_tc_pack_chan(system_id, component_id, chan, msg, reset_servo_tc->servo_id);
-}
-
-/**
- * @brief Send a reset_servo_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param servo_id A member of the ServosList enum
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_reset_servo_tc_send(mavlink_channel_t chan, uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RESET_SERVO_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESET_SERVO_TC, buf, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-#else
- mavlink_reset_servo_tc_t packet;
- packet.servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESET_SERVO_TC, (const char *)&packet, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a reset_servo_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_reset_servo_tc_send_struct(mavlink_channel_t chan, const mavlink_reset_servo_tc_t* reset_servo_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_reset_servo_tc_send(chan, reset_servo_tc->servo_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESET_SERVO_TC, (const char *)reset_servo_tc, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_RESET_SERVO_TC_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_reset_servo_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESET_SERVO_TC, buf, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-#else
- mavlink_reset_servo_tc_t *packet = (mavlink_reset_servo_tc_t *)msgbuf;
- packet->servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESET_SERVO_TC, (const char *)packet, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE RESET_SERVO_TC UNPACKING
-
-
-/**
- * @brief Get field servo_id from reset_servo_tc message
- *
- * @return A member of the ServosList enum
- */
-static inline uint8_t mavlink_msg_reset_servo_tc_get_servo_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a reset_servo_tc message into a struct
- *
- * @param msg The message to decode
- * @param reset_servo_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_reset_servo_tc_decode(const mavlink_message_t* msg, mavlink_reset_servo_tc_t* reset_servo_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- reset_servo_tc->servo_id = mavlink_msg_reset_servo_tc_get_servo_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_RESET_SERVO_TC_LEN? msg->len : MAVLINK_MSG_ID_RESET_SERVO_TC_LEN;
- memset(reset_servo_tc, 0, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN);
- memcpy(reset_servo_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_rocket_flight_tm.h b/mavlink_lib/gemini/mavlink_msg_rocket_flight_tm.h
deleted file mode 100644
index e3949ca456e8719920b4822b1e08e708b2e51b26..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_rocket_flight_tm.h
+++ /dev/null
@@ -1,1488 +0,0 @@
-#pragma once
-// MESSAGE ROCKET_FLIGHT_TM PACKING
-
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM 208
-
-
-typedef struct __mavlink_rocket_flight_tm_t {
- uint64_t timestamp; /*< [us] Timestamp in microseconds*/
- float pressure_ada; /*< [Pa] Atmospheric pressure estimated by ADA*/
- float pressure_digi; /*< [Pa] Pressure from digital sensor*/
- float pressure_static; /*< [Pa] Pressure from static port*/
- float pressure_dpl; /*< [Pa] Pressure from deployment vane sensor*/
- float airspeed_pitot; /*< [m/s] Pitot airspeed*/
- float altitude_agl; /*< [m] Altitude above ground level*/
- float ada_vert_speed; /*< [m/s] Vertical speed estimated by ADA*/
- float mea_mass; /*< [kg] Mass estimated by MEA*/
- float acc_x; /*< [m/s^2] Acceleration on X axis (body)*/
- float acc_y; /*< [m/s^2] Acceleration on Y axis (body)*/
- float acc_z; /*< [m/s^2] Acceleration on Z axis (body)*/
- float gyro_x; /*< [rad/s] Angular speed on X axis (body)*/
- float gyro_y; /*< [rad/s] Angular speed on Y axis (body)*/
- float gyro_z; /*< [rad/s] Angular speed on Z axis (body)*/
- float mag_x; /*< [uT] Magnetic field on X axis (body)*/
- float mag_y; /*< [uT] Magnetic field on Y axis (body)*/
- float mag_z; /*< [uT] Magnetic field on Z axis (body)*/
- float gps_lat; /*< [deg] Latitude*/
- float gps_lon; /*< [deg] Longitude*/
- float gps_alt; /*< [m] GPS Altitude*/
- float abk_angle; /*< [deg] Air Brakes angle*/
- float nas_n; /*< [deg] Navigation system estimated noth position*/
- float nas_e; /*< [deg] Navigation system estimated east position*/
- float nas_d; /*< [m] Navigation system estimated down position*/
- float nas_vn; /*< [m/s] Navigation system estimated north velocity*/
- float nas_ve; /*< [m/s] Navigation system estimated east velocity*/
- float nas_vd; /*< [m/s] Navigation system estimated down velocity*/
- float nas_qx; /*< [deg] Navigation system estimated attitude (qx)*/
- float nas_qy; /*< [deg] Navigation system estimated attitude (qy)*/
- float nas_qz; /*< [deg] Navigation system estimated attitude (qz)*/
- float nas_qw; /*< [deg] Navigation system estimated attitude (qw)*/
- float nas_bias_x; /*< Navigation system gyroscope bias on x axis*/
- float nas_bias_y; /*< Navigation system gyroscope bias on y axis*/
- float nas_bias_z; /*< Navigation system gyroscope bias on z axis*/
- float pin_quick_connector; /*< Quick connector detach pin */
- float battery_voltage; /*< [V] Battery voltage*/
- float cam_battery_voltage; /*< [V] Camera battery voltage*/
- float current_consumption; /*< [A] Battery current*/
- float temperature; /*< [degC] Temperature*/
- uint8_t ada_state; /*< ADA Controller State*/
- uint8_t fmm_state; /*< Flight Mode Manager State*/
- uint8_t dpl_state; /*< Deployment Controller State*/
- uint8_t abk_state; /*< Airbrake FSM state*/
- uint8_t nas_state; /*< Navigation System FSM State*/
- uint8_t mea_state; /*< MEA Controller State*/
- uint8_t gps_fix; /*< GPS fix (1 = fix, 0 = no fix)*/
- uint8_t pin_launch; /*< Launch pin status (1 = connected, 0 = disconnected)*/
- uint8_t pin_nosecone; /*< Nosecone pin status (1 = connected, 0 = disconnected)*/
- uint8_t pin_expulsion; /*< Servo sensor status (1 = actuated, 0 = idle)*/
- uint8_t cutter_presence; /*< Cutter presence status (1 = present, 0 = missing)*/
- int8_t logger_error; /*< Logger error (0 = no error, -1 otherwise)*/
-} mavlink_rocket_flight_tm_t;
-
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN 176
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN 176
-#define MAVLINK_MSG_ID_208_LEN 176
-#define MAVLINK_MSG_ID_208_MIN_LEN 176
-
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC 214
-#define MAVLINK_MSG_ID_208_CRC 214
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM { \
- 208, \
- "ROCKET_FLIGHT_TM", \
- 52, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_flight_tm_t, timestamp) }, \
- { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_rocket_flight_tm_t, ada_state) }, \
- { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_rocket_flight_tm_t, fmm_state) }, \
- { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_rocket_flight_tm_t, dpl_state) }, \
- { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 167, offsetof(mavlink_rocket_flight_tm_t, abk_state) }, \
- { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 168, offsetof(mavlink_rocket_flight_tm_t, nas_state) }, \
- { "mea_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 169, offsetof(mavlink_rocket_flight_tm_t, mea_state) }, \
- { "pressure_ada", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_rocket_flight_tm_t, pressure_ada) }, \
- { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_rocket_flight_tm_t, pressure_digi) }, \
- { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_rocket_flight_tm_t, pressure_static) }, \
- { "pressure_dpl", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_rocket_flight_tm_t, pressure_dpl) }, \
- { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_rocket_flight_tm_t, airspeed_pitot) }, \
- { "altitude_agl", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_rocket_flight_tm_t, altitude_agl) }, \
- { "ada_vert_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_rocket_flight_tm_t, ada_vert_speed) }, \
- { "mea_mass", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_rocket_flight_tm_t, mea_mass) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_rocket_flight_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_rocket_flight_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_rocket_flight_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_rocket_flight_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_rocket_flight_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_rocket_flight_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_flight_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_flight_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_flight_tm_t, mag_z) }, \
- { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 170, offsetof(mavlink_rocket_flight_tm_t, gps_fix) }, \
- { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_flight_tm_t, gps_lat) }, \
- { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_flight_tm_t, gps_lon) }, \
- { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_flight_tm_t, gps_alt) }, \
- { "abk_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_rocket_flight_tm_t, abk_angle) }, \
- { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_rocket_flight_tm_t, nas_n) }, \
- { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_rocket_flight_tm_t, nas_e) }, \
- { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_rocket_flight_tm_t, nas_d) }, \
- { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_rocket_flight_tm_t, nas_vn) }, \
- { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_rocket_flight_tm_t, nas_ve) }, \
- { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_rocket_flight_tm_t, nas_vd) }, \
- { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_rocket_flight_tm_t, nas_qx) }, \
- { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_rocket_flight_tm_t, nas_qy) }, \
- { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_rocket_flight_tm_t, nas_qz) }, \
- { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_rocket_flight_tm_t, nas_qw) }, \
- { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_rocket_flight_tm_t, nas_bias_x) }, \
- { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_rocket_flight_tm_t, nas_bias_y) }, \
- { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_rocket_flight_tm_t, nas_bias_z) }, \
- { "pin_quick_connector", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_rocket_flight_tm_t, pin_quick_connector) }, \
- { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 171, offsetof(mavlink_rocket_flight_tm_t, pin_launch) }, \
- { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 172, offsetof(mavlink_rocket_flight_tm_t, pin_nosecone) }, \
- { "pin_expulsion", NULL, MAVLINK_TYPE_UINT8_T, 0, 173, offsetof(mavlink_rocket_flight_tm_t, pin_expulsion) }, \
- { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 174, offsetof(mavlink_rocket_flight_tm_t, cutter_presence) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, battery_voltage) }, \
- { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_rocket_flight_tm_t, cam_battery_voltage) }, \
- { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 156, offsetof(mavlink_rocket_flight_tm_t, current_consumption) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 160, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \
- { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 175, offsetof(mavlink_rocket_flight_tm_t, logger_error) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM { \
- "ROCKET_FLIGHT_TM", \
- 52, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_flight_tm_t, timestamp) }, \
- { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_rocket_flight_tm_t, ada_state) }, \
- { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_rocket_flight_tm_t, fmm_state) }, \
- { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_rocket_flight_tm_t, dpl_state) }, \
- { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 167, offsetof(mavlink_rocket_flight_tm_t, abk_state) }, \
- { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 168, offsetof(mavlink_rocket_flight_tm_t, nas_state) }, \
- { "mea_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 169, offsetof(mavlink_rocket_flight_tm_t, mea_state) }, \
- { "pressure_ada", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_rocket_flight_tm_t, pressure_ada) }, \
- { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_rocket_flight_tm_t, pressure_digi) }, \
- { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_rocket_flight_tm_t, pressure_static) }, \
- { "pressure_dpl", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_rocket_flight_tm_t, pressure_dpl) }, \
- { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_rocket_flight_tm_t, airspeed_pitot) }, \
- { "altitude_agl", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_rocket_flight_tm_t, altitude_agl) }, \
- { "ada_vert_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_rocket_flight_tm_t, ada_vert_speed) }, \
- { "mea_mass", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_rocket_flight_tm_t, mea_mass) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_rocket_flight_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_rocket_flight_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_rocket_flight_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_rocket_flight_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_rocket_flight_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_rocket_flight_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_flight_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_flight_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_flight_tm_t, mag_z) }, \
- { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 170, offsetof(mavlink_rocket_flight_tm_t, gps_fix) }, \
- { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_flight_tm_t, gps_lat) }, \
- { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_flight_tm_t, gps_lon) }, \
- { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_flight_tm_t, gps_alt) }, \
- { "abk_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_rocket_flight_tm_t, abk_angle) }, \
- { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_rocket_flight_tm_t, nas_n) }, \
- { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_rocket_flight_tm_t, nas_e) }, \
- { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_rocket_flight_tm_t, nas_d) }, \
- { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_rocket_flight_tm_t, nas_vn) }, \
- { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_rocket_flight_tm_t, nas_ve) }, \
- { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_rocket_flight_tm_t, nas_vd) }, \
- { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_rocket_flight_tm_t, nas_qx) }, \
- { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_rocket_flight_tm_t, nas_qy) }, \
- { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_rocket_flight_tm_t, nas_qz) }, \
- { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_rocket_flight_tm_t, nas_qw) }, \
- { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_rocket_flight_tm_t, nas_bias_x) }, \
- { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_rocket_flight_tm_t, nas_bias_y) }, \
- { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_rocket_flight_tm_t, nas_bias_z) }, \
- { "pin_quick_connector", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_rocket_flight_tm_t, pin_quick_connector) }, \
- { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 171, offsetof(mavlink_rocket_flight_tm_t, pin_launch) }, \
- { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 172, offsetof(mavlink_rocket_flight_tm_t, pin_nosecone) }, \
- { "pin_expulsion", NULL, MAVLINK_TYPE_UINT8_T, 0, 173, offsetof(mavlink_rocket_flight_tm_t, pin_expulsion) }, \
- { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 174, offsetof(mavlink_rocket_flight_tm_t, cutter_presence) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, battery_voltage) }, \
- { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_rocket_flight_tm_t, cam_battery_voltage) }, \
- { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 156, offsetof(mavlink_rocket_flight_tm_t, current_consumption) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 160, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \
- { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 175, offsetof(mavlink_rocket_flight_tm_t, logger_error) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a rocket_flight_tm 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 in microseconds
- * @param ada_state ADA Controller State
- * @param fmm_state Flight Mode Manager State
- * @param dpl_state Deployment Controller State
- * @param abk_state Airbrake FSM state
- * @param nas_state Navigation System FSM State
- * @param mea_state MEA Controller State
- * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane sensor
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param altitude_agl [m] Altitude above ground level
- * @param ada_vert_speed [m/s] Vertical speed estimated by ADA
- * @param mea_mass [kg] Mass estimated by MEA
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param abk_angle [deg] Air Brakes angle
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on y axis
- * @param nas_bias_z Navigation system gyroscope bias on z axis
- * @param pin_quick_connector Quick connector detach pin
- * @param pin_launch Launch pin status (1 = connected, 0 = disconnected)
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param pin_expulsion Servo sensor status (1 = actuated, 0 = idle)
- * @param cutter_presence Cutter presence status (1 = present, 0 = missing)
- * @param battery_voltage [V] Battery voltage
- * @param cam_battery_voltage [V] Camera battery voltage
- * @param current_consumption [A] Battery current
- * @param temperature [degC] Temperature
- * @param logger_error Logger error (0 = no error, -1 otherwise)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float pin_quick_connector, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float current_consumption, float temperature, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_ada);
- _mav_put_float(buf, 12, pressure_digi);
- _mav_put_float(buf, 16, pressure_static);
- _mav_put_float(buf, 20, pressure_dpl);
- _mav_put_float(buf, 24, airspeed_pitot);
- _mav_put_float(buf, 28, altitude_agl);
- _mav_put_float(buf, 32, ada_vert_speed);
- _mav_put_float(buf, 36, mea_mass);
- _mav_put_float(buf, 40, acc_x);
- _mav_put_float(buf, 44, acc_y);
- _mav_put_float(buf, 48, acc_z);
- _mav_put_float(buf, 52, gyro_x);
- _mav_put_float(buf, 56, gyro_y);
- _mav_put_float(buf, 60, gyro_z);
- _mav_put_float(buf, 64, mag_x);
- _mav_put_float(buf, 68, mag_y);
- _mav_put_float(buf, 72, mag_z);
- _mav_put_float(buf, 76, gps_lat);
- _mav_put_float(buf, 80, gps_lon);
- _mav_put_float(buf, 84, gps_alt);
- _mav_put_float(buf, 88, abk_angle);
- _mav_put_float(buf, 92, nas_n);
- _mav_put_float(buf, 96, nas_e);
- _mav_put_float(buf, 100, nas_d);
- _mav_put_float(buf, 104, nas_vn);
- _mav_put_float(buf, 108, nas_ve);
- _mav_put_float(buf, 112, nas_vd);
- _mav_put_float(buf, 116, nas_qx);
- _mav_put_float(buf, 120, nas_qy);
- _mav_put_float(buf, 124, nas_qz);
- _mav_put_float(buf, 128, nas_qw);
- _mav_put_float(buf, 132, nas_bias_x);
- _mav_put_float(buf, 136, nas_bias_y);
- _mav_put_float(buf, 140, nas_bias_z);
- _mav_put_float(buf, 144, pin_quick_connector);
- _mav_put_float(buf, 148, battery_voltage);
- _mav_put_float(buf, 152, cam_battery_voltage);
- _mav_put_float(buf, 156, current_consumption);
- _mav_put_float(buf, 160, temperature);
- _mav_put_uint8_t(buf, 164, ada_state);
- _mav_put_uint8_t(buf, 165, fmm_state);
- _mav_put_uint8_t(buf, 166, dpl_state);
- _mav_put_uint8_t(buf, 167, abk_state);
- _mav_put_uint8_t(buf, 168, nas_state);
- _mav_put_uint8_t(buf, 169, mea_state);
- _mav_put_uint8_t(buf, 170, gps_fix);
- _mav_put_uint8_t(buf, 171, pin_launch);
- _mav_put_uint8_t(buf, 172, pin_nosecone);
- _mav_put_uint8_t(buf, 173, pin_expulsion);
- _mav_put_uint8_t(buf, 174, cutter_presence);
- _mav_put_int8_t(buf, 175, logger_error);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
-#else
- mavlink_rocket_flight_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_ada = pressure_ada;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.pressure_dpl = pressure_dpl;
- packet.airspeed_pitot = airspeed_pitot;
- packet.altitude_agl = altitude_agl;
- packet.ada_vert_speed = ada_vert_speed;
- packet.mea_mass = mea_mass;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.abk_angle = abk_angle;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.pin_quick_connector = pin_quick_connector;
- packet.battery_voltage = battery_voltage;
- packet.cam_battery_voltage = cam_battery_voltage;
- packet.current_consumption = current_consumption;
- packet.temperature = temperature;
- packet.ada_state = ada_state;
- packet.fmm_state = fmm_state;
- packet.dpl_state = dpl_state;
- packet.abk_state = abk_state;
- packet.nas_state = nas_state;
- packet.mea_state = mea_state;
- packet.gps_fix = gps_fix;
- packet.pin_launch = pin_launch;
- packet.pin_nosecone = pin_nosecone;
- packet.pin_expulsion = pin_expulsion;
- packet.cutter_presence = cutter_presence;
- packet.logger_error = logger_error;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ROCKET_FLIGHT_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-}
-
-/**
- * @brief Pack a rocket_flight_tm 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 in microseconds
- * @param ada_state ADA Controller State
- * @param fmm_state Flight Mode Manager State
- * @param dpl_state Deployment Controller State
- * @param abk_state Airbrake FSM state
- * @param nas_state Navigation System FSM State
- * @param mea_state MEA Controller State
- * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane sensor
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param altitude_agl [m] Altitude above ground level
- * @param ada_vert_speed [m/s] Vertical speed estimated by ADA
- * @param mea_mass [kg] Mass estimated by MEA
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param abk_angle [deg] Air Brakes angle
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on y axis
- * @param nas_bias_z Navigation system gyroscope bias on z axis
- * @param pin_quick_connector Quick connector detach pin
- * @param pin_launch Launch pin status (1 = connected, 0 = disconnected)
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param pin_expulsion Servo sensor status (1 = actuated, 0 = idle)
- * @param cutter_presence Cutter presence status (1 = present, 0 = missing)
- * @param battery_voltage [V] Battery voltage
- * @param cam_battery_voltage [V] Camera battery voltage
- * @param current_consumption [A] Battery current
- * @param temperature [degC] Temperature
- * @param logger_error Logger error (0 = no error, -1 otherwise)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t ada_state,uint8_t fmm_state,uint8_t dpl_state,uint8_t abk_state,uint8_t nas_state,uint8_t mea_state,float pressure_ada,float pressure_digi,float pressure_static,float pressure_dpl,float airspeed_pitot,float altitude_agl,float ada_vert_speed,float mea_mass,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float abk_angle,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,float pin_quick_connector,uint8_t pin_launch,uint8_t pin_nosecone,uint8_t pin_expulsion,uint8_t cutter_presence,float battery_voltage,float cam_battery_voltage,float current_consumption,float temperature,int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_ada);
- _mav_put_float(buf, 12, pressure_digi);
- _mav_put_float(buf, 16, pressure_static);
- _mav_put_float(buf, 20, pressure_dpl);
- _mav_put_float(buf, 24, airspeed_pitot);
- _mav_put_float(buf, 28, altitude_agl);
- _mav_put_float(buf, 32, ada_vert_speed);
- _mav_put_float(buf, 36, mea_mass);
- _mav_put_float(buf, 40, acc_x);
- _mav_put_float(buf, 44, acc_y);
- _mav_put_float(buf, 48, acc_z);
- _mav_put_float(buf, 52, gyro_x);
- _mav_put_float(buf, 56, gyro_y);
- _mav_put_float(buf, 60, gyro_z);
- _mav_put_float(buf, 64, mag_x);
- _mav_put_float(buf, 68, mag_y);
- _mav_put_float(buf, 72, mag_z);
- _mav_put_float(buf, 76, gps_lat);
- _mav_put_float(buf, 80, gps_lon);
- _mav_put_float(buf, 84, gps_alt);
- _mav_put_float(buf, 88, abk_angle);
- _mav_put_float(buf, 92, nas_n);
- _mav_put_float(buf, 96, nas_e);
- _mav_put_float(buf, 100, nas_d);
- _mav_put_float(buf, 104, nas_vn);
- _mav_put_float(buf, 108, nas_ve);
- _mav_put_float(buf, 112, nas_vd);
- _mav_put_float(buf, 116, nas_qx);
- _mav_put_float(buf, 120, nas_qy);
- _mav_put_float(buf, 124, nas_qz);
- _mav_put_float(buf, 128, nas_qw);
- _mav_put_float(buf, 132, nas_bias_x);
- _mav_put_float(buf, 136, nas_bias_y);
- _mav_put_float(buf, 140, nas_bias_z);
- _mav_put_float(buf, 144, pin_quick_connector);
- _mav_put_float(buf, 148, battery_voltage);
- _mav_put_float(buf, 152, cam_battery_voltage);
- _mav_put_float(buf, 156, current_consumption);
- _mav_put_float(buf, 160, temperature);
- _mav_put_uint8_t(buf, 164, ada_state);
- _mav_put_uint8_t(buf, 165, fmm_state);
- _mav_put_uint8_t(buf, 166, dpl_state);
- _mav_put_uint8_t(buf, 167, abk_state);
- _mav_put_uint8_t(buf, 168, nas_state);
- _mav_put_uint8_t(buf, 169, mea_state);
- _mav_put_uint8_t(buf, 170, gps_fix);
- _mav_put_uint8_t(buf, 171, pin_launch);
- _mav_put_uint8_t(buf, 172, pin_nosecone);
- _mav_put_uint8_t(buf, 173, pin_expulsion);
- _mav_put_uint8_t(buf, 174, cutter_presence);
- _mav_put_int8_t(buf, 175, logger_error);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
-#else
- mavlink_rocket_flight_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_ada = pressure_ada;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.pressure_dpl = pressure_dpl;
- packet.airspeed_pitot = airspeed_pitot;
- packet.altitude_agl = altitude_agl;
- packet.ada_vert_speed = ada_vert_speed;
- packet.mea_mass = mea_mass;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.abk_angle = abk_angle;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.pin_quick_connector = pin_quick_connector;
- packet.battery_voltage = battery_voltage;
- packet.cam_battery_voltage = cam_battery_voltage;
- packet.current_consumption = current_consumption;
- packet.temperature = temperature;
- packet.ada_state = ada_state;
- packet.fmm_state = fmm_state;
- packet.dpl_state = dpl_state;
- packet.abk_state = abk_state;
- packet.nas_state = nas_state;
- packet.mea_state = mea_state;
- packet.gps_fix = gps_fix;
- packet.pin_launch = pin_launch;
- packet.pin_nosecone = pin_nosecone;
- packet.pin_expulsion = pin_expulsion;
- packet.cutter_presence = cutter_presence;
- packet.logger_error = logger_error;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ROCKET_FLIGHT_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-}
-
-/**
- * @brief Encode a rocket_flight_tm 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 rocket_flight_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_rocket_flight_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rocket_flight_tm_t* rocket_flight_tm)
-{
- return mavlink_msg_rocket_flight_tm_pack(system_id, component_id, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_quick_connector, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->cam_battery_voltage, rocket_flight_tm->current_consumption, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
-}
-
-/**
- * @brief Encode a rocket_flight_tm 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 rocket_flight_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_rocket_flight_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rocket_flight_tm_t* rocket_flight_tm)
-{
- return mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, chan, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_quick_connector, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->cam_battery_voltage, rocket_flight_tm->current_consumption, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
-}
-
-/**
- * @brief Send a rocket_flight_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp in microseconds
- * @param ada_state ADA Controller State
- * @param fmm_state Flight Mode Manager State
- * @param dpl_state Deployment Controller State
- * @param abk_state Airbrake FSM state
- * @param nas_state Navigation System FSM State
- * @param mea_state MEA Controller State
- * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane sensor
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param altitude_agl [m] Altitude above ground level
- * @param ada_vert_speed [m/s] Vertical speed estimated by ADA
- * @param mea_mass [kg] Mass estimated by MEA
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param abk_angle [deg] Air Brakes angle
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on y axis
- * @param nas_bias_z Navigation system gyroscope bias on z axis
- * @param pin_quick_connector Quick connector detach pin
- * @param pin_launch Launch pin status (1 = connected, 0 = disconnected)
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param pin_expulsion Servo sensor status (1 = actuated, 0 = idle)
- * @param cutter_presence Cutter presence status (1 = present, 0 = missing)
- * @param battery_voltage [V] Battery voltage
- * @param cam_battery_voltage [V] Camera battery voltage
- * @param current_consumption [A] Battery current
- * @param temperature [degC] Temperature
- * @param logger_error Logger error (0 = no error, -1 otherwise)
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float pin_quick_connector, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float current_consumption, float temperature, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_ada);
- _mav_put_float(buf, 12, pressure_digi);
- _mav_put_float(buf, 16, pressure_static);
- _mav_put_float(buf, 20, pressure_dpl);
- _mav_put_float(buf, 24, airspeed_pitot);
- _mav_put_float(buf, 28, altitude_agl);
- _mav_put_float(buf, 32, ada_vert_speed);
- _mav_put_float(buf, 36, mea_mass);
- _mav_put_float(buf, 40, acc_x);
- _mav_put_float(buf, 44, acc_y);
- _mav_put_float(buf, 48, acc_z);
- _mav_put_float(buf, 52, gyro_x);
- _mav_put_float(buf, 56, gyro_y);
- _mav_put_float(buf, 60, gyro_z);
- _mav_put_float(buf, 64, mag_x);
- _mav_put_float(buf, 68, mag_y);
- _mav_put_float(buf, 72, mag_z);
- _mav_put_float(buf, 76, gps_lat);
- _mav_put_float(buf, 80, gps_lon);
- _mav_put_float(buf, 84, gps_alt);
- _mav_put_float(buf, 88, abk_angle);
- _mav_put_float(buf, 92, nas_n);
- _mav_put_float(buf, 96, nas_e);
- _mav_put_float(buf, 100, nas_d);
- _mav_put_float(buf, 104, nas_vn);
- _mav_put_float(buf, 108, nas_ve);
- _mav_put_float(buf, 112, nas_vd);
- _mav_put_float(buf, 116, nas_qx);
- _mav_put_float(buf, 120, nas_qy);
- _mav_put_float(buf, 124, nas_qz);
- _mav_put_float(buf, 128, nas_qw);
- _mav_put_float(buf, 132, nas_bias_x);
- _mav_put_float(buf, 136, nas_bias_y);
- _mav_put_float(buf, 140, nas_bias_z);
- _mav_put_float(buf, 144, pin_quick_connector);
- _mav_put_float(buf, 148, battery_voltage);
- _mav_put_float(buf, 152, cam_battery_voltage);
- _mav_put_float(buf, 156, current_consumption);
- _mav_put_float(buf, 160, temperature);
- _mav_put_uint8_t(buf, 164, ada_state);
- _mav_put_uint8_t(buf, 165, fmm_state);
- _mav_put_uint8_t(buf, 166, dpl_state);
- _mav_put_uint8_t(buf, 167, abk_state);
- _mav_put_uint8_t(buf, 168, nas_state);
- _mav_put_uint8_t(buf, 169, mea_state);
- _mav_put_uint8_t(buf, 170, gps_fix);
- _mav_put_uint8_t(buf, 171, pin_launch);
- _mav_put_uint8_t(buf, 172, pin_nosecone);
- _mav_put_uint8_t(buf, 173, pin_expulsion);
- _mav_put_uint8_t(buf, 174, cutter_presence);
- _mav_put_int8_t(buf, 175, logger_error);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-#else
- mavlink_rocket_flight_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_ada = pressure_ada;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.pressure_dpl = pressure_dpl;
- packet.airspeed_pitot = airspeed_pitot;
- packet.altitude_agl = altitude_agl;
- packet.ada_vert_speed = ada_vert_speed;
- packet.mea_mass = mea_mass;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.abk_angle = abk_angle;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.pin_quick_connector = pin_quick_connector;
- packet.battery_voltage = battery_voltage;
- packet.cam_battery_voltage = cam_battery_voltage;
- packet.current_consumption = current_consumption;
- packet.temperature = temperature;
- packet.ada_state = ada_state;
- packet.fmm_state = fmm_state;
- packet.dpl_state = dpl_state;
- packet.abk_state = abk_state;
- packet.nas_state = nas_state;
- packet.mea_state = mea_state;
- packet.gps_fix = gps_fix;
- packet.pin_launch = pin_launch;
- packet.pin_nosecone = pin_nosecone;
- packet.pin_expulsion = pin_expulsion;
- packet.cutter_presence = cutter_presence;
- packet.logger_error = logger_error;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, (const char *)&packet, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a rocket_flight_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_rocket_flight_tm_send_struct(mavlink_channel_t chan, const mavlink_rocket_flight_tm_t* rocket_flight_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_rocket_flight_tm_send(chan, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_quick_connector, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->cam_battery_voltage, rocket_flight_tm->current_consumption, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, (const char *)rocket_flight_tm, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_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_rocket_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float pin_quick_connector, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float current_consumption, float temperature, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_ada);
- _mav_put_float(buf, 12, pressure_digi);
- _mav_put_float(buf, 16, pressure_static);
- _mav_put_float(buf, 20, pressure_dpl);
- _mav_put_float(buf, 24, airspeed_pitot);
- _mav_put_float(buf, 28, altitude_agl);
- _mav_put_float(buf, 32, ada_vert_speed);
- _mav_put_float(buf, 36, mea_mass);
- _mav_put_float(buf, 40, acc_x);
- _mav_put_float(buf, 44, acc_y);
- _mav_put_float(buf, 48, acc_z);
- _mav_put_float(buf, 52, gyro_x);
- _mav_put_float(buf, 56, gyro_y);
- _mav_put_float(buf, 60, gyro_z);
- _mav_put_float(buf, 64, mag_x);
- _mav_put_float(buf, 68, mag_y);
- _mav_put_float(buf, 72, mag_z);
- _mav_put_float(buf, 76, gps_lat);
- _mav_put_float(buf, 80, gps_lon);
- _mav_put_float(buf, 84, gps_alt);
- _mav_put_float(buf, 88, abk_angle);
- _mav_put_float(buf, 92, nas_n);
- _mav_put_float(buf, 96, nas_e);
- _mav_put_float(buf, 100, nas_d);
- _mav_put_float(buf, 104, nas_vn);
- _mav_put_float(buf, 108, nas_ve);
- _mav_put_float(buf, 112, nas_vd);
- _mav_put_float(buf, 116, nas_qx);
- _mav_put_float(buf, 120, nas_qy);
- _mav_put_float(buf, 124, nas_qz);
- _mav_put_float(buf, 128, nas_qw);
- _mav_put_float(buf, 132, nas_bias_x);
- _mav_put_float(buf, 136, nas_bias_y);
- _mav_put_float(buf, 140, nas_bias_z);
- _mav_put_float(buf, 144, pin_quick_connector);
- _mav_put_float(buf, 148, battery_voltage);
- _mav_put_float(buf, 152, cam_battery_voltage);
- _mav_put_float(buf, 156, current_consumption);
- _mav_put_float(buf, 160, temperature);
- _mav_put_uint8_t(buf, 164, ada_state);
- _mav_put_uint8_t(buf, 165, fmm_state);
- _mav_put_uint8_t(buf, 166, dpl_state);
- _mav_put_uint8_t(buf, 167, abk_state);
- _mav_put_uint8_t(buf, 168, nas_state);
- _mav_put_uint8_t(buf, 169, mea_state);
- _mav_put_uint8_t(buf, 170, gps_fix);
- _mav_put_uint8_t(buf, 171, pin_launch);
- _mav_put_uint8_t(buf, 172, pin_nosecone);
- _mav_put_uint8_t(buf, 173, pin_expulsion);
- _mav_put_uint8_t(buf, 174, cutter_presence);
- _mav_put_int8_t(buf, 175, logger_error);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-#else
- mavlink_rocket_flight_tm_t *packet = (mavlink_rocket_flight_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->pressure_ada = pressure_ada;
- packet->pressure_digi = pressure_digi;
- packet->pressure_static = pressure_static;
- packet->pressure_dpl = pressure_dpl;
- packet->airspeed_pitot = airspeed_pitot;
- packet->altitude_agl = altitude_agl;
- packet->ada_vert_speed = ada_vert_speed;
- packet->mea_mass = mea_mass;
- packet->acc_x = acc_x;
- packet->acc_y = acc_y;
- packet->acc_z = acc_z;
- packet->gyro_x = gyro_x;
- packet->gyro_y = gyro_y;
- packet->gyro_z = gyro_z;
- packet->mag_x = mag_x;
- packet->mag_y = mag_y;
- packet->mag_z = mag_z;
- packet->gps_lat = gps_lat;
- packet->gps_lon = gps_lon;
- packet->gps_alt = gps_alt;
- packet->abk_angle = abk_angle;
- packet->nas_n = nas_n;
- packet->nas_e = nas_e;
- packet->nas_d = nas_d;
- packet->nas_vn = nas_vn;
- packet->nas_ve = nas_ve;
- packet->nas_vd = nas_vd;
- packet->nas_qx = nas_qx;
- packet->nas_qy = nas_qy;
- packet->nas_qz = nas_qz;
- packet->nas_qw = nas_qw;
- packet->nas_bias_x = nas_bias_x;
- packet->nas_bias_y = nas_bias_y;
- packet->nas_bias_z = nas_bias_z;
- packet->pin_quick_connector = pin_quick_connector;
- packet->battery_voltage = battery_voltage;
- packet->cam_battery_voltage = cam_battery_voltage;
- packet->current_consumption = current_consumption;
- packet->temperature = temperature;
- packet->ada_state = ada_state;
- packet->fmm_state = fmm_state;
- packet->dpl_state = dpl_state;
- packet->abk_state = abk_state;
- packet->nas_state = nas_state;
- packet->mea_state = mea_state;
- packet->gps_fix = gps_fix;
- packet->pin_launch = pin_launch;
- packet->pin_nosecone = pin_nosecone;
- packet->pin_expulsion = pin_expulsion;
- packet->cutter_presence = cutter_presence;
- packet->logger_error = logger_error;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, (const char *)packet, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ROCKET_FLIGHT_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from rocket_flight_tm message
- *
- * @return [us] Timestamp in microseconds
- */
-static inline uint64_t mavlink_msg_rocket_flight_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field ada_state from rocket_flight_tm message
- *
- * @return ADA Controller State
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_ada_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 164);
-}
-
-/**
- * @brief Get field fmm_state from rocket_flight_tm message
- *
- * @return Flight Mode Manager State
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_fmm_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 165);
-}
-
-/**
- * @brief Get field dpl_state from rocket_flight_tm message
- *
- * @return Deployment Controller State
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_dpl_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 166);
-}
-
-/**
- * @brief Get field abk_state from rocket_flight_tm message
- *
- * @return Airbrake FSM state
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_abk_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 167);
-}
-
-/**
- * @brief Get field nas_state from rocket_flight_tm message
- *
- * @return Navigation System FSM State
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_nas_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 168);
-}
-
-/**
- * @brief Get field mea_state from rocket_flight_tm message
- *
- * @return MEA Controller State
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_mea_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 169);
-}
-
-/**
- * @brief Get field pressure_ada from rocket_flight_tm message
- *
- * @return [Pa] Atmospheric pressure estimated by ADA
- */
-static inline float mavlink_msg_rocket_flight_tm_get_pressure_ada(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field pressure_digi from rocket_flight_tm message
- *
- * @return [Pa] Pressure from digital sensor
- */
-static inline float mavlink_msg_rocket_flight_tm_get_pressure_digi(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field pressure_static from rocket_flight_tm message
- *
- * @return [Pa] Pressure from static port
- */
-static inline float mavlink_msg_rocket_flight_tm_get_pressure_static(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field pressure_dpl from rocket_flight_tm message
- *
- * @return [Pa] Pressure from deployment vane sensor
- */
-static inline float mavlink_msg_rocket_flight_tm_get_pressure_dpl(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field airspeed_pitot from rocket_flight_tm message
- *
- * @return [m/s] Pitot airspeed
- */
-static inline float mavlink_msg_rocket_flight_tm_get_airspeed_pitot(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field altitude_agl from rocket_flight_tm message
- *
- * @return [m] Altitude above ground level
- */
-static inline float mavlink_msg_rocket_flight_tm_get_altitude_agl(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field ada_vert_speed from rocket_flight_tm message
- *
- * @return [m/s] Vertical speed estimated by ADA
- */
-static inline float mavlink_msg_rocket_flight_tm_get_ada_vert_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field mea_mass from rocket_flight_tm message
- *
- * @return [kg] Mass estimated by MEA
- */
-static inline float mavlink_msg_rocket_flight_tm_get_mea_mass(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field acc_x from rocket_flight_tm message
- *
- * @return [m/s^2] Acceleration on X axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_acc_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field acc_y from rocket_flight_tm message
- *
- * @return [m/s^2] Acceleration on Y axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_acc_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field acc_z from rocket_flight_tm message
- *
- * @return [m/s^2] Acceleration on Z axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_acc_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field gyro_x from rocket_flight_tm message
- *
- * @return [rad/s] Angular speed on X axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_gyro_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field gyro_y from rocket_flight_tm message
- *
- * @return [rad/s] Angular speed on Y axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_gyro_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field gyro_z from rocket_flight_tm message
- *
- * @return [rad/s] Angular speed on Z axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_gyro_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field mag_x from rocket_flight_tm message
- *
- * @return [uT] Magnetic field on X axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_mag_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field mag_y from rocket_flight_tm message
- *
- * @return [uT] Magnetic field on Y axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_mag_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field mag_z from rocket_flight_tm message
- *
- * @return [uT] Magnetic field on Z axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_mag_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 72);
-}
-
-/**
- * @brief Get field gps_fix from rocket_flight_tm message
- *
- * @return GPS fix (1 = fix, 0 = no fix)
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_gps_fix(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 170);
-}
-
-/**
- * @brief Get field gps_lat from rocket_flight_tm message
- *
- * @return [deg] Latitude
- */
-static inline float mavlink_msg_rocket_flight_tm_get_gps_lat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 76);
-}
-
-/**
- * @brief Get field gps_lon from rocket_flight_tm message
- *
- * @return [deg] Longitude
- */
-static inline float mavlink_msg_rocket_flight_tm_get_gps_lon(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 80);
-}
-
-/**
- * @brief Get field gps_alt from rocket_flight_tm message
- *
- * @return [m] GPS Altitude
- */
-static inline float mavlink_msg_rocket_flight_tm_get_gps_alt(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 84);
-}
-
-/**
- * @brief Get field abk_angle from rocket_flight_tm message
- *
- * @return [deg] Air Brakes angle
- */
-static inline float mavlink_msg_rocket_flight_tm_get_abk_angle(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 88);
-}
-
-/**
- * @brief Get field nas_n from rocket_flight_tm message
- *
- * @return [deg] Navigation system estimated noth position
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_n(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 92);
-}
-
-/**
- * @brief Get field nas_e from rocket_flight_tm message
- *
- * @return [deg] Navigation system estimated east position
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_e(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 96);
-}
-
-/**
- * @brief Get field nas_d from rocket_flight_tm message
- *
- * @return [m] Navigation system estimated down position
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_d(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 100);
-}
-
-/**
- * @brief Get field nas_vn from rocket_flight_tm message
- *
- * @return [m/s] Navigation system estimated north velocity
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_vn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 104);
-}
-
-/**
- * @brief Get field nas_ve from rocket_flight_tm message
- *
- * @return [m/s] Navigation system estimated east velocity
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_ve(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 108);
-}
-
-/**
- * @brief Get field nas_vd from rocket_flight_tm message
- *
- * @return [m/s] Navigation system estimated down velocity
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_vd(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 112);
-}
-
-/**
- * @brief Get field nas_qx from rocket_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qx)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_qx(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 116);
-}
-
-/**
- * @brief Get field nas_qy from rocket_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qy)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_qy(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 120);
-}
-
-/**
- * @brief Get field nas_qz from rocket_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qz)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_qz(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 124);
-}
-
-/**
- * @brief Get field nas_qw from rocket_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qw)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_qw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 128);
-}
-
-/**
- * @brief Get field nas_bias_x from rocket_flight_tm message
- *
- * @return Navigation system gyroscope bias on x axis
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 132);
-}
-
-/**
- * @brief Get field nas_bias_y from rocket_flight_tm message
- *
- * @return Navigation system gyroscope bias on y axis
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 136);
-}
-
-/**
- * @brief Get field nas_bias_z from rocket_flight_tm message
- *
- * @return Navigation system gyroscope bias on z axis
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 140);
-}
-
-/**
- * @brief Get field pin_quick_connector from rocket_flight_tm message
- *
- * @return Quick connector detach pin
- */
-static inline float mavlink_msg_rocket_flight_tm_get_pin_quick_connector(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 144);
-}
-
-/**
- * @brief Get field pin_launch from rocket_flight_tm message
- *
- * @return Launch pin status (1 = connected, 0 = disconnected)
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_launch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 171);
-}
-
-/**
- * @brief Get field pin_nosecone from rocket_flight_tm message
- *
- * @return Nosecone pin status (1 = connected, 0 = disconnected)
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_nosecone(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 172);
-}
-
-/**
- * @brief Get field pin_expulsion from rocket_flight_tm message
- *
- * @return Servo sensor status (1 = actuated, 0 = idle)
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_expulsion(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 173);
-}
-
-/**
- * @brief Get field cutter_presence from rocket_flight_tm message
- *
- * @return Cutter presence status (1 = present, 0 = missing)
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_cutter_presence(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 174);
-}
-
-/**
- * @brief Get field battery_voltage from rocket_flight_tm message
- *
- * @return [V] Battery voltage
- */
-static inline float mavlink_msg_rocket_flight_tm_get_battery_voltage(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 148);
-}
-
-/**
- * @brief Get field cam_battery_voltage from rocket_flight_tm message
- *
- * @return [V] Camera battery voltage
- */
-static inline float mavlink_msg_rocket_flight_tm_get_cam_battery_voltage(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 152);
-}
-
-/**
- * @brief Get field current_consumption from rocket_flight_tm message
- *
- * @return [A] Battery current
- */
-static inline float mavlink_msg_rocket_flight_tm_get_current_consumption(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 156);
-}
-
-/**
- * @brief Get field temperature from rocket_flight_tm message
- *
- * @return [degC] Temperature
- */
-static inline float mavlink_msg_rocket_flight_tm_get_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 160);
-}
-
-/**
- * @brief Get field logger_error from rocket_flight_tm message
- *
- * @return Logger error (0 = no error, -1 otherwise)
- */
-static inline int8_t mavlink_msg_rocket_flight_tm_get_logger_error(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int8_t(msg, 175);
-}
-
-/**
- * @brief Decode a rocket_flight_tm message into a struct
- *
- * @param msg The message to decode
- * @param rocket_flight_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_rocket_flight_tm_decode(const mavlink_message_t* msg, mavlink_rocket_flight_tm_t* rocket_flight_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- rocket_flight_tm->timestamp = mavlink_msg_rocket_flight_tm_get_timestamp(msg);
- rocket_flight_tm->pressure_ada = mavlink_msg_rocket_flight_tm_get_pressure_ada(msg);
- rocket_flight_tm->pressure_digi = mavlink_msg_rocket_flight_tm_get_pressure_digi(msg);
- rocket_flight_tm->pressure_static = mavlink_msg_rocket_flight_tm_get_pressure_static(msg);
- rocket_flight_tm->pressure_dpl = mavlink_msg_rocket_flight_tm_get_pressure_dpl(msg);
- rocket_flight_tm->airspeed_pitot = mavlink_msg_rocket_flight_tm_get_airspeed_pitot(msg);
- rocket_flight_tm->altitude_agl = mavlink_msg_rocket_flight_tm_get_altitude_agl(msg);
- rocket_flight_tm->ada_vert_speed = mavlink_msg_rocket_flight_tm_get_ada_vert_speed(msg);
- rocket_flight_tm->mea_mass = mavlink_msg_rocket_flight_tm_get_mea_mass(msg);
- rocket_flight_tm->acc_x = mavlink_msg_rocket_flight_tm_get_acc_x(msg);
- rocket_flight_tm->acc_y = mavlink_msg_rocket_flight_tm_get_acc_y(msg);
- rocket_flight_tm->acc_z = mavlink_msg_rocket_flight_tm_get_acc_z(msg);
- rocket_flight_tm->gyro_x = mavlink_msg_rocket_flight_tm_get_gyro_x(msg);
- rocket_flight_tm->gyro_y = mavlink_msg_rocket_flight_tm_get_gyro_y(msg);
- rocket_flight_tm->gyro_z = mavlink_msg_rocket_flight_tm_get_gyro_z(msg);
- rocket_flight_tm->mag_x = mavlink_msg_rocket_flight_tm_get_mag_x(msg);
- rocket_flight_tm->mag_y = mavlink_msg_rocket_flight_tm_get_mag_y(msg);
- rocket_flight_tm->mag_z = mavlink_msg_rocket_flight_tm_get_mag_z(msg);
- rocket_flight_tm->gps_lat = mavlink_msg_rocket_flight_tm_get_gps_lat(msg);
- rocket_flight_tm->gps_lon = mavlink_msg_rocket_flight_tm_get_gps_lon(msg);
- rocket_flight_tm->gps_alt = mavlink_msg_rocket_flight_tm_get_gps_alt(msg);
- rocket_flight_tm->abk_angle = mavlink_msg_rocket_flight_tm_get_abk_angle(msg);
- rocket_flight_tm->nas_n = mavlink_msg_rocket_flight_tm_get_nas_n(msg);
- rocket_flight_tm->nas_e = mavlink_msg_rocket_flight_tm_get_nas_e(msg);
- rocket_flight_tm->nas_d = mavlink_msg_rocket_flight_tm_get_nas_d(msg);
- rocket_flight_tm->nas_vn = mavlink_msg_rocket_flight_tm_get_nas_vn(msg);
- rocket_flight_tm->nas_ve = mavlink_msg_rocket_flight_tm_get_nas_ve(msg);
- rocket_flight_tm->nas_vd = mavlink_msg_rocket_flight_tm_get_nas_vd(msg);
- rocket_flight_tm->nas_qx = mavlink_msg_rocket_flight_tm_get_nas_qx(msg);
- rocket_flight_tm->nas_qy = mavlink_msg_rocket_flight_tm_get_nas_qy(msg);
- rocket_flight_tm->nas_qz = mavlink_msg_rocket_flight_tm_get_nas_qz(msg);
- rocket_flight_tm->nas_qw = mavlink_msg_rocket_flight_tm_get_nas_qw(msg);
- rocket_flight_tm->nas_bias_x = mavlink_msg_rocket_flight_tm_get_nas_bias_x(msg);
- rocket_flight_tm->nas_bias_y = mavlink_msg_rocket_flight_tm_get_nas_bias_y(msg);
- rocket_flight_tm->nas_bias_z = mavlink_msg_rocket_flight_tm_get_nas_bias_z(msg);
- rocket_flight_tm->pin_quick_connector = mavlink_msg_rocket_flight_tm_get_pin_quick_connector(msg);
- rocket_flight_tm->battery_voltage = mavlink_msg_rocket_flight_tm_get_battery_voltage(msg);
- rocket_flight_tm->cam_battery_voltage = mavlink_msg_rocket_flight_tm_get_cam_battery_voltage(msg);
- rocket_flight_tm->current_consumption = mavlink_msg_rocket_flight_tm_get_current_consumption(msg);
- rocket_flight_tm->temperature = mavlink_msg_rocket_flight_tm_get_temperature(msg);
- rocket_flight_tm->ada_state = mavlink_msg_rocket_flight_tm_get_ada_state(msg);
- rocket_flight_tm->fmm_state = mavlink_msg_rocket_flight_tm_get_fmm_state(msg);
- rocket_flight_tm->dpl_state = mavlink_msg_rocket_flight_tm_get_dpl_state(msg);
- rocket_flight_tm->abk_state = mavlink_msg_rocket_flight_tm_get_abk_state(msg);
- rocket_flight_tm->nas_state = mavlink_msg_rocket_flight_tm_get_nas_state(msg);
- rocket_flight_tm->mea_state = mavlink_msg_rocket_flight_tm_get_mea_state(msg);
- rocket_flight_tm->gps_fix = mavlink_msg_rocket_flight_tm_get_gps_fix(msg);
- rocket_flight_tm->pin_launch = mavlink_msg_rocket_flight_tm_get_pin_launch(msg);
- rocket_flight_tm->pin_nosecone = mavlink_msg_rocket_flight_tm_get_pin_nosecone(msg);
- rocket_flight_tm->pin_expulsion = mavlink_msg_rocket_flight_tm_get_pin_expulsion(msg);
- rocket_flight_tm->cutter_presence = mavlink_msg_rocket_flight_tm_get_cutter_presence(msg);
- rocket_flight_tm->logger_error = mavlink_msg_rocket_flight_tm_get_logger_error(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN? msg->len : MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN;
- memset(rocket_flight_tm, 0, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
- memcpy(rocket_flight_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_rocket_stats_tm.h b/mavlink_lib/gemini/mavlink_msg_rocket_stats_tm.h
deleted file mode 100644
index c878c468511c88c92b03ee5caa9a8f0ce437a766..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_rocket_stats_tm.h
+++ /dev/null
@@ -1,638 +0,0 @@
-#pragma once
-// MESSAGE ROCKET_STATS_TM PACKING
-
-#define MAVLINK_MSG_ID_ROCKET_STATS_TM 210
-
-
-typedef struct __mavlink_rocket_stats_tm_t {
- uint64_t liftoff_ts; /*< [us] System clock at liftoff*/
- uint64_t liftoff_max_acc_ts; /*< [us] System clock at the maximum liftoff acceleration*/
- uint64_t dpl_ts; /*< [us] System clock at drouge deployment*/
- uint64_t max_z_speed_ts; /*< [us] System clock at ADA max vertical speed*/
- uint64_t apogee_ts; /*< [us] System clock at apogee*/
- float liftoff_max_acc; /*< [m/s2] Maximum liftoff acceleration*/
- float dpl_max_acc; /*< [m/s2] Max acceleration during drouge deployment*/
- float max_z_speed; /*< [m/s] Max measured vertical speed - ADA*/
- float max_airspeed_pitot; /*< [m/s] Max speed read by the pitot tube*/
- float max_speed_altitude; /*< [m] Altitude at max speed*/
- float apogee_lat; /*< [deg] Apogee latitude*/
- float apogee_lon; /*< [deg] Apogee longitude*/
- float apogee_alt; /*< [m] Apogee altitude*/
- float min_pressure; /*< [Pa] Apogee pressure - Digital barometer*/
- float ada_min_pressure; /*< [Pa] Apogee pressure - ADA filtered*/
- float dpl_vane_max_pressure; /*< [Pa] Max pressure in the deployment bay during drogue deployment*/
- float cpu_load; /*< CPU load in percentage*/
- uint32_t free_heap; /*< Amount of available heap in memory*/
-} mavlink_rocket_stats_tm_t;
-
-#define MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN 92
-#define MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN 92
-#define MAVLINK_MSG_ID_210_LEN 92
-#define MAVLINK_MSG_ID_210_MIN_LEN 92
-
-#define MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC 245
-#define MAVLINK_MSG_ID_210_CRC 245
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM { \
- 210, \
- "ROCKET_STATS_TM", \
- 18, \
- { { "liftoff_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_stats_tm_t, liftoff_ts) }, \
- { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_rocket_stats_tm_t, liftoff_max_acc_ts) }, \
- { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_rocket_stats_tm_t, liftoff_max_acc) }, \
- { "dpl_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_rocket_stats_tm_t, dpl_ts) }, \
- { "dpl_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_rocket_stats_tm_t, dpl_max_acc) }, \
- { "max_z_speed_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 24, offsetof(mavlink_rocket_stats_tm_t, max_z_speed_ts) }, \
- { "max_z_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_rocket_stats_tm_t, max_z_speed) }, \
- { "max_airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_rocket_stats_tm_t, max_airspeed_pitot) }, \
- { "max_speed_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_rocket_stats_tm_t, max_speed_altitude) }, \
- { "apogee_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 32, offsetof(mavlink_rocket_stats_tm_t, apogee_ts) }, \
- { "apogee_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_rocket_stats_tm_t, apogee_lat) }, \
- { "apogee_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_stats_tm_t, apogee_lon) }, \
- { "apogee_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_stats_tm_t, apogee_alt) }, \
- { "min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_stats_tm_t, min_pressure) }, \
- { "ada_min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_stats_tm_t, ada_min_pressure) }, \
- { "dpl_vane_max_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_stats_tm_t, dpl_vane_max_pressure) }, \
- { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_stats_tm_t, cpu_load) }, \
- { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 88, offsetof(mavlink_rocket_stats_tm_t, free_heap) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM { \
- "ROCKET_STATS_TM", \
- 18, \
- { { "liftoff_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_stats_tm_t, liftoff_ts) }, \
- { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_rocket_stats_tm_t, liftoff_max_acc_ts) }, \
- { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_rocket_stats_tm_t, liftoff_max_acc) }, \
- { "dpl_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_rocket_stats_tm_t, dpl_ts) }, \
- { "dpl_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_rocket_stats_tm_t, dpl_max_acc) }, \
- { "max_z_speed_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 24, offsetof(mavlink_rocket_stats_tm_t, max_z_speed_ts) }, \
- { "max_z_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_rocket_stats_tm_t, max_z_speed) }, \
- { "max_airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_rocket_stats_tm_t, max_airspeed_pitot) }, \
- { "max_speed_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_rocket_stats_tm_t, max_speed_altitude) }, \
- { "apogee_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 32, offsetof(mavlink_rocket_stats_tm_t, apogee_ts) }, \
- { "apogee_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_rocket_stats_tm_t, apogee_lat) }, \
- { "apogee_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_stats_tm_t, apogee_lon) }, \
- { "apogee_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_stats_tm_t, apogee_alt) }, \
- { "min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_stats_tm_t, min_pressure) }, \
- { "ada_min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_stats_tm_t, ada_min_pressure) }, \
- { "dpl_vane_max_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_stats_tm_t, dpl_vane_max_pressure) }, \
- { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_stats_tm_t, cpu_load) }, \
- { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 88, offsetof(mavlink_rocket_stats_tm_t, free_heap) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a rocket_stats_tm 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 liftoff_ts [us] System clock at liftoff
- * @param liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param dpl_ts [us] System clock at drouge deployment
- * @param dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param max_z_speed_ts [us] System clock at ADA max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed - ADA
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [us] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param apogee_alt [m] Apogee altitude
- * @param min_pressure [Pa] Apogee pressure - Digital barometer
- * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered
- * @param dpl_vane_max_pressure [Pa] Max pressure in the deployment bay during drogue deployment
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_rocket_stats_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float ada_min_pressure, float dpl_vane_max_pressure, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_ts);
- _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 16, dpl_ts);
- _mav_put_uint64_t(buf, 24, max_z_speed_ts);
- _mav_put_uint64_t(buf, 32, apogee_ts);
- _mav_put_float(buf, 40, liftoff_max_acc);
- _mav_put_float(buf, 44, dpl_max_acc);
- _mav_put_float(buf, 48, max_z_speed);
- _mav_put_float(buf, 52, max_airspeed_pitot);
- _mav_put_float(buf, 56, max_speed_altitude);
- _mav_put_float(buf, 60, apogee_lat);
- _mav_put_float(buf, 64, apogee_lon);
- _mav_put_float(buf, 68, apogee_alt);
- _mav_put_float(buf, 72, min_pressure);
- _mav_put_float(buf, 76, ada_min_pressure);
- _mav_put_float(buf, 80, dpl_vane_max_pressure);
- _mav_put_float(buf, 84, cpu_load);
- _mav_put_uint32_t(buf, 88, free_heap);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
-#else
- mavlink_rocket_stats_tm_t packet;
- packet.liftoff_ts = liftoff_ts;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.dpl_ts = dpl_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.dpl_max_acc = dpl_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.apogee_alt = apogee_alt;
- packet.min_pressure = min_pressure;
- packet.ada_min_pressure = ada_min_pressure;
- packet.dpl_vane_max_pressure = dpl_vane_max_pressure;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ROCKET_STATS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-}
-
-/**
- * @brief Pack a rocket_stats_tm 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 liftoff_ts [us] System clock at liftoff
- * @param liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param dpl_ts [us] System clock at drouge deployment
- * @param dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param max_z_speed_ts [us] System clock at ADA max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed - ADA
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [us] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param apogee_alt [m] Apogee altitude
- * @param min_pressure [Pa] Apogee pressure - Digital barometer
- * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered
- * @param dpl_vane_max_pressure [Pa] Max pressure in the deployment bay during drogue deployment
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_rocket_stats_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t liftoff_ts,uint64_t liftoff_max_acc_ts,float liftoff_max_acc,uint64_t dpl_ts,float dpl_max_acc,uint64_t max_z_speed_ts,float max_z_speed,float max_airspeed_pitot,float max_speed_altitude,uint64_t apogee_ts,float apogee_lat,float apogee_lon,float apogee_alt,float min_pressure,float ada_min_pressure,float dpl_vane_max_pressure,float cpu_load,uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_ts);
- _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 16, dpl_ts);
- _mav_put_uint64_t(buf, 24, max_z_speed_ts);
- _mav_put_uint64_t(buf, 32, apogee_ts);
- _mav_put_float(buf, 40, liftoff_max_acc);
- _mav_put_float(buf, 44, dpl_max_acc);
- _mav_put_float(buf, 48, max_z_speed);
- _mav_put_float(buf, 52, max_airspeed_pitot);
- _mav_put_float(buf, 56, max_speed_altitude);
- _mav_put_float(buf, 60, apogee_lat);
- _mav_put_float(buf, 64, apogee_lon);
- _mav_put_float(buf, 68, apogee_alt);
- _mav_put_float(buf, 72, min_pressure);
- _mav_put_float(buf, 76, ada_min_pressure);
- _mav_put_float(buf, 80, dpl_vane_max_pressure);
- _mav_put_float(buf, 84, cpu_load);
- _mav_put_uint32_t(buf, 88, free_heap);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
-#else
- mavlink_rocket_stats_tm_t packet;
- packet.liftoff_ts = liftoff_ts;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.dpl_ts = dpl_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.dpl_max_acc = dpl_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.apogee_alt = apogee_alt;
- packet.min_pressure = min_pressure;
- packet.ada_min_pressure = ada_min_pressure;
- packet.dpl_vane_max_pressure = dpl_vane_max_pressure;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ROCKET_STATS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-}
-
-/**
- * @brief Encode a rocket_stats_tm 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 rocket_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_rocket_stats_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rocket_stats_tm_t* rocket_stats_tm)
-{
- return mavlink_msg_rocket_stats_tm_pack(system_id, component_id, msg, rocket_stats_tm->liftoff_ts, rocket_stats_tm->liftoff_max_acc_ts, rocket_stats_tm->liftoff_max_acc, rocket_stats_tm->dpl_ts, rocket_stats_tm->dpl_max_acc, rocket_stats_tm->max_z_speed_ts, rocket_stats_tm->max_z_speed, rocket_stats_tm->max_airspeed_pitot, rocket_stats_tm->max_speed_altitude, rocket_stats_tm->apogee_ts, rocket_stats_tm->apogee_lat, rocket_stats_tm->apogee_lon, rocket_stats_tm->apogee_alt, rocket_stats_tm->min_pressure, rocket_stats_tm->ada_min_pressure, rocket_stats_tm->dpl_vane_max_pressure, rocket_stats_tm->cpu_load, rocket_stats_tm->free_heap);
-}
-
-/**
- * @brief Encode a rocket_stats_tm 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 rocket_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_rocket_stats_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rocket_stats_tm_t* rocket_stats_tm)
-{
- return mavlink_msg_rocket_stats_tm_pack_chan(system_id, component_id, chan, msg, rocket_stats_tm->liftoff_ts, rocket_stats_tm->liftoff_max_acc_ts, rocket_stats_tm->liftoff_max_acc, rocket_stats_tm->dpl_ts, rocket_stats_tm->dpl_max_acc, rocket_stats_tm->max_z_speed_ts, rocket_stats_tm->max_z_speed, rocket_stats_tm->max_airspeed_pitot, rocket_stats_tm->max_speed_altitude, rocket_stats_tm->apogee_ts, rocket_stats_tm->apogee_lat, rocket_stats_tm->apogee_lon, rocket_stats_tm->apogee_alt, rocket_stats_tm->min_pressure, rocket_stats_tm->ada_min_pressure, rocket_stats_tm->dpl_vane_max_pressure, rocket_stats_tm->cpu_load, rocket_stats_tm->free_heap);
-}
-
-/**
- * @brief Send a rocket_stats_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param liftoff_ts [us] System clock at liftoff
- * @param liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param dpl_ts [us] System clock at drouge deployment
- * @param dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param max_z_speed_ts [us] System clock at ADA max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed - ADA
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [us] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param apogee_alt [m] Apogee altitude
- * @param min_pressure [Pa] Apogee pressure - Digital barometer
- * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered
- * @param dpl_vane_max_pressure [Pa] Max pressure in the deployment bay during drogue deployment
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_rocket_stats_tm_send(mavlink_channel_t chan, uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float ada_min_pressure, float dpl_vane_max_pressure, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_ts);
- _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 16, dpl_ts);
- _mav_put_uint64_t(buf, 24, max_z_speed_ts);
- _mav_put_uint64_t(buf, 32, apogee_ts);
- _mav_put_float(buf, 40, liftoff_max_acc);
- _mav_put_float(buf, 44, dpl_max_acc);
- _mav_put_float(buf, 48, max_z_speed);
- _mav_put_float(buf, 52, max_airspeed_pitot);
- _mav_put_float(buf, 56, max_speed_altitude);
- _mav_put_float(buf, 60, apogee_lat);
- _mav_put_float(buf, 64, apogee_lon);
- _mav_put_float(buf, 68, apogee_alt);
- _mav_put_float(buf, 72, min_pressure);
- _mav_put_float(buf, 76, ada_min_pressure);
- _mav_put_float(buf, 80, dpl_vane_max_pressure);
- _mav_put_float(buf, 84, cpu_load);
- _mav_put_uint32_t(buf, 88, free_heap);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_STATS_TM, buf, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-#else
- mavlink_rocket_stats_tm_t packet;
- packet.liftoff_ts = liftoff_ts;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.dpl_ts = dpl_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.dpl_max_acc = dpl_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.apogee_alt = apogee_alt;
- packet.min_pressure = min_pressure;
- packet.ada_min_pressure = ada_min_pressure;
- packet.dpl_vane_max_pressure = dpl_vane_max_pressure;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_STATS_TM, (const char *)&packet, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a rocket_stats_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_rocket_stats_tm_send_struct(mavlink_channel_t chan, const mavlink_rocket_stats_tm_t* rocket_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_rocket_stats_tm_send(chan, rocket_stats_tm->liftoff_ts, rocket_stats_tm->liftoff_max_acc_ts, rocket_stats_tm->liftoff_max_acc, rocket_stats_tm->dpl_ts, rocket_stats_tm->dpl_max_acc, rocket_stats_tm->max_z_speed_ts, rocket_stats_tm->max_z_speed, rocket_stats_tm->max_airspeed_pitot, rocket_stats_tm->max_speed_altitude, rocket_stats_tm->apogee_ts, rocket_stats_tm->apogee_lat, rocket_stats_tm->apogee_lon, rocket_stats_tm->apogee_alt, rocket_stats_tm->min_pressure, rocket_stats_tm->ada_min_pressure, rocket_stats_tm->dpl_vane_max_pressure, rocket_stats_tm->cpu_load, rocket_stats_tm->free_heap);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_STATS_TM, (const char *)rocket_stats_tm, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ROCKET_STATS_TM_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_rocket_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float ada_min_pressure, float dpl_vane_max_pressure, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, liftoff_ts);
- _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 16, dpl_ts);
- _mav_put_uint64_t(buf, 24, max_z_speed_ts);
- _mav_put_uint64_t(buf, 32, apogee_ts);
- _mav_put_float(buf, 40, liftoff_max_acc);
- _mav_put_float(buf, 44, dpl_max_acc);
- _mav_put_float(buf, 48, max_z_speed);
- _mav_put_float(buf, 52, max_airspeed_pitot);
- _mav_put_float(buf, 56, max_speed_altitude);
- _mav_put_float(buf, 60, apogee_lat);
- _mav_put_float(buf, 64, apogee_lon);
- _mav_put_float(buf, 68, apogee_alt);
- _mav_put_float(buf, 72, min_pressure);
- _mav_put_float(buf, 76, ada_min_pressure);
- _mav_put_float(buf, 80, dpl_vane_max_pressure);
- _mav_put_float(buf, 84, cpu_load);
- _mav_put_uint32_t(buf, 88, free_heap);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_STATS_TM, buf, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-#else
- mavlink_rocket_stats_tm_t *packet = (mavlink_rocket_stats_tm_t *)msgbuf;
- packet->liftoff_ts = liftoff_ts;
- packet->liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet->dpl_ts = dpl_ts;
- packet->max_z_speed_ts = max_z_speed_ts;
- packet->apogee_ts = apogee_ts;
- packet->liftoff_max_acc = liftoff_max_acc;
- packet->dpl_max_acc = dpl_max_acc;
- packet->max_z_speed = max_z_speed;
- packet->max_airspeed_pitot = max_airspeed_pitot;
- packet->max_speed_altitude = max_speed_altitude;
- packet->apogee_lat = apogee_lat;
- packet->apogee_lon = apogee_lon;
- packet->apogee_alt = apogee_alt;
- packet->min_pressure = min_pressure;
- packet->ada_min_pressure = ada_min_pressure;
- packet->dpl_vane_max_pressure = dpl_vane_max_pressure;
- packet->cpu_load = cpu_load;
- packet->free_heap = free_heap;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_STATS_TM, (const char *)packet, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ROCKET_STATS_TM UNPACKING
-
-
-/**
- * @brief Get field liftoff_ts from rocket_stats_tm message
- *
- * @return [us] System clock at liftoff
- */
-static inline uint64_t mavlink_msg_rocket_stats_tm_get_liftoff_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field liftoff_max_acc_ts from rocket_stats_tm message
- *
- * @return [us] System clock at the maximum liftoff acceleration
- */
-static inline uint64_t mavlink_msg_rocket_stats_tm_get_liftoff_max_acc_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 8);
-}
-
-/**
- * @brief Get field liftoff_max_acc from rocket_stats_tm message
- *
- * @return [m/s2] Maximum liftoff acceleration
- */
-static inline float mavlink_msg_rocket_stats_tm_get_liftoff_max_acc(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field dpl_ts from rocket_stats_tm message
- *
- * @return [us] System clock at drouge deployment
- */
-static inline uint64_t mavlink_msg_rocket_stats_tm_get_dpl_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 16);
-}
-
-/**
- * @brief Get field dpl_max_acc from rocket_stats_tm message
- *
- * @return [m/s2] Max acceleration during drouge deployment
- */
-static inline float mavlink_msg_rocket_stats_tm_get_dpl_max_acc(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field max_z_speed_ts from rocket_stats_tm message
- *
- * @return [us] System clock at ADA max vertical speed
- */
-static inline uint64_t mavlink_msg_rocket_stats_tm_get_max_z_speed_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 24);
-}
-
-/**
- * @brief Get field max_z_speed from rocket_stats_tm message
- *
- * @return [m/s] Max measured vertical speed - ADA
- */
-static inline float mavlink_msg_rocket_stats_tm_get_max_z_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field max_airspeed_pitot from rocket_stats_tm message
- *
- * @return [m/s] Max speed read by the pitot tube
- */
-static inline float mavlink_msg_rocket_stats_tm_get_max_airspeed_pitot(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field max_speed_altitude from rocket_stats_tm message
- *
- * @return [m] Altitude at max speed
- */
-static inline float mavlink_msg_rocket_stats_tm_get_max_speed_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field apogee_ts from rocket_stats_tm message
- *
- * @return [us] System clock at apogee
- */
-static inline uint64_t mavlink_msg_rocket_stats_tm_get_apogee_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 32);
-}
-
-/**
- * @brief Get field apogee_lat from rocket_stats_tm message
- *
- * @return [deg] Apogee latitude
- */
-static inline float mavlink_msg_rocket_stats_tm_get_apogee_lat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field apogee_lon from rocket_stats_tm message
- *
- * @return [deg] Apogee longitude
- */
-static inline float mavlink_msg_rocket_stats_tm_get_apogee_lon(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field apogee_alt from rocket_stats_tm message
- *
- * @return [m] Apogee altitude
- */
-static inline float mavlink_msg_rocket_stats_tm_get_apogee_alt(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field min_pressure from rocket_stats_tm message
- *
- * @return [Pa] Apogee pressure - Digital barometer
- */
-static inline float mavlink_msg_rocket_stats_tm_get_min_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 72);
-}
-
-/**
- * @brief Get field ada_min_pressure from rocket_stats_tm message
- *
- * @return [Pa] Apogee pressure - ADA filtered
- */
-static inline float mavlink_msg_rocket_stats_tm_get_ada_min_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 76);
-}
-
-/**
- * @brief Get field dpl_vane_max_pressure from rocket_stats_tm message
- *
- * @return [Pa] Max pressure in the deployment bay during drogue deployment
- */
-static inline float mavlink_msg_rocket_stats_tm_get_dpl_vane_max_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 80);
-}
-
-/**
- * @brief Get field cpu_load from rocket_stats_tm message
- *
- * @return CPU load in percentage
- */
-static inline float mavlink_msg_rocket_stats_tm_get_cpu_load(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 84);
-}
-
-/**
- * @brief Get field free_heap from rocket_stats_tm message
- *
- * @return Amount of available heap in memory
- */
-static inline uint32_t mavlink_msg_rocket_stats_tm_get_free_heap(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 88);
-}
-
-/**
- * @brief Decode a rocket_stats_tm message into a struct
- *
- * @param msg The message to decode
- * @param rocket_stats_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_rocket_stats_tm_decode(const mavlink_message_t* msg, mavlink_rocket_stats_tm_t* rocket_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- rocket_stats_tm->liftoff_ts = mavlink_msg_rocket_stats_tm_get_liftoff_ts(msg);
- rocket_stats_tm->liftoff_max_acc_ts = mavlink_msg_rocket_stats_tm_get_liftoff_max_acc_ts(msg);
- rocket_stats_tm->dpl_ts = mavlink_msg_rocket_stats_tm_get_dpl_ts(msg);
- rocket_stats_tm->max_z_speed_ts = mavlink_msg_rocket_stats_tm_get_max_z_speed_ts(msg);
- rocket_stats_tm->apogee_ts = mavlink_msg_rocket_stats_tm_get_apogee_ts(msg);
- rocket_stats_tm->liftoff_max_acc = mavlink_msg_rocket_stats_tm_get_liftoff_max_acc(msg);
- rocket_stats_tm->dpl_max_acc = mavlink_msg_rocket_stats_tm_get_dpl_max_acc(msg);
- rocket_stats_tm->max_z_speed = mavlink_msg_rocket_stats_tm_get_max_z_speed(msg);
- rocket_stats_tm->max_airspeed_pitot = mavlink_msg_rocket_stats_tm_get_max_airspeed_pitot(msg);
- rocket_stats_tm->max_speed_altitude = mavlink_msg_rocket_stats_tm_get_max_speed_altitude(msg);
- rocket_stats_tm->apogee_lat = mavlink_msg_rocket_stats_tm_get_apogee_lat(msg);
- rocket_stats_tm->apogee_lon = mavlink_msg_rocket_stats_tm_get_apogee_lon(msg);
- rocket_stats_tm->apogee_alt = mavlink_msg_rocket_stats_tm_get_apogee_alt(msg);
- rocket_stats_tm->min_pressure = mavlink_msg_rocket_stats_tm_get_min_pressure(msg);
- rocket_stats_tm->ada_min_pressure = mavlink_msg_rocket_stats_tm_get_ada_min_pressure(msg);
- rocket_stats_tm->dpl_vane_max_pressure = mavlink_msg_rocket_stats_tm_get_dpl_vane_max_pressure(msg);
- rocket_stats_tm->cpu_load = mavlink_msg_rocket_stats_tm_get_cpu_load(msg);
- rocket_stats_tm->free_heap = mavlink_msg_rocket_stats_tm_get_free_heap(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN? msg->len : MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN;
- memset(rocket_stats_tm, 0, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
- memcpy(rocket_stats_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_send_conrig_state_tc.h b/mavlink_lib/gemini/mavlink_msg_send_conrig_state_tc.h
deleted file mode 100644
index 672244d9efc2718ced83af37ef3140ede75f0eb8..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_send_conrig_state_tc.h
+++ /dev/null
@@ -1,338 +0,0 @@
-#pragma once
-// MESSAGE SEND_CONRIG_STATE_TC PACKING
-
-#define MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC 18
-
-
-typedef struct __mavlink_send_conrig_state_tc_t {
- uint8_t ignition_btn; /*< Ignition button pressed*/
- uint8_t filling_valve_btn; /*< Open filling valve pressed*/
- uint8_t venting_valve_btn; /*< Open venting valve pressed*/
- uint8_t release_pressure_btn; /*< Release filling line pressure pressed*/
- uint8_t quick_connector_btn; /*< Detach quick connector pressed*/
- uint8_t start_tars_btn; /*< Startup TARS pressed*/
-} mavlink_send_conrig_state_tc_t;
-
-#define MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_LEN 6
-#define MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_MIN_LEN 6
-#define MAVLINK_MSG_ID_18_LEN 6
-#define MAVLINK_MSG_ID_18_MIN_LEN 6
-
-#define MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_CRC 149
-#define MAVLINK_MSG_ID_18_CRC 149
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SEND_CONRIG_STATE_TC { \
- 18, \
- "SEND_CONRIG_STATE_TC", \
- 6, \
- { { "ignition_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_send_conrig_state_tc_t, ignition_btn) }, \
- { "filling_valve_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_send_conrig_state_tc_t, filling_valve_btn) }, \
- { "venting_valve_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_send_conrig_state_tc_t, venting_valve_btn) }, \
- { "release_pressure_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_send_conrig_state_tc_t, release_pressure_btn) }, \
- { "quick_connector_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_send_conrig_state_tc_t, quick_connector_btn) }, \
- { "start_tars_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_send_conrig_state_tc_t, start_tars_btn) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SEND_CONRIG_STATE_TC { \
- "SEND_CONRIG_STATE_TC", \
- 6, \
- { { "ignition_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_send_conrig_state_tc_t, ignition_btn) }, \
- { "filling_valve_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_send_conrig_state_tc_t, filling_valve_btn) }, \
- { "venting_valve_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_send_conrig_state_tc_t, venting_valve_btn) }, \
- { "release_pressure_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_send_conrig_state_tc_t, release_pressure_btn) }, \
- { "quick_connector_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_send_conrig_state_tc_t, quick_connector_btn) }, \
- { "start_tars_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_send_conrig_state_tc_t, start_tars_btn) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a send_conrig_state_tc 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 ignition_btn Ignition button pressed
- * @param filling_valve_btn Open filling valve pressed
- * @param venting_valve_btn Open venting valve pressed
- * @param release_pressure_btn Release filling line pressure pressed
- * @param quick_connector_btn Detach quick connector pressed
- * @param start_tars_btn Startup TARS pressed
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_send_conrig_state_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t ignition_btn, uint8_t filling_valve_btn, uint8_t venting_valve_btn, uint8_t release_pressure_btn, uint8_t quick_connector_btn, uint8_t start_tars_btn)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_LEN];
- _mav_put_uint8_t(buf, 0, ignition_btn);
- _mav_put_uint8_t(buf, 1, filling_valve_btn);
- _mav_put_uint8_t(buf, 2, venting_valve_btn);
- _mav_put_uint8_t(buf, 3, release_pressure_btn);
- _mav_put_uint8_t(buf, 4, quick_connector_btn);
- _mav_put_uint8_t(buf, 5, start_tars_btn);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_LEN);
-#else
- mavlink_send_conrig_state_tc_t packet;
- packet.ignition_btn = ignition_btn;
- packet.filling_valve_btn = filling_valve_btn;
- packet.venting_valve_btn = venting_valve_btn;
- packet.release_pressure_btn = release_pressure_btn;
- packet.quick_connector_btn = quick_connector_btn;
- packet.start_tars_btn = start_tars_btn;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_CRC);
-}
-
-/**
- * @brief Pack a send_conrig_state_tc 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 ignition_btn Ignition button pressed
- * @param filling_valve_btn Open filling valve pressed
- * @param venting_valve_btn Open venting valve pressed
- * @param release_pressure_btn Release filling line pressure pressed
- * @param quick_connector_btn Detach quick connector pressed
- * @param start_tars_btn Startup TARS pressed
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_send_conrig_state_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t ignition_btn,uint8_t filling_valve_btn,uint8_t venting_valve_btn,uint8_t release_pressure_btn,uint8_t quick_connector_btn,uint8_t start_tars_btn)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_LEN];
- _mav_put_uint8_t(buf, 0, ignition_btn);
- _mav_put_uint8_t(buf, 1, filling_valve_btn);
- _mav_put_uint8_t(buf, 2, venting_valve_btn);
- _mav_put_uint8_t(buf, 3, release_pressure_btn);
- _mav_put_uint8_t(buf, 4, quick_connector_btn);
- _mav_put_uint8_t(buf, 5, start_tars_btn);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_LEN);
-#else
- mavlink_send_conrig_state_tc_t packet;
- packet.ignition_btn = ignition_btn;
- packet.filling_valve_btn = filling_valve_btn;
- packet.venting_valve_btn = venting_valve_btn;
- packet.release_pressure_btn = release_pressure_btn;
- packet.quick_connector_btn = quick_connector_btn;
- packet.start_tars_btn = start_tars_btn;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_CRC);
-}
-
-/**
- * @brief Encode a send_conrig_state_tc 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 send_conrig_state_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_send_conrig_state_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_send_conrig_state_tc_t* send_conrig_state_tc)
-{
- return mavlink_msg_send_conrig_state_tc_pack(system_id, component_id, msg, send_conrig_state_tc->ignition_btn, send_conrig_state_tc->filling_valve_btn, send_conrig_state_tc->venting_valve_btn, send_conrig_state_tc->release_pressure_btn, send_conrig_state_tc->quick_connector_btn, send_conrig_state_tc->start_tars_btn);
-}
-
-/**
- * @brief Encode a send_conrig_state_tc 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 send_conrig_state_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_send_conrig_state_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_send_conrig_state_tc_t* send_conrig_state_tc)
-{
- return mavlink_msg_send_conrig_state_tc_pack_chan(system_id, component_id, chan, msg, send_conrig_state_tc->ignition_btn, send_conrig_state_tc->filling_valve_btn, send_conrig_state_tc->venting_valve_btn, send_conrig_state_tc->release_pressure_btn, send_conrig_state_tc->quick_connector_btn, send_conrig_state_tc->start_tars_btn);
-}
-
-/**
- * @brief Send a send_conrig_state_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param ignition_btn Ignition button pressed
- * @param filling_valve_btn Open filling valve pressed
- * @param venting_valve_btn Open venting valve pressed
- * @param release_pressure_btn Release filling line pressure pressed
- * @param quick_connector_btn Detach quick connector pressed
- * @param start_tars_btn Startup TARS pressed
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_send_conrig_state_tc_send(mavlink_channel_t chan, uint8_t ignition_btn, uint8_t filling_valve_btn, uint8_t venting_valve_btn, uint8_t release_pressure_btn, uint8_t quick_connector_btn, uint8_t start_tars_btn)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_LEN];
- _mav_put_uint8_t(buf, 0, ignition_btn);
- _mav_put_uint8_t(buf, 1, filling_valve_btn);
- _mav_put_uint8_t(buf, 2, venting_valve_btn);
- _mav_put_uint8_t(buf, 3, release_pressure_btn);
- _mav_put_uint8_t(buf, 4, quick_connector_btn);
- _mav_put_uint8_t(buf, 5, start_tars_btn);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC, buf, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_CRC);
-#else
- mavlink_send_conrig_state_tc_t packet;
- packet.ignition_btn = ignition_btn;
- packet.filling_valve_btn = filling_valve_btn;
- packet.venting_valve_btn = venting_valve_btn;
- packet.release_pressure_btn = release_pressure_btn;
- packet.quick_connector_btn = quick_connector_btn;
- packet.start_tars_btn = start_tars_btn;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC, (const char *)&packet, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a send_conrig_state_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_send_conrig_state_tc_send_struct(mavlink_channel_t chan, const mavlink_send_conrig_state_tc_t* send_conrig_state_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_send_conrig_state_tc_send(chan, send_conrig_state_tc->ignition_btn, send_conrig_state_tc->filling_valve_btn, send_conrig_state_tc->venting_valve_btn, send_conrig_state_tc->release_pressure_btn, send_conrig_state_tc->quick_connector_btn, send_conrig_state_tc->start_tars_btn);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC, (const char *)send_conrig_state_tc, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_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_send_conrig_state_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t ignition_btn, uint8_t filling_valve_btn, uint8_t venting_valve_btn, uint8_t release_pressure_btn, uint8_t quick_connector_btn, uint8_t start_tars_btn)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, ignition_btn);
- _mav_put_uint8_t(buf, 1, filling_valve_btn);
- _mav_put_uint8_t(buf, 2, venting_valve_btn);
- _mav_put_uint8_t(buf, 3, release_pressure_btn);
- _mav_put_uint8_t(buf, 4, quick_connector_btn);
- _mav_put_uint8_t(buf, 5, start_tars_btn);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC, buf, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_CRC);
-#else
- mavlink_send_conrig_state_tc_t *packet = (mavlink_send_conrig_state_tc_t *)msgbuf;
- packet->ignition_btn = ignition_btn;
- packet->filling_valve_btn = filling_valve_btn;
- packet->venting_valve_btn = venting_valve_btn;
- packet->release_pressure_btn = release_pressure_btn;
- packet->quick_connector_btn = quick_connector_btn;
- packet->start_tars_btn = start_tars_btn;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC, (const char *)packet, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SEND_CONRIG_STATE_TC UNPACKING
-
-
-/**
- * @brief Get field ignition_btn from send_conrig_state_tc message
- *
- * @return Ignition button pressed
- */
-static inline uint8_t mavlink_msg_send_conrig_state_tc_get_ignition_btn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field filling_valve_btn from send_conrig_state_tc message
- *
- * @return Open filling valve pressed
- */
-static inline uint8_t mavlink_msg_send_conrig_state_tc_get_filling_valve_btn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Get field venting_valve_btn from send_conrig_state_tc message
- *
- * @return Open venting valve pressed
- */
-static inline uint8_t mavlink_msg_send_conrig_state_tc_get_venting_valve_btn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 2);
-}
-
-/**
- * @brief Get field release_pressure_btn from send_conrig_state_tc message
- *
- * @return Release filling line pressure pressed
- */
-static inline uint8_t mavlink_msg_send_conrig_state_tc_get_release_pressure_btn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 3);
-}
-
-/**
- * @brief Get field quick_connector_btn from send_conrig_state_tc message
- *
- * @return Detach quick connector pressed
- */
-static inline uint8_t mavlink_msg_send_conrig_state_tc_get_quick_connector_btn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 4);
-}
-
-/**
- * @brief Get field start_tars_btn from send_conrig_state_tc message
- *
- * @return Startup TARS pressed
- */
-static inline uint8_t mavlink_msg_send_conrig_state_tc_get_start_tars_btn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 5);
-}
-
-/**
- * @brief Decode a send_conrig_state_tc message into a struct
- *
- * @param msg The message to decode
- * @param send_conrig_state_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_send_conrig_state_tc_decode(const mavlink_message_t* msg, mavlink_send_conrig_state_tc_t* send_conrig_state_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- send_conrig_state_tc->ignition_btn = mavlink_msg_send_conrig_state_tc_get_ignition_btn(msg);
- send_conrig_state_tc->filling_valve_btn = mavlink_msg_send_conrig_state_tc_get_filling_valve_btn(msg);
- send_conrig_state_tc->venting_valve_btn = mavlink_msg_send_conrig_state_tc_get_venting_valve_btn(msg);
- send_conrig_state_tc->release_pressure_btn = mavlink_msg_send_conrig_state_tc_get_release_pressure_btn(msg);
- send_conrig_state_tc->quick_connector_btn = mavlink_msg_send_conrig_state_tc_get_quick_connector_btn(msg);
- send_conrig_state_tc->start_tars_btn = mavlink_msg_send_conrig_state_tc_get_start_tars_btn(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_LEN? msg->len : MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_LEN;
- memset(send_conrig_state_tc, 0, MAVLINK_MSG_ID_SEND_CONRIG_STATE_TC_LEN);
- memcpy(send_conrig_state_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_sensor_state_tm.h b/mavlink_lib/gemini/mavlink_msg_sensor_state_tm.h
deleted file mode 100644
index deec614076883a9d0a979da1a7b2c515b2d87361..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_sensor_state_tm.h
+++ /dev/null
@@ -1,230 +0,0 @@
-#pragma once
-// MESSAGE SENSOR_STATE_TM PACKING
-
-#define MAVLINK_MSG_ID_SENSOR_STATE_TM 111
-
-
-typedef struct __mavlink_sensor_state_tm_t {
- char sensor_name[20]; /*< Sensor name*/
- uint8_t state; /*< Boolean that represents the init state*/
-} mavlink_sensor_state_tm_t;
-
-#define MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN 21
-#define MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN 21
-#define MAVLINK_MSG_ID_111_LEN 21
-#define MAVLINK_MSG_ID_111_MIN_LEN 21
-
-#define MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC 155
-#define MAVLINK_MSG_ID_111_CRC 155
-
-#define MAVLINK_MSG_SENSOR_STATE_TM_FIELD_SENSOR_NAME_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM { \
- 111, \
- "SENSOR_STATE_TM", \
- 2, \
- { { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 0, offsetof(mavlink_sensor_state_tm_t, sensor_name) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_sensor_state_tm_t, state) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM { \
- "SENSOR_STATE_TM", \
- 2, \
- { { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 0, offsetof(mavlink_sensor_state_tm_t, sensor_name) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_sensor_state_tm_t, state) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a sensor_state_tm 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 sensor_name Sensor name
- * @param state Boolean that represents the init state
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sensor_state_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- const char *sensor_name, uint8_t state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN];
- _mav_put_uint8_t(buf, 20, state);
- _mav_put_char_array(buf, 0, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
-#else
- mavlink_sensor_state_tm_t packet;
- packet.state = state;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SENSOR_STATE_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-}
-
-/**
- * @brief Pack a sensor_state_tm 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 sensor_name Sensor name
- * @param state Boolean that represents the init state
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sensor_state_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- const char *sensor_name,uint8_t state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN];
- _mav_put_uint8_t(buf, 20, state);
- _mav_put_char_array(buf, 0, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
-#else
- mavlink_sensor_state_tm_t packet;
- packet.state = state;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SENSOR_STATE_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-}
-
-/**
- * @brief Encode a sensor_state_tm 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 sensor_state_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sensor_state_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_state_tm_t* sensor_state_tm)
-{
- return mavlink_msg_sensor_state_tm_pack(system_id, component_id, msg, sensor_state_tm->sensor_name, sensor_state_tm->state);
-}
-
-/**
- * @brief Encode a sensor_state_tm 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 sensor_state_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sensor_state_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sensor_state_tm_t* sensor_state_tm)
-{
- return mavlink_msg_sensor_state_tm_pack_chan(system_id, component_id, chan, msg, sensor_state_tm->sensor_name, sensor_state_tm->state);
-}
-
-/**
- * @brief Send a sensor_state_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param sensor_name Sensor name
- * @param state Boolean that represents the init state
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_sensor_state_tm_send(mavlink_channel_t chan, const char *sensor_name, uint8_t state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN];
- _mav_put_uint8_t(buf, 20, state);
- _mav_put_char_array(buf, 0, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_STATE_TM, buf, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-#else
- mavlink_sensor_state_tm_t packet;
- packet.state = state;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_STATE_TM, (const char *)&packet, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a sensor_state_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_sensor_state_tm_send_struct(mavlink_channel_t chan, const mavlink_sensor_state_tm_t* sensor_state_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_sensor_state_tm_send(chan, sensor_state_tm->sensor_name, sensor_state_tm->state);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_STATE_TM, (const char *)sensor_state_tm, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SENSOR_STATE_TM_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_sensor_state_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *sensor_name, uint8_t state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 20, state);
- _mav_put_char_array(buf, 0, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_STATE_TM, buf, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-#else
- mavlink_sensor_state_tm_t *packet = (mavlink_sensor_state_tm_t *)msgbuf;
- packet->state = state;
- mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_STATE_TM, (const char *)packet, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SENSOR_STATE_TM UNPACKING
-
-
-/**
- * @brief Get field sensor_name from sensor_state_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_sensor_state_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
-{
- return _MAV_RETURN_char_array(msg, sensor_name, 20, 0);
-}
-
-/**
- * @brief Get field state from sensor_state_tm message
- *
- * @return Boolean that represents the init state
- */
-static inline uint8_t mavlink_msg_sensor_state_tm_get_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 20);
-}
-
-/**
- * @brief Decode a sensor_state_tm message into a struct
- *
- * @param msg The message to decode
- * @param sensor_state_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_sensor_state_tm_decode(const mavlink_message_t* msg, mavlink_sensor_state_tm_t* sensor_state_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_sensor_state_tm_get_sensor_name(msg, sensor_state_tm->sensor_name);
- sensor_state_tm->state = mavlink_msg_sensor_state_tm_get_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN? msg->len : MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN;
- memset(sensor_state_tm, 0, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
- memcpy(sensor_state_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_sensor_tm_request_tc.h b/mavlink_lib/gemini/mavlink_msg_sensor_tm_request_tc.h
deleted file mode 100644
index bdf4a43617f74e9ba284ef8613ba5f01e808b707..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_sensor_tm_request_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SENSOR_TM_REQUEST_TC PACKING
-
-#define MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC 4
-
-
-typedef struct __mavlink_sensor_tm_request_tc_t {
- uint8_t sensor_name; /*< A member of the SensorTMList enum*/
-} mavlink_sensor_tm_request_tc_t;
-
-#define MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN 1
-#define MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_4_LEN 1
-#define MAVLINK_MSG_ID_4_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC 248
-#define MAVLINK_MSG_ID_4_CRC 248
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC { \
- 4, \
- "SENSOR_TM_REQUEST_TC", \
- 1, \
- { { "sensor_name", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_sensor_tm_request_tc_t, sensor_name) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC { \
- "SENSOR_TM_REQUEST_TC", \
- 1, \
- { { "sensor_name", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_sensor_tm_request_tc_t, sensor_name) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a sensor_tm_request_tc 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 sensor_name A member of the SensorTMList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sensor_tm_request_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t sensor_name)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, sensor_name);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN);
-#else
- mavlink_sensor_tm_request_tc_t packet;
- packet.sensor_name = sensor_name;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Pack a sensor_tm_request_tc 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 sensor_name A member of the SensorTMList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sensor_tm_request_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t sensor_name)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, sensor_name);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN);
-#else
- mavlink_sensor_tm_request_tc_t packet;
- packet.sensor_name = sensor_name;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Encode a sensor_tm_request_tc 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 sensor_tm_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sensor_tm_request_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_tm_request_tc_t* sensor_tm_request_tc)
-{
- return mavlink_msg_sensor_tm_request_tc_pack(system_id, component_id, msg, sensor_tm_request_tc->sensor_name);
-}
-
-/**
- * @brief Encode a sensor_tm_request_tc 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 sensor_tm_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sensor_tm_request_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sensor_tm_request_tc_t* sensor_tm_request_tc)
-{
- return mavlink_msg_sensor_tm_request_tc_pack_chan(system_id, component_id, chan, msg, sensor_tm_request_tc->sensor_name);
-}
-
-/**
- * @brief Send a sensor_tm_request_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param sensor_name A member of the SensorTMList enum
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_sensor_tm_request_tc_send(mavlink_channel_t chan, uint8_t sensor_name)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, sensor_name);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC, buf, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-#else
- mavlink_sensor_tm_request_tc_t packet;
- packet.sensor_name = sensor_name;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC, (const char *)&packet, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a sensor_tm_request_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_sensor_tm_request_tc_send_struct(mavlink_channel_t chan, const mavlink_sensor_tm_request_tc_t* sensor_tm_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_sensor_tm_request_tc_send(chan, sensor_tm_request_tc->sensor_name);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC, (const char *)sensor_tm_request_tc, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_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_sensor_tm_request_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t sensor_name)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, sensor_name);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC, buf, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-#else
- mavlink_sensor_tm_request_tc_t *packet = (mavlink_sensor_tm_request_tc_t *)msgbuf;
- packet->sensor_name = sensor_name;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC, (const char *)packet, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SENSOR_TM_REQUEST_TC UNPACKING
-
-
-/**
- * @brief Get field sensor_name from sensor_tm_request_tc message
- *
- * @return A member of the SensorTMList enum
- */
-static inline uint8_t mavlink_msg_sensor_tm_request_tc_get_sensor_name(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a sensor_tm_request_tc message into a struct
- *
- * @param msg The message to decode
- * @param sensor_tm_request_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_sensor_tm_request_tc_decode(const mavlink_message_t* msg, mavlink_sensor_tm_request_tc_t* sensor_tm_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- sensor_tm_request_tc->sensor_name = mavlink_msg_sensor_tm_request_tc_get_sensor_name(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN? msg->len : MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN;
- memset(sensor_tm_request_tc, 0, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN);
- memcpy(sensor_tm_request_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_servo_tm.h b/mavlink_lib/gemini/mavlink_msg_servo_tm.h
deleted file mode 100644
index 0ffe705d7c4094e1d82b537e2c7977a64b12c86a..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_servo_tm.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SERVO_TM PACKING
-
-#define MAVLINK_MSG_ID_SERVO_TM 112
-
-
-typedef struct __mavlink_servo_tm_t {
- float servo_position; /*< Position of the servo [0-1]*/
- uint8_t servo_id; /*< A member of the ServosList enum*/
-} mavlink_servo_tm_t;
-
-#define MAVLINK_MSG_ID_SERVO_TM_LEN 5
-#define MAVLINK_MSG_ID_SERVO_TM_MIN_LEN 5
-#define MAVLINK_MSG_ID_112_LEN 5
-#define MAVLINK_MSG_ID_112_MIN_LEN 5
-
-#define MAVLINK_MSG_ID_SERVO_TM_CRC 87
-#define MAVLINK_MSG_ID_112_CRC 87
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SERVO_TM { \
- 112, \
- "SERVO_TM", \
- 2, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_servo_tm_t, servo_id) }, \
- { "servo_position", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_servo_tm_t, servo_position) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SERVO_TM { \
- "SERVO_TM", \
- 2, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_servo_tm_t, servo_id) }, \
- { "servo_position", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_servo_tm_t, servo_position) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a servo_tm 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 servo_id A member of the ServosList enum
- * @param servo_position Position of the servo [0-1]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_servo_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t servo_id, float servo_position)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SERVO_TM_LEN];
- _mav_put_float(buf, 0, servo_position);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_TM_LEN);
-#else
- mavlink_servo_tm_t packet;
- packet.servo_position = servo_position;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SERVO_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-}
-
-/**
- * @brief Pack a servo_tm 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 servo_id A member of the ServosList enum
- * @param servo_position Position of the servo [0-1]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_servo_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t servo_id,float servo_position)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SERVO_TM_LEN];
- _mav_put_float(buf, 0, servo_position);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_TM_LEN);
-#else
- mavlink_servo_tm_t packet;
- packet.servo_position = servo_position;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SERVO_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-}
-
-/**
- * @brief Encode a servo_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_servo_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_servo_tm_t* servo_tm)
-{
- return mavlink_msg_servo_tm_pack(system_id, component_id, msg, servo_tm->servo_id, servo_tm->servo_position);
-}
-
-/**
- * @brief Encode a servo_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_servo_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_servo_tm_t* servo_tm)
-{
- return mavlink_msg_servo_tm_pack_chan(system_id, component_id, chan, msg, servo_tm->servo_id, servo_tm->servo_position);
-}
-
-/**
- * @brief Send a servo_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param servo_id A member of the ServosList enum
- * @param servo_position Position of the servo [0-1]
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_servo_tm_send(mavlink_channel_t chan, uint8_t servo_id, float servo_position)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SERVO_TM_LEN];
- _mav_put_float(buf, 0, servo_position);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM, buf, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-#else
- mavlink_servo_tm_t packet;
- packet.servo_position = servo_position;
- packet.servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM, (const char *)&packet, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a servo_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_servo_tm_send_struct(mavlink_channel_t chan, const mavlink_servo_tm_t* servo_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_servo_tm_send(chan, servo_tm->servo_id, servo_tm->servo_position);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM, (const char *)servo_tm, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SERVO_TM_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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t servo_id, float servo_position)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, servo_position);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM, buf, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-#else
- mavlink_servo_tm_t *packet = (mavlink_servo_tm_t *)msgbuf;
- packet->servo_position = servo_position;
- packet->servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM, (const char *)packet, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SERVO_TM UNPACKING
-
-
-/**
- * @brief Get field servo_id from servo_tm message
- *
- * @return A member of the ServosList enum
- */
-static inline uint8_t mavlink_msg_servo_tm_get_servo_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 4);
-}
-
-/**
- * @brief Get field servo_position from servo_tm message
- *
- * @return Position of the servo [0-1]
- */
-static inline float mavlink_msg_servo_tm_get_servo_position(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a servo_tm message into a struct
- *
- * @param msg The message to decode
- * @param servo_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_servo_tm_decode(const mavlink_message_t* msg, mavlink_servo_tm_t* servo_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- servo_tm->servo_position = mavlink_msg_servo_tm_get_servo_position(msg);
- servo_tm->servo_id = mavlink_msg_servo_tm_get_servo_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SERVO_TM_LEN? msg->len : MAVLINK_MSG_ID_SERVO_TM_LEN;
- memset(servo_tm, 0, MAVLINK_MSG_ID_SERVO_TM_LEN);
- memcpy(servo_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_servo_tm_request_tc.h b/mavlink_lib/gemini/mavlink_msg_servo_tm_request_tc.h
deleted file mode 100644
index 6ac27824c3a9ac7df9d8bf0a0983c552f689cb71..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_servo_tm_request_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SERVO_TM_REQUEST_TC PACKING
-
-#define MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC 5
-
-
-typedef struct __mavlink_servo_tm_request_tc_t {
- uint8_t servo_id; /*< A member of the ServosList enum*/
-} mavlink_servo_tm_request_tc_t;
-
-#define MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN 1
-#define MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_5_LEN 1
-#define MAVLINK_MSG_ID_5_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC 184
-#define MAVLINK_MSG_ID_5_CRC 184
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC { \
- 5, \
- "SERVO_TM_REQUEST_TC", \
- 1, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_servo_tm_request_tc_t, servo_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC { \
- "SERVO_TM_REQUEST_TC", \
- 1, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_servo_tm_request_tc_t, servo_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a servo_tm_request_tc 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 servo_id A member of the ServosList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_servo_tm_request_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN);
-#else
- mavlink_servo_tm_request_tc_t packet;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Pack a servo_tm_request_tc 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 servo_id A member of the ServosList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_servo_tm_request_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN);
-#else
- mavlink_servo_tm_request_tc_t packet;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Encode a servo_tm_request_tc 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_tm_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_servo_tm_request_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_servo_tm_request_tc_t* servo_tm_request_tc)
-{
- return mavlink_msg_servo_tm_request_tc_pack(system_id, component_id, msg, servo_tm_request_tc->servo_id);
-}
-
-/**
- * @brief Encode a servo_tm_request_tc 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_tm_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_servo_tm_request_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_servo_tm_request_tc_t* servo_tm_request_tc)
-{
- return mavlink_msg_servo_tm_request_tc_pack_chan(system_id, component_id, chan, msg, servo_tm_request_tc->servo_id);
-}
-
-/**
- * @brief Send a servo_tm_request_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param servo_id A member of the ServosList enum
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_servo_tm_request_tc_send(mavlink_channel_t chan, uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC, buf, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-#else
- mavlink_servo_tm_request_tc_t packet;
- packet.servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC, (const char *)&packet, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a servo_tm_request_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_servo_tm_request_tc_send_struct(mavlink_channel_t chan, const mavlink_servo_tm_request_tc_t* servo_tm_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_servo_tm_request_tc_send(chan, servo_tm_request_tc->servo_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC, (const char *)servo_tm_request_tc, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_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_tm_request_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC, buf, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-#else
- mavlink_servo_tm_request_tc_t *packet = (mavlink_servo_tm_request_tc_t *)msgbuf;
- packet->servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC, (const char *)packet, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SERVO_TM_REQUEST_TC UNPACKING
-
-
-/**
- * @brief Get field servo_id from servo_tm_request_tc message
- *
- * @return A member of the ServosList enum
- */
-static inline uint8_t mavlink_msg_servo_tm_request_tc_get_servo_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a servo_tm_request_tc message into a struct
- *
- * @param msg The message to decode
- * @param servo_tm_request_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_servo_tm_request_tc_decode(const mavlink_message_t* msg, mavlink_servo_tm_request_tc_t* servo_tm_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- servo_tm_request_tc->servo_id = mavlink_msg_servo_tm_request_tc_get_servo_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN? msg->len : MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN;
- memset(servo_tm_request_tc, 0, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN);
- memcpy(servo_tm_request_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_set_algorithm_tc.h b/mavlink_lib/gemini/mavlink_msg_set_algorithm_tc.h
deleted file mode 100644
index 68de47900b54c4ba2dd2d8243250d5a1474d57e2..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_set_algorithm_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SET_ALGORITHM_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_ALGORITHM_TC 16
-
-
-typedef struct __mavlink_set_algorithm_tc_t {
- uint8_t algorithm_number; /*< Algorithm number*/
-} mavlink_set_algorithm_tc_t;
-
-#define MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN 1
-#define MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_16_LEN 1
-#define MAVLINK_MSG_ID_16_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC 181
-#define MAVLINK_MSG_ID_16_CRC 181
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC { \
- 16, \
- "SET_ALGORITHM_TC", \
- 1, \
- { { "algorithm_number", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_algorithm_tc_t, algorithm_number) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC { \
- "SET_ALGORITHM_TC", \
- 1, \
- { { "algorithm_number", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_algorithm_tc_t, algorithm_number) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_algorithm_tc 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 algorithm_number Algorithm number
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_algorithm_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t algorithm_number)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN];
- _mav_put_uint8_t(buf, 0, algorithm_number);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN);
-#else
- mavlink_set_algorithm_tc_t packet;
- packet.algorithm_number = algorithm_number;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_ALGORITHM_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-}
-
-/**
- * @brief Pack a set_algorithm_tc 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 algorithm_number Algorithm number
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_algorithm_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t algorithm_number)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN];
- _mav_put_uint8_t(buf, 0, algorithm_number);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN);
-#else
- mavlink_set_algorithm_tc_t packet;
- packet.algorithm_number = algorithm_number;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_ALGORITHM_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-}
-
-/**
- * @brief Encode a set_algorithm_tc 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_algorithm_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_algorithm_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_algorithm_tc_t* set_algorithm_tc)
-{
- return mavlink_msg_set_algorithm_tc_pack(system_id, component_id, msg, set_algorithm_tc->algorithm_number);
-}
-
-/**
- * @brief Encode a set_algorithm_tc 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_algorithm_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_algorithm_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_algorithm_tc_t* set_algorithm_tc)
-{
- return mavlink_msg_set_algorithm_tc_pack_chan(system_id, component_id, chan, msg, set_algorithm_tc->algorithm_number);
-}
-
-/**
- * @brief Send a set_algorithm_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param algorithm_number Algorithm number
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_algorithm_tc_send(mavlink_channel_t chan, uint8_t algorithm_number)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN];
- _mav_put_uint8_t(buf, 0, algorithm_number);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ALGORITHM_TC, buf, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-#else
- mavlink_set_algorithm_tc_t packet;
- packet.algorithm_number = algorithm_number;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ALGORITHM_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_algorithm_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_algorithm_tc_send_struct(mavlink_channel_t chan, const mavlink_set_algorithm_tc_t* set_algorithm_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_algorithm_tc_send(chan, set_algorithm_tc->algorithm_number);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ALGORITHM_TC, (const char *)set_algorithm_tc, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_ALGORITHM_TC_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_algorithm_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t algorithm_number)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, algorithm_number);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ALGORITHM_TC, buf, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-#else
- mavlink_set_algorithm_tc_t *packet = (mavlink_set_algorithm_tc_t *)msgbuf;
- packet->algorithm_number = algorithm_number;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ALGORITHM_TC, (const char *)packet, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_ALGORITHM_TC UNPACKING
-
-
-/**
- * @brief Get field algorithm_number from set_algorithm_tc message
- *
- * @return Algorithm number
- */
-static inline uint8_t mavlink_msg_set_algorithm_tc_get_algorithm_number(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a set_algorithm_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_algorithm_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_algorithm_tc_decode(const mavlink_message_t* msg, mavlink_set_algorithm_tc_t* set_algorithm_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_algorithm_tc->algorithm_number = mavlink_msg_set_algorithm_tc_get_algorithm_number(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN;
- memset(set_algorithm_tc, 0, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN);
- memcpy(set_algorithm_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_set_atomic_valve_timing_tc.h b/mavlink_lib/gemini/mavlink_msg_set_atomic_valve_timing_tc.h
deleted file mode 100644
index 767be290e5f5524ce02c1663f7eaedcd12a5a34f..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_set_atomic_valve_timing_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SET_ATOMIC_VALVE_TIMING_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC 17
-
-
-typedef struct __mavlink_set_atomic_valve_timing_tc_t {
- uint32_t maximum_timing; /*< [ms] Maximum timing in [ms]*/
- uint8_t servo_id; /*< A member of the ServosList enum*/
-} mavlink_set_atomic_valve_timing_tc_t;
-
-#define MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN 5
-#define MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN 5
-#define MAVLINK_MSG_ID_17_LEN 5
-#define MAVLINK_MSG_ID_17_MIN_LEN 5
-
-#define MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_CRC 110
-#define MAVLINK_MSG_ID_17_CRC 110
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_ATOMIC_VALVE_TIMING_TC { \
- 17, \
- "SET_ATOMIC_VALVE_TIMING_TC", \
- 2, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_atomic_valve_timing_tc_t, servo_id) }, \
- { "maximum_timing", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_atomic_valve_timing_tc_t, maximum_timing) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_ATOMIC_VALVE_TIMING_TC { \
- "SET_ATOMIC_VALVE_TIMING_TC", \
- 2, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_atomic_valve_timing_tc_t, servo_id) }, \
- { "maximum_timing", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_atomic_valve_timing_tc_t, maximum_timing) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_atomic_valve_timing_tc 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 servo_id A member of the ServosList enum
- * @param maximum_timing [ms] Maximum timing in [ms]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_atomic_valve_timing_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t servo_id, uint32_t maximum_timing)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN];
- _mav_put_uint32_t(buf, 0, maximum_timing);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN);
-#else
- mavlink_set_atomic_valve_timing_tc_t packet;
- packet.maximum_timing = maximum_timing;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_CRC);
-}
-
-/**
- * @brief Pack a set_atomic_valve_timing_tc 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 servo_id A member of the ServosList enum
- * @param maximum_timing [ms] Maximum timing in [ms]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_atomic_valve_timing_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t servo_id,uint32_t maximum_timing)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN];
- _mav_put_uint32_t(buf, 0, maximum_timing);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN);
-#else
- mavlink_set_atomic_valve_timing_tc_t packet;
- packet.maximum_timing = maximum_timing;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_CRC);
-}
-
-/**
- * @brief Encode a set_atomic_valve_timing_tc 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_atomic_valve_timing_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_atomic_valve_timing_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_atomic_valve_timing_tc_t* set_atomic_valve_timing_tc)
-{
- return mavlink_msg_set_atomic_valve_timing_tc_pack(system_id, component_id, msg, set_atomic_valve_timing_tc->servo_id, set_atomic_valve_timing_tc->maximum_timing);
-}
-
-/**
- * @brief Encode a set_atomic_valve_timing_tc 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_atomic_valve_timing_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_atomic_valve_timing_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_atomic_valve_timing_tc_t* set_atomic_valve_timing_tc)
-{
- return mavlink_msg_set_atomic_valve_timing_tc_pack_chan(system_id, component_id, chan, msg, set_atomic_valve_timing_tc->servo_id, set_atomic_valve_timing_tc->maximum_timing);
-}
-
-/**
- * @brief Send a set_atomic_valve_timing_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param servo_id A member of the ServosList enum
- * @param maximum_timing [ms] Maximum timing in [ms]
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_atomic_valve_timing_tc_send(mavlink_channel_t chan, uint8_t servo_id, uint32_t maximum_timing)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN];
- _mav_put_uint32_t(buf, 0, maximum_timing);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC, buf, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_CRC);
-#else
- mavlink_set_atomic_valve_timing_tc_t packet;
- packet.maximum_timing = maximum_timing;
- packet.servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_atomic_valve_timing_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_atomic_valve_timing_tc_send_struct(mavlink_channel_t chan, const mavlink_set_atomic_valve_timing_tc_t* set_atomic_valve_timing_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_atomic_valve_timing_tc_send(chan, set_atomic_valve_timing_tc->servo_id, set_atomic_valve_timing_tc->maximum_timing);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC, (const char *)set_atomic_valve_timing_tc, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_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_atomic_valve_timing_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t servo_id, uint32_t maximum_timing)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint32_t(buf, 0, maximum_timing);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC, buf, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_CRC);
-#else
- mavlink_set_atomic_valve_timing_tc_t *packet = (mavlink_set_atomic_valve_timing_tc_t *)msgbuf;
- packet->maximum_timing = maximum_timing;
- packet->servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC, (const char *)packet, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_ATOMIC_VALVE_TIMING_TC UNPACKING
-
-
-/**
- * @brief Get field servo_id from set_atomic_valve_timing_tc message
- *
- * @return A member of the ServosList enum
- */
-static inline uint8_t mavlink_msg_set_atomic_valve_timing_tc_get_servo_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 4);
-}
-
-/**
- * @brief Get field maximum_timing from set_atomic_valve_timing_tc message
- *
- * @return [ms] Maximum timing in [ms]
- */
-static inline uint32_t mavlink_msg_set_atomic_valve_timing_tc_get_maximum_timing(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 0);
-}
-
-/**
- * @brief Decode a set_atomic_valve_timing_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_atomic_valve_timing_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_atomic_valve_timing_tc_decode(const mavlink_message_t* msg, mavlink_set_atomic_valve_timing_tc_t* set_atomic_valve_timing_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_atomic_valve_timing_tc->maximum_timing = mavlink_msg_set_atomic_valve_timing_tc_get_maximum_timing(msg);
- set_atomic_valve_timing_tc->servo_id = mavlink_msg_set_atomic_valve_timing_tc_get_servo_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN;
- memset(set_atomic_valve_timing_tc, 0, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN);
- memcpy(set_atomic_valve_timing_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_set_coordinates_tc.h b/mavlink_lib/gemini/mavlink_msg_set_coordinates_tc.h
deleted file mode 100644
index 827f0ec42e8f8ca2cc283732f06ebc1f9a966af0..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_set_coordinates_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SET_COORDINATES_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_COORDINATES_TC 12
-
-
-typedef struct __mavlink_set_coordinates_tc_t {
- float latitude; /*< [deg] Latitude*/
- float longitude; /*< [deg] Longitude*/
-} mavlink_set_coordinates_tc_t;
-
-#define MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN 8
-#define MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_12_LEN 8
-#define MAVLINK_MSG_ID_12_MIN_LEN 8
-
-#define MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC 67
-#define MAVLINK_MSG_ID_12_CRC 67
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC { \
- 12, \
- "SET_COORDINATES_TC", \
- 2, \
- { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_coordinates_tc_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_coordinates_tc_t, longitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC { \
- "SET_COORDINATES_TC", \
- 2, \
- { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_coordinates_tc_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_coordinates_tc_t, longitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_coordinates_tc 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 [deg] Latitude
- * @param longitude [deg] Longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_coordinates_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN);
-#else
- mavlink_set_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_COORDINATES_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-}
-
-/**
- * @brief Pack a set_coordinates_tc 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 [deg] Latitude
- * @param longitude [deg] Longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_coordinates_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float latitude,float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN);
-#else
- mavlink_set_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_COORDINATES_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-}
-
-/**
- * @brief Encode a set_coordinates_tc 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_coordinates_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_coordinates_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_coordinates_tc_t* set_coordinates_tc)
-{
- return mavlink_msg_set_coordinates_tc_pack(system_id, component_id, msg, set_coordinates_tc->latitude, set_coordinates_tc->longitude);
-}
-
-/**
- * @brief Encode a set_coordinates_tc 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_coordinates_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_coordinates_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_coordinates_tc_t* set_coordinates_tc)
-{
- return mavlink_msg_set_coordinates_tc_pack_chan(system_id, component_id, chan, msg, set_coordinates_tc->latitude, set_coordinates_tc->longitude);
-}
-
-/**
- * @brief Send a set_coordinates_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param latitude [deg] Latitude
- * @param longitude [deg] Longitude
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_coordinates_tc_send(mavlink_channel_t chan, float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_COORDINATES_TC, buf, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-#else
- mavlink_set_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_COORDINATES_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_coordinates_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_coordinates_tc_send_struct(mavlink_channel_t chan, const mavlink_set_coordinates_tc_t* set_coordinates_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_coordinates_tc_send(chan, set_coordinates_tc->latitude, set_coordinates_tc->longitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_COORDINATES_TC, (const char *)set_coordinates_tc, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_COORDINATES_TC_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_coordinates_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_COORDINATES_TC, buf, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-#else
- mavlink_set_coordinates_tc_t *packet = (mavlink_set_coordinates_tc_t *)msgbuf;
- packet->latitude = latitude;
- packet->longitude = longitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_COORDINATES_TC, (const char *)packet, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_COORDINATES_TC UNPACKING
-
-
-/**
- * @brief Get field latitude from set_coordinates_tc message
- *
- * @return [deg] Latitude
- */
-static inline float mavlink_msg_set_coordinates_tc_get_latitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Get field longitude from set_coordinates_tc message
- *
- * @return [deg] Longitude
- */
-static inline float mavlink_msg_set_coordinates_tc_get_longitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 4);
-}
-
-/**
- * @brief Decode a set_coordinates_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_coordinates_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_coordinates_tc_decode(const mavlink_message_t* msg, mavlink_set_coordinates_tc_t* set_coordinates_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_coordinates_tc->latitude = mavlink_msg_set_coordinates_tc_get_latitude(msg);
- set_coordinates_tc->longitude = mavlink_msg_set_coordinates_tc_get_longitude(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN;
- memset(set_coordinates_tc, 0, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN);
- memcpy(set_coordinates_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_set_deployment_altitude_tc.h b/mavlink_lib/gemini/mavlink_msg_set_deployment_altitude_tc.h
deleted file mode 100644
index 38c61267d4498fb5f1924eaf8a83b701d0d37677..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_set_deployment_altitude_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SET_DEPLOYMENT_ALTITUDE_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC 14
-
-
-typedef struct __mavlink_set_deployment_altitude_tc_t {
- float dpl_altitude; /*< [m] Deployment altitude*/
-} mavlink_set_deployment_altitude_tc_t;
-
-#define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN 4
-#define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN 4
-#define MAVLINK_MSG_ID_14_LEN 4
-#define MAVLINK_MSG_ID_14_MIN_LEN 4
-
-#define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC 44
-#define MAVLINK_MSG_ID_14_CRC 44
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC { \
- 14, \
- "SET_DEPLOYMENT_ALTITUDE_TC", \
- 1, \
- { { "dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_deployment_altitude_tc_t, dpl_altitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC { \
- "SET_DEPLOYMENT_ALTITUDE_TC", \
- 1, \
- { { "dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_deployment_altitude_tc_t, dpl_altitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_deployment_altitude_tc 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 dpl_altitude [m] Deployment altitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_deployment_altitude_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, dpl_altitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
-#else
- mavlink_set_deployment_altitude_tc_t packet;
- packet.dpl_altitude = dpl_altitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-}
-
-/**
- * @brief Pack a set_deployment_altitude_tc 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 dpl_altitude [m] Deployment altitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_deployment_altitude_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, dpl_altitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
-#else
- mavlink_set_deployment_altitude_tc_t packet;
- packet.dpl_altitude = dpl_altitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-}
-
-/**
- * @brief Encode a set_deployment_altitude_tc 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_deployment_altitude_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_deployment_altitude_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_deployment_altitude_tc_t* set_deployment_altitude_tc)
-{
- return mavlink_msg_set_deployment_altitude_tc_pack(system_id, component_id, msg, set_deployment_altitude_tc->dpl_altitude);
-}
-
-/**
- * @brief Encode a set_deployment_altitude_tc 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_deployment_altitude_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_deployment_altitude_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_deployment_altitude_tc_t* set_deployment_altitude_tc)
-{
- return mavlink_msg_set_deployment_altitude_tc_pack_chan(system_id, component_id, chan, msg, set_deployment_altitude_tc->dpl_altitude);
-}
-
-/**
- * @brief Send a set_deployment_altitude_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param dpl_altitude [m] Deployment altitude
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_deployment_altitude_tc_send(mavlink_channel_t chan, float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, dpl_altitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC, buf, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-#else
- mavlink_set_deployment_altitude_tc_t packet;
- packet.dpl_altitude = dpl_altitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_deployment_altitude_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_deployment_altitude_tc_send_struct(mavlink_channel_t chan, const mavlink_set_deployment_altitude_tc_t* set_deployment_altitude_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_deployment_altitude_tc_send(chan, set_deployment_altitude_tc->dpl_altitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC, (const char *)set_deployment_altitude_tc, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_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_deployment_altitude_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, dpl_altitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC, buf, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-#else
- mavlink_set_deployment_altitude_tc_t *packet = (mavlink_set_deployment_altitude_tc_t *)msgbuf;
- packet->dpl_altitude = dpl_altitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC, (const char *)packet, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_DEPLOYMENT_ALTITUDE_TC UNPACKING
-
-
-/**
- * @brief Get field dpl_altitude from set_deployment_altitude_tc message
- *
- * @return [m] Deployment altitude
- */
-static inline float mavlink_msg_set_deployment_altitude_tc_get_dpl_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a set_deployment_altitude_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_deployment_altitude_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_deployment_altitude_tc_decode(const mavlink_message_t* msg, mavlink_set_deployment_altitude_tc_t* set_deployment_altitude_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_deployment_altitude_tc->dpl_altitude = mavlink_msg_set_deployment_altitude_tc_get_dpl_altitude(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN;
- memset(set_deployment_altitude_tc, 0, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
- memcpy(set_deployment_altitude_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_set_ignition_time_tc.h b/mavlink_lib/gemini/mavlink_msg_set_ignition_time_tc.h
deleted file mode 100644
index 8ca91d61d9f9331adcf84943b20765cc5b65bc74..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_set_ignition_time_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SET_IGNITION_TIME_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_IGNITION_TIME_TC 20
-
-
-typedef struct __mavlink_set_ignition_time_tc_t {
- uint32_t timing; /*< [ms] Timing in [ms]*/
-} mavlink_set_ignition_time_tc_t;
-
-#define MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN 4
-#define MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN 4
-#define MAVLINK_MSG_ID_20_LEN 4
-#define MAVLINK_MSG_ID_20_MIN_LEN 4
-
-#define MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC 79
-#define MAVLINK_MSG_ID_20_CRC 79
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC { \
- 20, \
- "SET_IGNITION_TIME_TC", \
- 1, \
- { { "timing", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_ignition_time_tc_t, timing) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC { \
- "SET_IGNITION_TIME_TC", \
- 1, \
- { { "timing", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_ignition_time_tc_t, timing) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_ignition_time_tc 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 timing [ms] Timing in [ms]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_ignition_time_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint32_t timing)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN];
- _mav_put_uint32_t(buf, 0, timing);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN);
-#else
- mavlink_set_ignition_time_tc_t packet;
- packet.timing = timing;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_IGNITION_TIME_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC);
-}
-
-/**
- * @brief Pack a set_ignition_time_tc 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 timing [ms] Timing in [ms]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_ignition_time_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint32_t timing)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN];
- _mav_put_uint32_t(buf, 0, timing);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN);
-#else
- mavlink_set_ignition_time_tc_t packet;
- packet.timing = timing;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_IGNITION_TIME_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC);
-}
-
-/**
- * @brief Encode a set_ignition_time_tc 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_ignition_time_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_ignition_time_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_ignition_time_tc_t* set_ignition_time_tc)
-{
- return mavlink_msg_set_ignition_time_tc_pack(system_id, component_id, msg, set_ignition_time_tc->timing);
-}
-
-/**
- * @brief Encode a set_ignition_time_tc 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_ignition_time_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_ignition_time_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_ignition_time_tc_t* set_ignition_time_tc)
-{
- return mavlink_msg_set_ignition_time_tc_pack_chan(system_id, component_id, chan, msg, set_ignition_time_tc->timing);
-}
-
-/**
- * @brief Send a set_ignition_time_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param timing [ms] Timing in [ms]
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_ignition_time_tc_send(mavlink_channel_t chan, uint32_t timing)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN];
- _mav_put_uint32_t(buf, 0, timing);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC, buf, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC);
-#else
- mavlink_set_ignition_time_tc_t packet;
- packet.timing = timing;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_ignition_time_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_ignition_time_tc_send_struct(mavlink_channel_t chan, const mavlink_set_ignition_time_tc_t* set_ignition_time_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_ignition_time_tc_send(chan, set_ignition_time_tc->timing);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC, (const char *)set_ignition_time_tc, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_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_ignition_time_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t timing)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint32_t(buf, 0, timing);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC, buf, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC);
-#else
- mavlink_set_ignition_time_tc_t *packet = (mavlink_set_ignition_time_tc_t *)msgbuf;
- packet->timing = timing;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC, (const char *)packet, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_IGNITION_TIME_TC UNPACKING
-
-
-/**
- * @brief Get field timing from set_ignition_time_tc message
- *
- * @return [ms] Timing in [ms]
- */
-static inline uint32_t mavlink_msg_set_ignition_time_tc_get_timing(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 0);
-}
-
-/**
- * @brief Decode a set_ignition_time_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_ignition_time_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_ignition_time_tc_decode(const mavlink_message_t* msg, mavlink_set_ignition_time_tc_t* set_ignition_time_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_ignition_time_tc->timing = mavlink_msg_set_ignition_time_tc_get_timing(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN;
- memset(set_ignition_time_tc, 0, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN);
- memcpy(set_ignition_time_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_set_orientation_tc.h b/mavlink_lib/gemini/mavlink_msg_set_orientation_tc.h
deleted file mode 100644
index 5169814cd4c7a7afbe6e204bf82fb2d049078fc7..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_set_orientation_tc.h
+++ /dev/null
@@ -1,263 +0,0 @@
-#pragma once
-// MESSAGE SET_ORIENTATION_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_ORIENTATION_TC 11
-
-
-typedef struct __mavlink_set_orientation_tc_t {
- float yaw; /*< [deg] Yaw angle*/
- float pitch; /*< [deg] Pitch angle*/
- float roll; /*< [deg] Roll angle*/
-} mavlink_set_orientation_tc_t;
-
-#define MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN 12
-#define MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN 12
-#define MAVLINK_MSG_ID_11_LEN 12
-#define MAVLINK_MSG_ID_11_MIN_LEN 12
-
-#define MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC 71
-#define MAVLINK_MSG_ID_11_CRC 71
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC { \
- 11, \
- "SET_ORIENTATION_TC", \
- 3, \
- { { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_orientation_tc_t, yaw) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_orientation_tc_t, pitch) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_orientation_tc_t, roll) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC { \
- "SET_ORIENTATION_TC", \
- 3, \
- { { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_orientation_tc_t, yaw) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_orientation_tc_t, pitch) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_orientation_tc_t, roll) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_orientation_tc 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 yaw [deg] Yaw angle
- * @param pitch [deg] Pitch angle
- * @param roll [deg] Roll angle
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_orientation_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float yaw, float pitch, float roll)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN];
- _mav_put_float(buf, 0, yaw);
- _mav_put_float(buf, 4, pitch);
- _mav_put_float(buf, 8, roll);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN);
-#else
- mavlink_set_orientation_tc_t packet;
- packet.yaw = yaw;
- packet.pitch = pitch;
- packet.roll = roll;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_ORIENTATION_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-}
-
-/**
- * @brief Pack a set_orientation_tc 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 yaw [deg] Yaw angle
- * @param pitch [deg] Pitch angle
- * @param roll [deg] Roll angle
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_orientation_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float yaw,float pitch,float roll)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN];
- _mav_put_float(buf, 0, yaw);
- _mav_put_float(buf, 4, pitch);
- _mav_put_float(buf, 8, roll);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN);
-#else
- mavlink_set_orientation_tc_t packet;
- packet.yaw = yaw;
- packet.pitch = pitch;
- packet.roll = roll;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_ORIENTATION_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-}
-
-/**
- * @brief Encode a set_orientation_tc 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_orientation_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_orientation_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_orientation_tc_t* set_orientation_tc)
-{
- return mavlink_msg_set_orientation_tc_pack(system_id, component_id, msg, set_orientation_tc->yaw, set_orientation_tc->pitch, set_orientation_tc->roll);
-}
-
-/**
- * @brief Encode a set_orientation_tc 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_orientation_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_orientation_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_orientation_tc_t* set_orientation_tc)
-{
- return mavlink_msg_set_orientation_tc_pack_chan(system_id, component_id, chan, msg, set_orientation_tc->yaw, set_orientation_tc->pitch, set_orientation_tc->roll);
-}
-
-/**
- * @brief Send a set_orientation_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param yaw [deg] Yaw angle
- * @param pitch [deg] Pitch angle
- * @param roll [deg] Roll angle
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_orientation_tc_send(mavlink_channel_t chan, float yaw, float pitch, float roll)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN];
- _mav_put_float(buf, 0, yaw);
- _mav_put_float(buf, 4, pitch);
- _mav_put_float(buf, 8, roll);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ORIENTATION_TC, buf, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-#else
- mavlink_set_orientation_tc_t packet;
- packet.yaw = yaw;
- packet.pitch = pitch;
- packet.roll = roll;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ORIENTATION_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_orientation_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_orientation_tc_send_struct(mavlink_channel_t chan, const mavlink_set_orientation_tc_t* set_orientation_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_orientation_tc_send(chan, set_orientation_tc->yaw, set_orientation_tc->pitch, set_orientation_tc->roll);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ORIENTATION_TC, (const char *)set_orientation_tc, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_ORIENTATION_TC_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_orientation_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float yaw, float pitch, float roll)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, yaw);
- _mav_put_float(buf, 4, pitch);
- _mav_put_float(buf, 8, roll);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ORIENTATION_TC, buf, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-#else
- mavlink_set_orientation_tc_t *packet = (mavlink_set_orientation_tc_t *)msgbuf;
- packet->yaw = yaw;
- packet->pitch = pitch;
- packet->roll = roll;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ORIENTATION_TC, (const char *)packet, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_ORIENTATION_TC UNPACKING
-
-
-/**
- * @brief Get field yaw from set_orientation_tc message
- *
- * @return [deg] Yaw angle
- */
-static inline float mavlink_msg_set_orientation_tc_get_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Get field pitch from set_orientation_tc message
- *
- * @return [deg] Pitch angle
- */
-static inline float mavlink_msg_set_orientation_tc_get_pitch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 4);
-}
-
-/**
- * @brief Get field roll from set_orientation_tc message
- *
- * @return [deg] Roll angle
- */
-static inline float mavlink_msg_set_orientation_tc_get_roll(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Decode a set_orientation_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_orientation_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_orientation_tc_decode(const mavlink_message_t* msg, mavlink_set_orientation_tc_t* set_orientation_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_orientation_tc->yaw = mavlink_msg_set_orientation_tc_get_yaw(msg);
- set_orientation_tc->pitch = mavlink_msg_set_orientation_tc_get_pitch(msg);
- set_orientation_tc->roll = mavlink_msg_set_orientation_tc_get_roll(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN;
- memset(set_orientation_tc, 0, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN);
- memcpy(set_orientation_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_set_reference_altitude_tc.h b/mavlink_lib/gemini/mavlink_msg_set_reference_altitude_tc.h
deleted file mode 100644
index a291b0b8da0d1d60e7e30767ade22abc5f35402a..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_set_reference_altitude_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SET_REFERENCE_ALTITUDE_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC 9
-
-
-typedef struct __mavlink_set_reference_altitude_tc_t {
- float ref_altitude; /*< [m] Reference altitude*/
-} mavlink_set_reference_altitude_tc_t;
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN 4
-#define MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN 4
-#define MAVLINK_MSG_ID_9_LEN 4
-#define MAVLINK_MSG_ID_9_MIN_LEN 4
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC 113
-#define MAVLINK_MSG_ID_9_CRC 113
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC { \
- 9, \
- "SET_REFERENCE_ALTITUDE_TC", \
- 1, \
- { { "ref_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_reference_altitude_tc_t, ref_altitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC { \
- "SET_REFERENCE_ALTITUDE_TC", \
- 1, \
- { { "ref_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_reference_altitude_tc_t, ref_altitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_reference_altitude_tc 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 ref_altitude [m] Reference altitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_reference_altitude_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float ref_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, ref_altitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN);
-#else
- mavlink_set_reference_altitude_tc_t packet;
- packet.ref_altitude = ref_altitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-}
-
-/**
- * @brief Pack a set_reference_altitude_tc 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 ref_altitude [m] Reference altitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_reference_altitude_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float ref_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, ref_altitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN);
-#else
- mavlink_set_reference_altitude_tc_t packet;
- packet.ref_altitude = ref_altitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-}
-
-/**
- * @brief Encode a set_reference_altitude_tc 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_reference_altitude_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_reference_altitude_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_reference_altitude_tc_t* set_reference_altitude_tc)
-{
- return mavlink_msg_set_reference_altitude_tc_pack(system_id, component_id, msg, set_reference_altitude_tc->ref_altitude);
-}
-
-/**
- * @brief Encode a set_reference_altitude_tc 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_reference_altitude_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_reference_altitude_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_reference_altitude_tc_t* set_reference_altitude_tc)
-{
- return mavlink_msg_set_reference_altitude_tc_pack_chan(system_id, component_id, chan, msg, set_reference_altitude_tc->ref_altitude);
-}
-
-/**
- * @brief Send a set_reference_altitude_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param ref_altitude [m] Reference altitude
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_reference_altitude_tc_send(mavlink_channel_t chan, float ref_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, ref_altitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC, buf, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-#else
- mavlink_set_reference_altitude_tc_t packet;
- packet.ref_altitude = ref_altitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_reference_altitude_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_reference_altitude_tc_send_struct(mavlink_channel_t chan, const mavlink_set_reference_altitude_tc_t* set_reference_altitude_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_reference_altitude_tc_send(chan, set_reference_altitude_tc->ref_altitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC, (const char *)set_reference_altitude_tc, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_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_reference_altitude_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float ref_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, ref_altitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC, buf, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-#else
- mavlink_set_reference_altitude_tc_t *packet = (mavlink_set_reference_altitude_tc_t *)msgbuf;
- packet->ref_altitude = ref_altitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC, (const char *)packet, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_REFERENCE_ALTITUDE_TC UNPACKING
-
-
-/**
- * @brief Get field ref_altitude from set_reference_altitude_tc message
- *
- * @return [m] Reference altitude
- */
-static inline float mavlink_msg_set_reference_altitude_tc_get_ref_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a set_reference_altitude_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_reference_altitude_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_reference_altitude_tc_decode(const mavlink_message_t* msg, mavlink_set_reference_altitude_tc_t* set_reference_altitude_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_reference_altitude_tc->ref_altitude = mavlink_msg_set_reference_altitude_tc_get_ref_altitude(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN;
- memset(set_reference_altitude_tc, 0, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN);
- memcpy(set_reference_altitude_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_set_reference_temperature_tc.h b/mavlink_lib/gemini/mavlink_msg_set_reference_temperature_tc.h
deleted file mode 100644
index 5bb1c529477606617b93eca65726e9580259f832..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_set_reference_temperature_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SET_REFERENCE_TEMPERATURE_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC 10
-
-
-typedef struct __mavlink_set_reference_temperature_tc_t {
- float ref_temp; /*< [degC] Reference temperature*/
-} mavlink_set_reference_temperature_tc_t;
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN 4
-#define MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN 4
-#define MAVLINK_MSG_ID_10_LEN 4
-#define MAVLINK_MSG_ID_10_MIN_LEN 4
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC 38
-#define MAVLINK_MSG_ID_10_CRC 38
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC { \
- 10, \
- "SET_REFERENCE_TEMPERATURE_TC", \
- 1, \
- { { "ref_temp", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_reference_temperature_tc_t, ref_temp) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC { \
- "SET_REFERENCE_TEMPERATURE_TC", \
- 1, \
- { { "ref_temp", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_reference_temperature_tc_t, ref_temp) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_reference_temperature_tc 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 ref_temp [degC] Reference temperature
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_reference_temperature_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float ref_temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN];
- _mav_put_float(buf, 0, ref_temp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
-#else
- mavlink_set_reference_temperature_tc_t packet;
- packet.ref_temp = ref_temp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-}
-
-/**
- * @brief Pack a set_reference_temperature_tc 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 ref_temp [degC] Reference temperature
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_reference_temperature_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float ref_temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN];
- _mav_put_float(buf, 0, ref_temp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
-#else
- mavlink_set_reference_temperature_tc_t packet;
- packet.ref_temp = ref_temp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-}
-
-/**
- * @brief Encode a set_reference_temperature_tc 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_reference_temperature_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_reference_temperature_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_reference_temperature_tc_t* set_reference_temperature_tc)
-{
- return mavlink_msg_set_reference_temperature_tc_pack(system_id, component_id, msg, set_reference_temperature_tc->ref_temp);
-}
-
-/**
- * @brief Encode a set_reference_temperature_tc 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_reference_temperature_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_reference_temperature_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_reference_temperature_tc_t* set_reference_temperature_tc)
-{
- return mavlink_msg_set_reference_temperature_tc_pack_chan(system_id, component_id, chan, msg, set_reference_temperature_tc->ref_temp);
-}
-
-/**
- * @brief Send a set_reference_temperature_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param ref_temp [degC] Reference temperature
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_reference_temperature_tc_send(mavlink_channel_t chan, float ref_temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN];
- _mav_put_float(buf, 0, ref_temp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC, buf, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-#else
- mavlink_set_reference_temperature_tc_t packet;
- packet.ref_temp = ref_temp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_reference_temperature_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_reference_temperature_tc_send_struct(mavlink_channel_t chan, const mavlink_set_reference_temperature_tc_t* set_reference_temperature_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_reference_temperature_tc_send(chan, set_reference_temperature_tc->ref_temp);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC, (const char *)set_reference_temperature_tc, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_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_reference_temperature_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float ref_temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, ref_temp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC, buf, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-#else
- mavlink_set_reference_temperature_tc_t *packet = (mavlink_set_reference_temperature_tc_t *)msgbuf;
- packet->ref_temp = ref_temp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC, (const char *)packet, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_REFERENCE_TEMPERATURE_TC UNPACKING
-
-
-/**
- * @brief Get field ref_temp from set_reference_temperature_tc message
- *
- * @return [degC] Reference temperature
- */
-static inline float mavlink_msg_set_reference_temperature_tc_get_ref_temp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a set_reference_temperature_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_reference_temperature_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_reference_temperature_tc_decode(const mavlink_message_t* msg, mavlink_set_reference_temperature_tc_t* set_reference_temperature_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_reference_temperature_tc->ref_temp = mavlink_msg_set_reference_temperature_tc_get_ref_temp(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN;
- memset(set_reference_temperature_tc, 0, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
- memcpy(set_reference_temperature_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_set_servo_angle_tc.h b/mavlink_lib/gemini/mavlink_msg_set_servo_angle_tc.h
deleted file mode 100644
index 74f2888721a7ed79d479df991d640deb064d50cc..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_set_servo_angle_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SET_SERVO_ANGLE_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC 6
-
-
-typedef struct __mavlink_set_servo_angle_tc_t {
- float angle; /*< Servo angle in normalized value [0-1]*/
- uint8_t servo_id; /*< A member of the ServosList enum*/
-} mavlink_set_servo_angle_tc_t;
-
-#define MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN 5
-#define MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN 5
-#define MAVLINK_MSG_ID_6_LEN 5
-#define MAVLINK_MSG_ID_6_MIN_LEN 5
-
-#define MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC 215
-#define MAVLINK_MSG_ID_6_CRC 215
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC { \
- 6, \
- "SET_SERVO_ANGLE_TC", \
- 2, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_servo_angle_tc_t, servo_id) }, \
- { "angle", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_servo_angle_tc_t, angle) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC { \
- "SET_SERVO_ANGLE_TC", \
- 2, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_servo_angle_tc_t, servo_id) }, \
- { "angle", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_servo_angle_tc_t, angle) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_servo_angle_tc 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 servo_id A member of the ServosList enum
- * @param angle Servo angle in normalized value [0-1]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_servo_angle_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t servo_id, float angle)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN];
- _mav_put_float(buf, 0, angle);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN);
-#else
- mavlink_set_servo_angle_tc_t packet;
- packet.angle = angle;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-}
-
-/**
- * @brief Pack a set_servo_angle_tc 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 servo_id A member of the ServosList enum
- * @param angle Servo angle in normalized value [0-1]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_servo_angle_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t servo_id,float angle)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN];
- _mav_put_float(buf, 0, angle);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN);
-#else
- mavlink_set_servo_angle_tc_t packet;
- packet.angle = angle;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-}
-
-/**
- * @brief Encode a set_servo_angle_tc 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_servo_angle_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_servo_angle_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_servo_angle_tc_t* set_servo_angle_tc)
-{
- return mavlink_msg_set_servo_angle_tc_pack(system_id, component_id, msg, set_servo_angle_tc->servo_id, set_servo_angle_tc->angle);
-}
-
-/**
- * @brief Encode a set_servo_angle_tc 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_servo_angle_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_servo_angle_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_servo_angle_tc_t* set_servo_angle_tc)
-{
- return mavlink_msg_set_servo_angle_tc_pack_chan(system_id, component_id, chan, msg, set_servo_angle_tc->servo_id, set_servo_angle_tc->angle);
-}
-
-/**
- * @brief Send a set_servo_angle_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param servo_id A member of the ServosList enum
- * @param angle Servo angle in normalized value [0-1]
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_servo_angle_tc_send(mavlink_channel_t chan, uint8_t servo_id, float angle)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN];
- _mav_put_float(buf, 0, angle);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC, buf, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-#else
- mavlink_set_servo_angle_tc_t packet;
- packet.angle = angle;
- packet.servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_servo_angle_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_servo_angle_tc_send_struct(mavlink_channel_t chan, const mavlink_set_servo_angle_tc_t* set_servo_angle_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_servo_angle_tc_send(chan, set_servo_angle_tc->servo_id, set_servo_angle_tc->angle);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC, (const char *)set_servo_angle_tc, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_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_servo_angle_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t servo_id, float angle)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, angle);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC, buf, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-#else
- mavlink_set_servo_angle_tc_t *packet = (mavlink_set_servo_angle_tc_t *)msgbuf;
- packet->angle = angle;
- packet->servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC, (const char *)packet, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_SERVO_ANGLE_TC UNPACKING
-
-
-/**
- * @brief Get field servo_id from set_servo_angle_tc message
- *
- * @return A member of the ServosList enum
- */
-static inline uint8_t mavlink_msg_set_servo_angle_tc_get_servo_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 4);
-}
-
-/**
- * @brief Get field angle from set_servo_angle_tc message
- *
- * @return Servo angle in normalized value [0-1]
- */
-static inline float mavlink_msg_set_servo_angle_tc_get_angle(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a set_servo_angle_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_servo_angle_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_servo_angle_tc_decode(const mavlink_message_t* msg, mavlink_set_servo_angle_tc_t* set_servo_angle_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_servo_angle_tc->angle = mavlink_msg_set_servo_angle_tc_get_angle(msg);
- set_servo_angle_tc->servo_id = mavlink_msg_set_servo_angle_tc_get_servo_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN;
- memset(set_servo_angle_tc, 0, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN);
- memcpy(set_servo_angle_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_set_target_coordinates_tc.h b/mavlink_lib/gemini/mavlink_msg_set_target_coordinates_tc.h
deleted file mode 100644
index 40394b728f76ebb99dfb689a467c28474a457fee..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_set_target_coordinates_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SET_TARGET_COORDINATES_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC 15
-
-
-typedef struct __mavlink_set_target_coordinates_tc_t {
- float latitude; /*< [deg] Latitude*/
- float longitude; /*< [deg] Longitude*/
-} mavlink_set_target_coordinates_tc_t;
-
-#define MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN 8
-#define MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_15_LEN 8
-#define MAVLINK_MSG_ID_15_MIN_LEN 8
-
-#define MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC 81
-#define MAVLINK_MSG_ID_15_CRC 81
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC { \
- 15, \
- "SET_TARGET_COORDINATES_TC", \
- 2, \
- { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_target_coordinates_tc_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_target_coordinates_tc_t, longitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC { \
- "SET_TARGET_COORDINATES_TC", \
- 2, \
- { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_target_coordinates_tc_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_target_coordinates_tc_t, longitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_target_coordinates_tc 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 [deg] Latitude
- * @param longitude [deg] Longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_target_coordinates_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN);
-#else
- mavlink_set_target_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-}
-
-/**
- * @brief Pack a set_target_coordinates_tc 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 [deg] Latitude
- * @param longitude [deg] Longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_target_coordinates_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float latitude,float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN);
-#else
- mavlink_set_target_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-}
-
-/**
- * @brief Encode a set_target_coordinates_tc 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_target_coordinates_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_target_coordinates_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_target_coordinates_tc_t* set_target_coordinates_tc)
-{
- return mavlink_msg_set_target_coordinates_tc_pack(system_id, component_id, msg, set_target_coordinates_tc->latitude, set_target_coordinates_tc->longitude);
-}
-
-/**
- * @brief Encode a set_target_coordinates_tc 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_target_coordinates_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_target_coordinates_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_target_coordinates_tc_t* set_target_coordinates_tc)
-{
- return mavlink_msg_set_target_coordinates_tc_pack_chan(system_id, component_id, chan, msg, set_target_coordinates_tc->latitude, set_target_coordinates_tc->longitude);
-}
-
-/**
- * @brief Send a set_target_coordinates_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param latitude [deg] Latitude
- * @param longitude [deg] Longitude
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_target_coordinates_tc_send(mavlink_channel_t chan, float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC, buf, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-#else
- mavlink_set_target_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_target_coordinates_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_target_coordinates_tc_send_struct(mavlink_channel_t chan, const mavlink_set_target_coordinates_tc_t* set_target_coordinates_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_target_coordinates_tc_send(chan, set_target_coordinates_tc->latitude, set_target_coordinates_tc->longitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC, (const char *)set_target_coordinates_tc, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_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_target_coordinates_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC, buf, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-#else
- mavlink_set_target_coordinates_tc_t *packet = (mavlink_set_target_coordinates_tc_t *)msgbuf;
- packet->latitude = latitude;
- packet->longitude = longitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC, (const char *)packet, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_TARGET_COORDINATES_TC UNPACKING
-
-
-/**
- * @brief Get field latitude from set_target_coordinates_tc message
- *
- * @return [deg] Latitude
- */
-static inline float mavlink_msg_set_target_coordinates_tc_get_latitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Get field longitude from set_target_coordinates_tc message
- *
- * @return [deg] Longitude
- */
-static inline float mavlink_msg_set_target_coordinates_tc_get_longitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 4);
-}
-
-/**
- * @brief Decode a set_target_coordinates_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_target_coordinates_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_target_coordinates_tc_decode(const mavlink_message_t* msg, mavlink_set_target_coordinates_tc_t* set_target_coordinates_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_target_coordinates_tc->latitude = mavlink_msg_set_target_coordinates_tc_get_latitude(msg);
- set_target_coordinates_tc->longitude = mavlink_msg_set_target_coordinates_tc_get_longitude(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN;
- memset(set_target_coordinates_tc, 0, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN);
- memcpy(set_target_coordinates_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_set_valve_maximum_aperture_tc.h b/mavlink_lib/gemini/mavlink_msg_set_valve_maximum_aperture_tc.h
deleted file mode 100644
index 6c13b3e2c6ec3002dd7dbef75785ae68f89ab5aa..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_set_valve_maximum_aperture_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SET_VALVE_MAXIMUM_APERTURE_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC 18
-
-
-typedef struct __mavlink_set_valve_maximum_aperture_tc_t {
- float maximum_aperture; /*< Maximum aperture*/
- uint8_t servo_id; /*< A member of the ServosList enum*/
-} mavlink_set_valve_maximum_aperture_tc_t;
-
-#define MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN 5
-#define MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN 5
-#define MAVLINK_MSG_ID_18_LEN 5
-#define MAVLINK_MSG_ID_18_MIN_LEN 5
-
-#define MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_CRC 22
-#define MAVLINK_MSG_ID_18_CRC 22
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_VALVE_MAXIMUM_APERTURE_TC { \
- 18, \
- "SET_VALVE_MAXIMUM_APERTURE_TC", \
- 2, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_valve_maximum_aperture_tc_t, servo_id) }, \
- { "maximum_aperture", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_valve_maximum_aperture_tc_t, maximum_aperture) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_VALVE_MAXIMUM_APERTURE_TC { \
- "SET_VALVE_MAXIMUM_APERTURE_TC", \
- 2, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_valve_maximum_aperture_tc_t, servo_id) }, \
- { "maximum_aperture", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_valve_maximum_aperture_tc_t, maximum_aperture) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_valve_maximum_aperture_tc 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 servo_id A member of the ServosList enum
- * @param maximum_aperture Maximum aperture
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_valve_maximum_aperture_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t servo_id, float maximum_aperture)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN];
- _mav_put_float(buf, 0, maximum_aperture);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN);
-#else
- mavlink_set_valve_maximum_aperture_tc_t packet;
- packet.maximum_aperture = maximum_aperture;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_CRC);
-}
-
-/**
- * @brief Pack a set_valve_maximum_aperture_tc 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 servo_id A member of the ServosList enum
- * @param maximum_aperture Maximum aperture
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_valve_maximum_aperture_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t servo_id,float maximum_aperture)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN];
- _mav_put_float(buf, 0, maximum_aperture);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN);
-#else
- mavlink_set_valve_maximum_aperture_tc_t packet;
- packet.maximum_aperture = maximum_aperture;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_CRC);
-}
-
-/**
- * @brief Encode a set_valve_maximum_aperture_tc 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_valve_maximum_aperture_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_valve_maximum_aperture_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_valve_maximum_aperture_tc_t* set_valve_maximum_aperture_tc)
-{
- return mavlink_msg_set_valve_maximum_aperture_tc_pack(system_id, component_id, msg, set_valve_maximum_aperture_tc->servo_id, set_valve_maximum_aperture_tc->maximum_aperture);
-}
-
-/**
- * @brief Encode a set_valve_maximum_aperture_tc 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_valve_maximum_aperture_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_valve_maximum_aperture_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_valve_maximum_aperture_tc_t* set_valve_maximum_aperture_tc)
-{
- return mavlink_msg_set_valve_maximum_aperture_tc_pack_chan(system_id, component_id, chan, msg, set_valve_maximum_aperture_tc->servo_id, set_valve_maximum_aperture_tc->maximum_aperture);
-}
-
-/**
- * @brief Send a set_valve_maximum_aperture_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param servo_id A member of the ServosList enum
- * @param maximum_aperture Maximum aperture
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_valve_maximum_aperture_tc_send(mavlink_channel_t chan, uint8_t servo_id, float maximum_aperture)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN];
- _mav_put_float(buf, 0, maximum_aperture);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC, buf, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_CRC);
-#else
- mavlink_set_valve_maximum_aperture_tc_t packet;
- packet.maximum_aperture = maximum_aperture;
- packet.servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_valve_maximum_aperture_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_valve_maximum_aperture_tc_send_struct(mavlink_channel_t chan, const mavlink_set_valve_maximum_aperture_tc_t* set_valve_maximum_aperture_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_valve_maximum_aperture_tc_send(chan, set_valve_maximum_aperture_tc->servo_id, set_valve_maximum_aperture_tc->maximum_aperture);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC, (const char *)set_valve_maximum_aperture_tc, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_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_valve_maximum_aperture_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t servo_id, float maximum_aperture)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, maximum_aperture);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC, buf, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_CRC);
-#else
- mavlink_set_valve_maximum_aperture_tc_t *packet = (mavlink_set_valve_maximum_aperture_tc_t *)msgbuf;
- packet->maximum_aperture = maximum_aperture;
- packet->servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC, (const char *)packet, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_VALVE_MAXIMUM_APERTURE_TC UNPACKING
-
-
-/**
- * @brief Get field servo_id from set_valve_maximum_aperture_tc message
- *
- * @return A member of the ServosList enum
- */
-static inline uint8_t mavlink_msg_set_valve_maximum_aperture_tc_get_servo_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 4);
-}
-
-/**
- * @brief Get field maximum_aperture from set_valve_maximum_aperture_tc message
- *
- * @return Maximum aperture
- */
-static inline float mavlink_msg_set_valve_maximum_aperture_tc_get_maximum_aperture(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a set_valve_maximum_aperture_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_valve_maximum_aperture_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_valve_maximum_aperture_tc_decode(const mavlink_message_t* msg, mavlink_set_valve_maximum_aperture_tc_t* set_valve_maximum_aperture_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_valve_maximum_aperture_tc->maximum_aperture = mavlink_msg_set_valve_maximum_aperture_tc_get_maximum_aperture(msg);
- set_valve_maximum_aperture_tc->servo_id = mavlink_msg_set_valve_maximum_aperture_tc_get_servo_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN;
- memset(set_valve_maximum_aperture_tc, 0, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN);
- memcpy(set_valve_maximum_aperture_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_sys_tm.h b/mavlink_lib/gemini/mavlink_msg_sys_tm.h
deleted file mode 100644
index 460e076f05dcf8b83836d80a887f0c77b074c517..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_sys_tm.h
+++ /dev/null
@@ -1,363 +0,0 @@
-#pragma once
-// MESSAGE SYS_TM PACKING
-
-#define MAVLINK_MSG_ID_SYS_TM 200
-
-
-typedef struct __mavlink_sys_tm_t {
- uint64_t timestamp; /*< [us] Timestamp*/
- uint8_t logger; /*< True if the logger started correctly*/
- uint8_t event_broker; /*< True if the event broker started correctly*/
- uint8_t radio; /*< True if the radio started correctly*/
- uint8_t pin_observer; /*< True if the pin observer started correctly*/
- uint8_t sensors; /*< True if the sensors started correctly*/
- uint8_t board_scheduler; /*< True if the board scheduler is running*/
-} mavlink_sys_tm_t;
-
-#define MAVLINK_MSG_ID_SYS_TM_LEN 14
-#define MAVLINK_MSG_ID_SYS_TM_MIN_LEN 14
-#define MAVLINK_MSG_ID_200_LEN 14
-#define MAVLINK_MSG_ID_200_MIN_LEN 14
-
-#define MAVLINK_MSG_ID_SYS_TM_CRC 183
-#define MAVLINK_MSG_ID_200_CRC 183
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SYS_TM { \
- 200, \
- "SYS_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_sys_tm_t, timestamp) }, \
- { "logger", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_sys_tm_t, logger) }, \
- { "event_broker", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_sys_tm_t, event_broker) }, \
- { "radio", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_sys_tm_t, radio) }, \
- { "pin_observer", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_sys_tm_t, pin_observer) }, \
- { "sensors", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_sys_tm_t, sensors) }, \
- { "board_scheduler", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_sys_tm_t, board_scheduler) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SYS_TM { \
- "SYS_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_sys_tm_t, timestamp) }, \
- { "logger", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_sys_tm_t, logger) }, \
- { "event_broker", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_sys_tm_t, event_broker) }, \
- { "radio", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_sys_tm_t, radio) }, \
- { "pin_observer", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_sys_tm_t, pin_observer) }, \
- { "sensors", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_sys_tm_t, sensors) }, \
- { "board_scheduler", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_sys_tm_t, board_scheduler) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a sys_tm 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
- * @param logger True if the logger started correctly
- * @param event_broker True if the event broker started correctly
- * @param radio True if the radio started correctly
- * @param pin_observer True if the pin observer started correctly
- * @param sensors True if the sensors started correctly
- * @param board_scheduler True if the board scheduler is running
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sys_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t logger, uint8_t event_broker, uint8_t radio, uint8_t pin_observer, uint8_t sensors, uint8_t board_scheduler)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, logger);
- _mav_put_uint8_t(buf, 9, event_broker);
- _mav_put_uint8_t(buf, 10, radio);
- _mav_put_uint8_t(buf, 11, pin_observer);
- _mav_put_uint8_t(buf, 12, sensors);
- _mav_put_uint8_t(buf, 13, board_scheduler);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_TM_LEN);
-#else
- mavlink_sys_tm_t packet;
- packet.timestamp = timestamp;
- packet.logger = logger;
- packet.event_broker = event_broker;
- packet.radio = radio;
- packet.pin_observer = pin_observer;
- packet.sensors = sensors;
- packet.board_scheduler = board_scheduler;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SYS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-}
-
-/**
- * @brief Pack a sys_tm 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
- * @param logger True if the logger started correctly
- * @param event_broker True if the event broker started correctly
- * @param radio True if the radio started correctly
- * @param pin_observer True if the pin observer started correctly
- * @param sensors True if the sensors started correctly
- * @param board_scheduler True if the board scheduler is running
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sys_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t logger,uint8_t event_broker,uint8_t radio,uint8_t pin_observer,uint8_t sensors,uint8_t board_scheduler)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, logger);
- _mav_put_uint8_t(buf, 9, event_broker);
- _mav_put_uint8_t(buf, 10, radio);
- _mav_put_uint8_t(buf, 11, pin_observer);
- _mav_put_uint8_t(buf, 12, sensors);
- _mav_put_uint8_t(buf, 13, board_scheduler);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_TM_LEN);
-#else
- mavlink_sys_tm_t packet;
- packet.timestamp = timestamp;
- packet.logger = logger;
- packet.event_broker = event_broker;
- packet.radio = radio;
- packet.pin_observer = pin_observer;
- packet.sensors = sensors;
- packet.board_scheduler = board_scheduler;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SYS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-}
-
-/**
- * @brief Encode a sys_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sys_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_tm_t* sys_tm)
-{
- return mavlink_msg_sys_tm_pack(system_id, component_id, msg, sys_tm->timestamp, sys_tm->logger, sys_tm->event_broker, sys_tm->radio, sys_tm->pin_observer, sys_tm->sensors, sys_tm->board_scheduler);
-}
-
-/**
- * @brief Encode a sys_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sys_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sys_tm_t* sys_tm)
-{
- return mavlink_msg_sys_tm_pack_chan(system_id, component_id, chan, msg, sys_tm->timestamp, sys_tm->logger, sys_tm->event_broker, sys_tm->radio, sys_tm->pin_observer, sys_tm->sensors, sys_tm->board_scheduler);
-}
-
-/**
- * @brief Send a sys_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp
- * @param logger True if the logger started correctly
- * @param event_broker True if the event broker started correctly
- * @param radio True if the radio started correctly
- * @param pin_observer True if the pin observer started correctly
- * @param sensors True if the sensors started correctly
- * @param board_scheduler True if the board scheduler is running
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_sys_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t logger, uint8_t event_broker, uint8_t radio, uint8_t pin_observer, uint8_t sensors, uint8_t board_scheduler)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, logger);
- _mav_put_uint8_t(buf, 9, event_broker);
- _mav_put_uint8_t(buf, 10, radio);
- _mav_put_uint8_t(buf, 11, pin_observer);
- _mav_put_uint8_t(buf, 12, sensors);
- _mav_put_uint8_t(buf, 13, board_scheduler);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, buf, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#else
- mavlink_sys_tm_t packet;
- packet.timestamp = timestamp;
- packet.logger = logger;
- packet.event_broker = event_broker;
- packet.radio = radio;
- packet.pin_observer = pin_observer;
- packet.sensors = sensors;
- packet.board_scheduler = board_scheduler;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, (const char *)&packet, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a sys_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_sys_tm_send_struct(mavlink_channel_t chan, const mavlink_sys_tm_t* sys_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_sys_tm_send(chan, sys_tm->timestamp, sys_tm->logger, sys_tm->event_broker, sys_tm->radio, sys_tm->pin_observer, sys_tm->sensors, sys_tm->board_scheduler);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, (const char *)sys_tm, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SYS_TM_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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t logger, uint8_t event_broker, uint8_t radio, uint8_t pin_observer, uint8_t sensors, uint8_t board_scheduler)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, logger);
- _mav_put_uint8_t(buf, 9, event_broker);
- _mav_put_uint8_t(buf, 10, radio);
- _mav_put_uint8_t(buf, 11, pin_observer);
- _mav_put_uint8_t(buf, 12, sensors);
- _mav_put_uint8_t(buf, 13, board_scheduler);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, buf, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#else
- mavlink_sys_tm_t *packet = (mavlink_sys_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->logger = logger;
- packet->event_broker = event_broker;
- packet->radio = radio;
- packet->pin_observer = pin_observer;
- packet->sensors = sensors;
- packet->board_scheduler = board_scheduler;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, (const char *)packet, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SYS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from sys_tm message
- *
- * @return [us] Timestamp
- */
-static inline uint64_t mavlink_msg_sys_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field logger from sys_tm message
- *
- * @return True if the logger started correctly
- */
-static inline uint8_t mavlink_msg_sys_tm_get_logger(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 8);
-}
-
-/**
- * @brief Get field event_broker from sys_tm message
- *
- * @return True if the event broker started correctly
- */
-static inline uint8_t mavlink_msg_sys_tm_get_event_broker(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 9);
-}
-
-/**
- * @brief Get field radio from sys_tm message
- *
- * @return True if the radio started correctly
- */
-static inline uint8_t mavlink_msg_sys_tm_get_radio(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 10);
-}
-
-/**
- * @brief Get field pin_observer from sys_tm message
- *
- * @return True if the pin observer started correctly
- */
-static inline uint8_t mavlink_msg_sys_tm_get_pin_observer(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 11);
-}
-
-/**
- * @brief Get field sensors from sys_tm message
- *
- * @return True if the sensors started correctly
- */
-static inline uint8_t mavlink_msg_sys_tm_get_sensors(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 12);
-}
-
-/**
- * @brief Get field board_scheduler from sys_tm message
- *
- * @return True if the board scheduler is running
- */
-static inline uint8_t mavlink_msg_sys_tm_get_board_scheduler(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 13);
-}
-
-/**
- * @brief Decode a sys_tm message into a struct
- *
- * @param msg The message to decode
- * @param sys_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_sys_tm_decode(const mavlink_message_t* msg, mavlink_sys_tm_t* sys_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- sys_tm->timestamp = mavlink_msg_sys_tm_get_timestamp(msg);
- sys_tm->logger = mavlink_msg_sys_tm_get_logger(msg);
- sys_tm->event_broker = mavlink_msg_sys_tm_get_event_broker(msg);
- sys_tm->radio = mavlink_msg_sys_tm_get_radio(msg);
- sys_tm->pin_observer = mavlink_msg_sys_tm_get_pin_observer(msg);
- sys_tm->sensors = mavlink_msg_sys_tm_get_sensors(msg);
- sys_tm->board_scheduler = mavlink_msg_sys_tm_get_board_scheduler(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SYS_TM_LEN? msg->len : MAVLINK_MSG_ID_SYS_TM_LEN;
- memset(sys_tm, 0, MAVLINK_MSG_ID_SYS_TM_LEN);
- memcpy(sys_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_system_tm_request_tc.h b/mavlink_lib/gemini/mavlink_msg_system_tm_request_tc.h
deleted file mode 100644
index de5a083eed2404c27df5ad34524fcac401fe3b6f..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_system_tm_request_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SYSTEM_TM_REQUEST_TC PACKING
-
-#define MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC 3
-
-
-typedef struct __mavlink_system_tm_request_tc_t {
- uint8_t tm_id; /*< A member of the SystemTMList enum*/
-} mavlink_system_tm_request_tc_t;
-
-#define MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN 1
-#define MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_3_LEN 1
-#define MAVLINK_MSG_ID_3_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC 165
-#define MAVLINK_MSG_ID_3_CRC 165
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC { \
- 3, \
- "SYSTEM_TM_REQUEST_TC", \
- 1, \
- { { "tm_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_system_tm_request_tc_t, tm_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC { \
- "SYSTEM_TM_REQUEST_TC", \
- 1, \
- { { "tm_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_system_tm_request_tc_t, tm_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a system_tm_request_tc 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 tm_id A member of the SystemTMList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_system_tm_request_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t tm_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, tm_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN);
-#else
- mavlink_system_tm_request_tc_t packet;
- packet.tm_id = tm_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Pack a system_tm_request_tc 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 tm_id A member of the SystemTMList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_system_tm_request_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t tm_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, tm_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN);
-#else
- mavlink_system_tm_request_tc_t packet;
- packet.tm_id = tm_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Encode a system_tm_request_tc 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_tm_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_system_tm_request_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_tm_request_tc_t* system_tm_request_tc)
-{
- return mavlink_msg_system_tm_request_tc_pack(system_id, component_id, msg, system_tm_request_tc->tm_id);
-}
-
-/**
- * @brief Encode a system_tm_request_tc 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_tm_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_system_tm_request_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_system_tm_request_tc_t* system_tm_request_tc)
-{
- return mavlink_msg_system_tm_request_tc_pack_chan(system_id, component_id, chan, msg, system_tm_request_tc->tm_id);
-}
-
-/**
- * @brief Send a system_tm_request_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param tm_id A member of the SystemTMList enum
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_system_tm_request_tc_send(mavlink_channel_t chan, uint8_t tm_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, tm_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC, buf, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-#else
- mavlink_system_tm_request_tc_t packet;
- packet.tm_id = tm_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC, (const char *)&packet, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a system_tm_request_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_system_tm_request_tc_send_struct(mavlink_channel_t chan, const mavlink_system_tm_request_tc_t* system_tm_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_system_tm_request_tc_send(chan, system_tm_request_tc->tm_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC, (const char *)system_tm_request_tc, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_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_tm_request_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t tm_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, tm_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC, buf, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-#else
- mavlink_system_tm_request_tc_t *packet = (mavlink_system_tm_request_tc_t *)msgbuf;
- packet->tm_id = tm_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC, (const char *)packet, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SYSTEM_TM_REQUEST_TC UNPACKING
-
-
-/**
- * @brief Get field tm_id from system_tm_request_tc message
- *
- * @return A member of the SystemTMList enum
- */
-static inline uint8_t mavlink_msg_system_tm_request_tc_get_tm_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a system_tm_request_tc message into a struct
- *
- * @param msg The message to decode
- * @param system_tm_request_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_system_tm_request_tc_decode(const mavlink_message_t* msg, mavlink_system_tm_request_tc_t* system_tm_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- system_tm_request_tc->tm_id = mavlink_msg_system_tm_request_tc_get_tm_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN? msg->len : MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN;
- memset(system_tm_request_tc, 0, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN);
- memcpy(system_tm_request_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_tars_tm.h b/mavlink_lib/gemini/mavlink_msg_tars_tm.h
deleted file mode 100644
index 91626913f9fa4a280b2eeaab2a60803cdc58f15c..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_tars_tm.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE TARS_TM PACKING
-
-#define MAVLINK_MSG_ID_TARS_TM 207
-
-
-typedef struct __mavlink_tars_tm_t {
- uint64_t timestamp; /*< [us] Timestamp in microseconds*/
- uint8_t algorithm_number; /*< Algorithm selection number*/
-} mavlink_tars_tm_t;
-
-#define MAVLINK_MSG_ID_TARS_TM_LEN 9
-#define MAVLINK_MSG_ID_TARS_TM_MIN_LEN 9
-#define MAVLINK_MSG_ID_207_LEN 9
-#define MAVLINK_MSG_ID_207_MIN_LEN 9
-
-#define MAVLINK_MSG_ID_TARS_TM_CRC 122
-#define MAVLINK_MSG_ID_207_CRC 122
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_TARS_TM { \
- 207, \
- "TARS_TM", \
- 2, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_tars_tm_t, timestamp) }, \
- { "algorithm_number", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_tars_tm_t, algorithm_number) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_TARS_TM { \
- "TARS_TM", \
- 2, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_tars_tm_t, timestamp) }, \
- { "algorithm_number", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_tars_tm_t, algorithm_number) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a tars_tm 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 in microseconds
- * @param algorithm_number Algorithm selection number
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_tars_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t algorithm_number)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TARS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, algorithm_number);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TARS_TM_LEN);
-#else
- mavlink_tars_tm_t packet;
- packet.timestamp = timestamp;
- packet.algorithm_number = algorithm_number;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TARS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TARS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TARS_TM_MIN_LEN, MAVLINK_MSG_ID_TARS_TM_LEN, MAVLINK_MSG_ID_TARS_TM_CRC);
-}
-
-/**
- * @brief Pack a tars_tm 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 in microseconds
- * @param algorithm_number Algorithm selection number
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_tars_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t algorithm_number)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TARS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, algorithm_number);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TARS_TM_LEN);
-#else
- mavlink_tars_tm_t packet;
- packet.timestamp = timestamp;
- packet.algorithm_number = algorithm_number;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TARS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TARS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TARS_TM_MIN_LEN, MAVLINK_MSG_ID_TARS_TM_LEN, MAVLINK_MSG_ID_TARS_TM_CRC);
-}
-
-/**
- * @brief Encode a tars_tm 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 tars_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_tars_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_tars_tm_t* tars_tm)
-{
- return mavlink_msg_tars_tm_pack(system_id, component_id, msg, tars_tm->timestamp, tars_tm->algorithm_number);
-}
-
-/**
- * @brief Encode a tars_tm 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 tars_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_tars_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_tars_tm_t* tars_tm)
-{
- return mavlink_msg_tars_tm_pack_chan(system_id, component_id, chan, msg, tars_tm->timestamp, tars_tm->algorithm_number);
-}
-
-/**
- * @brief Send a tars_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp in microseconds
- * @param algorithm_number Algorithm selection number
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_tars_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t algorithm_number)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TARS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, algorithm_number);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TARS_TM, buf, MAVLINK_MSG_ID_TARS_TM_MIN_LEN, MAVLINK_MSG_ID_TARS_TM_LEN, MAVLINK_MSG_ID_TARS_TM_CRC);
-#else
- mavlink_tars_tm_t packet;
- packet.timestamp = timestamp;
- packet.algorithm_number = algorithm_number;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TARS_TM, (const char *)&packet, MAVLINK_MSG_ID_TARS_TM_MIN_LEN, MAVLINK_MSG_ID_TARS_TM_LEN, MAVLINK_MSG_ID_TARS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a tars_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_tars_tm_send_struct(mavlink_channel_t chan, const mavlink_tars_tm_t* tars_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_tars_tm_send(chan, tars_tm->timestamp, tars_tm->algorithm_number);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TARS_TM, (const char *)tars_tm, MAVLINK_MSG_ID_TARS_TM_MIN_LEN, MAVLINK_MSG_ID_TARS_TM_LEN, MAVLINK_MSG_ID_TARS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_TARS_TM_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_tars_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t algorithm_number)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, algorithm_number);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TARS_TM, buf, MAVLINK_MSG_ID_TARS_TM_MIN_LEN, MAVLINK_MSG_ID_TARS_TM_LEN, MAVLINK_MSG_ID_TARS_TM_CRC);
-#else
- mavlink_tars_tm_t *packet = (mavlink_tars_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->algorithm_number = algorithm_number;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TARS_TM, (const char *)packet, MAVLINK_MSG_ID_TARS_TM_MIN_LEN, MAVLINK_MSG_ID_TARS_TM_LEN, MAVLINK_MSG_ID_TARS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE TARS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from tars_tm message
- *
- * @return [us] Timestamp in microseconds
- */
-static inline uint64_t mavlink_msg_tars_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field algorithm_number from tars_tm message
- *
- * @return Algorithm selection number
- */
-static inline uint8_t mavlink_msg_tars_tm_get_algorithm_number(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 8);
-}
-
-/**
- * @brief Decode a tars_tm message into a struct
- *
- * @param msg The message to decode
- * @param tars_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_tars_tm_decode(const mavlink_message_t* msg, mavlink_tars_tm_t* tars_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- tars_tm->timestamp = mavlink_msg_tars_tm_get_timestamp(msg);
- tars_tm->algorithm_number = mavlink_msg_tars_tm_get_algorithm_number(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_TARS_TM_LEN? msg->len : MAVLINK_MSG_ID_TARS_TM_LEN;
- memset(tars_tm, 0, MAVLINK_MSG_ID_TARS_TM_LEN);
- memcpy(tars_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_task_stats_tm.h b/mavlink_lib/gemini/mavlink_msg_task_stats_tm.h
deleted file mode 100644
index 81727059a4f8f5ed68fc83870afb0b99ab064bba..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_task_stats_tm.h
+++ /dev/null
@@ -1,363 +0,0 @@
-#pragma once
-// MESSAGE TASK_STATS_TM PACKING
-
-#define MAVLINK_MSG_ID_TASK_STATS_TM 204
-
-
-typedef struct __mavlink_task_stats_tm_t {
- uint64_t timestamp; /*< [us] When was this logged */
- float task_min; /*< Task min period*/
- float task_max; /*< Task max period*/
- float task_mean; /*< Task mean period*/
- float task_stddev; /*< Task period std deviation*/
- uint16_t task_period; /*< [ms] Period of the task*/
- uint8_t task_id; /*< Task ID*/
-} mavlink_task_stats_tm_t;
-
-#define MAVLINK_MSG_ID_TASK_STATS_TM_LEN 27
-#define MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN 27
-#define MAVLINK_MSG_ID_204_LEN 27
-#define MAVLINK_MSG_ID_204_MIN_LEN 27
-
-#define MAVLINK_MSG_ID_TASK_STATS_TM_CRC 133
-#define MAVLINK_MSG_ID_204_CRC 133
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_TASK_STATS_TM { \
- 204, \
- "TASK_STATS_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_task_stats_tm_t, timestamp) }, \
- { "task_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_task_stats_tm_t, task_id) }, \
- { "task_period", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_task_stats_tm_t, task_period) }, \
- { "task_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_task_stats_tm_t, task_min) }, \
- { "task_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_task_stats_tm_t, task_max) }, \
- { "task_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_task_stats_tm_t, task_mean) }, \
- { "task_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_task_stats_tm_t, task_stddev) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_TASK_STATS_TM { \
- "TASK_STATS_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_task_stats_tm_t, timestamp) }, \
- { "task_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_task_stats_tm_t, task_id) }, \
- { "task_period", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_task_stats_tm_t, task_period) }, \
- { "task_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_task_stats_tm_t, task_min) }, \
- { "task_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_task_stats_tm_t, task_max) }, \
- { "task_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_task_stats_tm_t, task_mean) }, \
- { "task_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_task_stats_tm_t, task_stddev) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a task_stats_tm 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] When was this logged
- * @param task_id Task ID
- * @param task_period [ms] Period of the task
- * @param task_min Task min period
- * @param task_max Task max period
- * @param task_mean Task mean period
- * @param task_stddev Task period std deviation
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_task_stats_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t task_id, uint16_t task_period, float task_min, float task_max, float task_mean, float task_stddev)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TASK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, task_min);
- _mav_put_float(buf, 12, task_max);
- _mav_put_float(buf, 16, task_mean);
- _mav_put_float(buf, 20, task_stddev);
- _mav_put_uint16_t(buf, 24, task_period);
- _mav_put_uint8_t(buf, 26, task_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
-#else
- mavlink_task_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.task_min = task_min;
- packet.task_max = task_max;
- packet.task_mean = task_mean;
- packet.task_stddev = task_stddev;
- packet.task_period = task_period;
- packet.task_id = task_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TASK_STATS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-}
-
-/**
- * @brief Pack a task_stats_tm 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] When was this logged
- * @param task_id Task ID
- * @param task_period [ms] Period of the task
- * @param task_min Task min period
- * @param task_max Task max period
- * @param task_mean Task mean period
- * @param task_stddev Task period std deviation
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_task_stats_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t task_id,uint16_t task_period,float task_min,float task_max,float task_mean,float task_stddev)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TASK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, task_min);
- _mav_put_float(buf, 12, task_max);
- _mav_put_float(buf, 16, task_mean);
- _mav_put_float(buf, 20, task_stddev);
- _mav_put_uint16_t(buf, 24, task_period);
- _mav_put_uint8_t(buf, 26, task_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
-#else
- mavlink_task_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.task_min = task_min;
- packet.task_max = task_max;
- packet.task_mean = task_mean;
- packet.task_stddev = task_stddev;
- packet.task_period = task_period;
- packet.task_id = task_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TASK_STATS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-}
-
-/**
- * @brief Encode a task_stats_tm 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 task_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_task_stats_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_task_stats_tm_t* task_stats_tm)
-{
- return mavlink_msg_task_stats_tm_pack(system_id, component_id, msg, task_stats_tm->timestamp, task_stats_tm->task_id, task_stats_tm->task_period, task_stats_tm->task_min, task_stats_tm->task_max, task_stats_tm->task_mean, task_stats_tm->task_stddev);
-}
-
-/**
- * @brief Encode a task_stats_tm 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 task_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_task_stats_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_task_stats_tm_t* task_stats_tm)
-{
- return mavlink_msg_task_stats_tm_pack_chan(system_id, component_id, chan, msg, task_stats_tm->timestamp, task_stats_tm->task_id, task_stats_tm->task_period, task_stats_tm->task_min, task_stats_tm->task_max, task_stats_tm->task_mean, task_stats_tm->task_stddev);
-}
-
-/**
- * @brief Send a task_stats_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param task_id Task ID
- * @param task_period [ms] Period of the task
- * @param task_min Task min period
- * @param task_max Task max period
- * @param task_mean Task mean period
- * @param task_stddev Task period std deviation
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_task_stats_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t task_id, uint16_t task_period, float task_min, float task_max, float task_mean, float task_stddev)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TASK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, task_min);
- _mav_put_float(buf, 12, task_max);
- _mav_put_float(buf, 16, task_mean);
- _mav_put_float(buf, 20, task_stddev);
- _mav_put_uint16_t(buf, 24, task_period);
- _mav_put_uint8_t(buf, 26, task_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, buf, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-#else
- mavlink_task_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.task_min = task_min;
- packet.task_max = task_max;
- packet.task_mean = task_mean;
- packet.task_stddev = task_stddev;
- packet.task_period = task_period;
- packet.task_id = task_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, (const char *)&packet, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a task_stats_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_task_stats_tm_send_struct(mavlink_channel_t chan, const mavlink_task_stats_tm_t* task_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_task_stats_tm_send(chan, task_stats_tm->timestamp, task_stats_tm->task_id, task_stats_tm->task_period, task_stats_tm->task_min, task_stats_tm->task_max, task_stats_tm->task_mean, task_stats_tm->task_stddev);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, (const char *)task_stats_tm, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_TASK_STATS_TM_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_task_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t task_id, uint16_t task_period, float task_min, float task_max, float task_mean, float task_stddev)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, task_min);
- _mav_put_float(buf, 12, task_max);
- _mav_put_float(buf, 16, task_mean);
- _mav_put_float(buf, 20, task_stddev);
- _mav_put_uint16_t(buf, 24, task_period);
- _mav_put_uint8_t(buf, 26, task_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, buf, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-#else
- mavlink_task_stats_tm_t *packet = (mavlink_task_stats_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->task_min = task_min;
- packet->task_max = task_max;
- packet->task_mean = task_mean;
- packet->task_stddev = task_stddev;
- packet->task_period = task_period;
- packet->task_id = task_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, (const char *)packet, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE TASK_STATS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from task_stats_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_task_stats_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field task_id from task_stats_tm message
- *
- * @return Task ID
- */
-static inline uint8_t mavlink_msg_task_stats_tm_get_task_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 26);
-}
-
-/**
- * @brief Get field task_period from task_stats_tm message
- *
- * @return [ms] Period of the task
- */
-static inline uint16_t mavlink_msg_task_stats_tm_get_task_period(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 24);
-}
-
-/**
- * @brief Get field task_min from task_stats_tm message
- *
- * @return Task min period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_min(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field task_max from task_stats_tm message
- *
- * @return Task max period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_max(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field task_mean from task_stats_tm message
- *
- * @return Task mean period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_mean(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field task_stddev from task_stats_tm message
- *
- * @return Task period std deviation
- */
-static inline float mavlink_msg_task_stats_tm_get_task_stddev(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Decode a task_stats_tm message into a struct
- *
- * @param msg The message to decode
- * @param task_stats_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_task_stats_tm_decode(const mavlink_message_t* msg, mavlink_task_stats_tm_t* task_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- task_stats_tm->timestamp = mavlink_msg_task_stats_tm_get_timestamp(msg);
- task_stats_tm->task_min = mavlink_msg_task_stats_tm_get_task_min(msg);
- task_stats_tm->task_max = mavlink_msg_task_stats_tm_get_task_max(msg);
- task_stats_tm->task_mean = mavlink_msg_task_stats_tm_get_task_mean(msg);
- task_stats_tm->task_stddev = mavlink_msg_task_stats_tm_get_task_stddev(msg);
- task_stats_tm->task_period = mavlink_msg_task_stats_tm_get_task_period(msg);
- task_stats_tm->task_id = mavlink_msg_task_stats_tm_get_task_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_TASK_STATS_TM_LEN? msg->len : MAVLINK_MSG_ID_TASK_STATS_TM_LEN;
- memset(task_stats_tm, 0, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
- memcpy(task_stats_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_temp_tm.h b/mavlink_lib/gemini/mavlink_msg_temp_tm.h
deleted file mode 100644
index 1334d436975a961e918b50ed4b8d04f058faab3f..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_temp_tm.h
+++ /dev/null
@@ -1,255 +0,0 @@
-#pragma once
-// MESSAGE TEMP_TM PACKING
-
-#define MAVLINK_MSG_ID_TEMP_TM 108
-
-
-typedef struct __mavlink_temp_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float temperature; /*< [deg] Temperature*/
- char sensor_name[20]; /*< Sensor name*/
-} mavlink_temp_tm_t;
-
-#define MAVLINK_MSG_ID_TEMP_TM_LEN 32
-#define MAVLINK_MSG_ID_TEMP_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_108_LEN 32
-#define MAVLINK_MSG_ID_108_MIN_LEN 32
-
-#define MAVLINK_MSG_ID_TEMP_TM_CRC 140
-#define MAVLINK_MSG_ID_108_CRC 140
-
-#define MAVLINK_MSG_TEMP_TM_FIELD_SENSOR_NAME_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_TEMP_TM { \
- 108, \
- "TEMP_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_temp_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_temp_tm_t, sensor_name) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_temp_tm_t, temperature) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_TEMP_TM { \
- "TEMP_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_temp_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_temp_tm_t, sensor_name) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_temp_tm_t, temperature) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a temp_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param temperature [deg] Temperature
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_temp_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_name, float temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TEMP_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, temperature);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TEMP_TM_LEN);
-#else
- mavlink_temp_tm_t packet;
- packet.timestamp = timestamp;
- packet.temperature = temperature;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TEMP_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TEMP_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-}
-
-/**
- * @brief Pack a temp_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param temperature [deg] Temperature
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_temp_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_name,float temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TEMP_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, temperature);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TEMP_TM_LEN);
-#else
- mavlink_temp_tm_t packet;
- packet.timestamp = timestamp;
- packet.temperature = temperature;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TEMP_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TEMP_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-}
-
-/**
- * @brief Encode a temp_tm 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 temp_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_temp_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_temp_tm_t* temp_tm)
-{
- return mavlink_msg_temp_tm_pack(system_id, component_id, msg, temp_tm->timestamp, temp_tm->sensor_name, temp_tm->temperature);
-}
-
-/**
- * @brief Encode a temp_tm 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 temp_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_temp_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_temp_tm_t* temp_tm)
-{
- return mavlink_msg_temp_tm_pack_chan(system_id, component_id, chan, msg, temp_tm->timestamp, temp_tm->sensor_name, temp_tm->temperature);
-}
-
-/**
- * @brief Send a temp_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_name Sensor name
- * @param temperature [deg] Temperature
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_temp_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TEMP_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, temperature);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEMP_TM, buf, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-#else
- mavlink_temp_tm_t packet;
- packet.timestamp = timestamp;
- packet.temperature = temperature;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEMP_TM, (const char *)&packet, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a temp_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_temp_tm_send_struct(mavlink_channel_t chan, const mavlink_temp_tm_t* temp_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_temp_tm_send(chan, temp_tm->timestamp, temp_tm->sensor_name, temp_tm->temperature);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEMP_TM, (const char *)temp_tm, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_TEMP_TM_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_temp_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, temperature);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEMP_TM, buf, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-#else
- mavlink_temp_tm_t *packet = (mavlink_temp_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->temperature = temperature;
- mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEMP_TM, (const char *)packet, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE TEMP_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from temp_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_temp_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_name from temp_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_temp_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
-{
- return _MAV_RETURN_char_array(msg, sensor_name, 20, 12);
-}
-
-/**
- * @brief Get field temperature from temp_tm message
- *
- * @return [deg] Temperature
- */
-static inline float mavlink_msg_temp_tm_get_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Decode a temp_tm message into a struct
- *
- * @param msg The message to decode
- * @param temp_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_temp_tm_decode(const mavlink_message_t* msg, mavlink_temp_tm_t* temp_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- temp_tm->timestamp = mavlink_msg_temp_tm_get_timestamp(msg);
- temp_tm->temperature = mavlink_msg_temp_tm_get_temperature(msg);
- mavlink_msg_temp_tm_get_sensor_name(msg, temp_tm->sensor_name);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_TEMP_TM_LEN? msg->len : MAVLINK_MSG_ID_TEMP_TM_LEN;
- memset(temp_tm, 0, MAVLINK_MSG_ID_TEMP_TM_LEN);
- memcpy(temp_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_voltage_tm.h b/mavlink_lib/gemini/mavlink_msg_voltage_tm.h
deleted file mode 100644
index 5a391cee271737b01330a5546290d5ba21f3c3a8..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_voltage_tm.h
+++ /dev/null
@@ -1,255 +0,0 @@
-#pragma once
-// MESSAGE VOLTAGE_TM PACKING
-
-#define MAVLINK_MSG_ID_VOLTAGE_TM 106
-
-
-typedef struct __mavlink_voltage_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float voltage; /*< [V] Voltage*/
- char sensor_name[20]; /*< Sensor name*/
-} mavlink_voltage_tm_t;
-
-#define MAVLINK_MSG_ID_VOLTAGE_TM_LEN 32
-#define MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_106_LEN 32
-#define MAVLINK_MSG_ID_106_MIN_LEN 32
-
-#define MAVLINK_MSG_ID_VOLTAGE_TM_CRC 245
-#define MAVLINK_MSG_ID_106_CRC 245
-
-#define MAVLINK_MSG_VOLTAGE_TM_FIELD_SENSOR_NAME_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_VOLTAGE_TM { \
- 106, \
- "VOLTAGE_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_voltage_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_voltage_tm_t, sensor_name) }, \
- { "voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_voltage_tm_t, voltage) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_VOLTAGE_TM { \
- "VOLTAGE_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_voltage_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_voltage_tm_t, sensor_name) }, \
- { "voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_voltage_tm_t, voltage) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a voltage_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param voltage [V] Voltage
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_voltage_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_name, float voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_VOLTAGE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, voltage);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VOLTAGE_TM_LEN);
-#else
- mavlink_voltage_tm_t packet;
- packet.timestamp = timestamp;
- packet.voltage = voltage;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VOLTAGE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_VOLTAGE_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-}
-
-/**
- * @brief Pack a voltage_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param voltage [V] Voltage
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_voltage_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_name,float voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_VOLTAGE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, voltage);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VOLTAGE_TM_LEN);
-#else
- mavlink_voltage_tm_t packet;
- packet.timestamp = timestamp;
- packet.voltage = voltage;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VOLTAGE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_VOLTAGE_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-}
-
-/**
- * @brief Encode a voltage_tm 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 voltage_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_voltage_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_voltage_tm_t* voltage_tm)
-{
- return mavlink_msg_voltage_tm_pack(system_id, component_id, msg, voltage_tm->timestamp, voltage_tm->sensor_name, voltage_tm->voltage);
-}
-
-/**
- * @brief Encode a voltage_tm 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 voltage_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_voltage_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_voltage_tm_t* voltage_tm)
-{
- return mavlink_msg_voltage_tm_pack_chan(system_id, component_id, chan, msg, voltage_tm->timestamp, voltage_tm->sensor_name, voltage_tm->voltage);
-}
-
-/**
- * @brief Send a voltage_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_name Sensor name
- * @param voltage [V] Voltage
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_voltage_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_VOLTAGE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, voltage);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLTAGE_TM, buf, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-#else
- mavlink_voltage_tm_t packet;
- packet.timestamp = timestamp;
- packet.voltage = voltage;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLTAGE_TM, (const char *)&packet, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a voltage_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_voltage_tm_send_struct(mavlink_channel_t chan, const mavlink_voltage_tm_t* voltage_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_voltage_tm_send(chan, voltage_tm->timestamp, voltage_tm->sensor_name, voltage_tm->voltage);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLTAGE_TM, (const char *)voltage_tm, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_VOLTAGE_TM_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_voltage_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, voltage);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLTAGE_TM, buf, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-#else
- mavlink_voltage_tm_t *packet = (mavlink_voltage_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->voltage = voltage;
- mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLTAGE_TM, (const char *)packet, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE VOLTAGE_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from voltage_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_voltage_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_name from voltage_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_voltage_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
-{
- return _MAV_RETURN_char_array(msg, sensor_name, 20, 12);
-}
-
-/**
- * @brief Get field voltage from voltage_tm message
- *
- * @return [V] Voltage
- */
-static inline float mavlink_msg_voltage_tm_get_voltage(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Decode a voltage_tm message into a struct
- *
- * @param msg The message to decode
- * @param voltage_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_voltage_tm_decode(const mavlink_message_t* msg, mavlink_voltage_tm_t* voltage_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- voltage_tm->timestamp = mavlink_msg_voltage_tm_get_timestamp(msg);
- voltage_tm->voltage = mavlink_msg_voltage_tm_get_voltage(msg);
- mavlink_msg_voltage_tm_get_sensor_name(msg, voltage_tm->sensor_name);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_VOLTAGE_TM_LEN? msg->len : MAVLINK_MSG_ID_VOLTAGE_TM_LEN;
- memset(voltage_tm, 0, MAVLINK_MSG_ID_VOLTAGE_TM_LEN);
- memcpy(voltage_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/mavlink_msg_wiggle_servo_tc.h b/mavlink_lib/gemini/mavlink_msg_wiggle_servo_tc.h
deleted file mode 100644
index b9e333c4ed5bde71c947b204fee64987ed98b2ad..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/mavlink_msg_wiggle_servo_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE WIGGLE_SERVO_TC PACKING
-
-#define MAVLINK_MSG_ID_WIGGLE_SERVO_TC 7
-
-
-typedef struct __mavlink_wiggle_servo_tc_t {
- uint8_t servo_id; /*< A member of the ServosList enum*/
-} mavlink_wiggle_servo_tc_t;
-
-#define MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN 1
-#define MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_7_LEN 1
-#define MAVLINK_MSG_ID_7_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC 160
-#define MAVLINK_MSG_ID_7_CRC 160
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC { \
- 7, \
- "WIGGLE_SERVO_TC", \
- 1, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_wiggle_servo_tc_t, servo_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC { \
- "WIGGLE_SERVO_TC", \
- 1, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_wiggle_servo_tc_t, servo_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a wiggle_servo_tc 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 servo_id A member of the ServosList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_wiggle_servo_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN);
-#else
- mavlink_wiggle_servo_tc_t packet;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_WIGGLE_SERVO_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-}
-
-/**
- * @brief Pack a wiggle_servo_tc 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 servo_id A member of the ServosList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_wiggle_servo_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN);
-#else
- mavlink_wiggle_servo_tc_t packet;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_WIGGLE_SERVO_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-}
-
-/**
- * @brief Encode a wiggle_servo_tc 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 wiggle_servo_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_wiggle_servo_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_wiggle_servo_tc_t* wiggle_servo_tc)
-{
- return mavlink_msg_wiggle_servo_tc_pack(system_id, component_id, msg, wiggle_servo_tc->servo_id);
-}
-
-/**
- * @brief Encode a wiggle_servo_tc 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 wiggle_servo_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_wiggle_servo_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_wiggle_servo_tc_t* wiggle_servo_tc)
-{
- return mavlink_msg_wiggle_servo_tc_pack_chan(system_id, component_id, chan, msg, wiggle_servo_tc->servo_id);
-}
-
-/**
- * @brief Send a wiggle_servo_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param servo_id A member of the ServosList enum
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_wiggle_servo_tc_send(mavlink_channel_t chan, uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIGGLE_SERVO_TC, buf, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-#else
- mavlink_wiggle_servo_tc_t packet;
- packet.servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIGGLE_SERVO_TC, (const char *)&packet, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a wiggle_servo_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_wiggle_servo_tc_send_struct(mavlink_channel_t chan, const mavlink_wiggle_servo_tc_t* wiggle_servo_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_wiggle_servo_tc_send(chan, wiggle_servo_tc->servo_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIGGLE_SERVO_TC, (const char *)wiggle_servo_tc, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_WIGGLE_SERVO_TC_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_wiggle_servo_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIGGLE_SERVO_TC, buf, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-#else
- mavlink_wiggle_servo_tc_t *packet = (mavlink_wiggle_servo_tc_t *)msgbuf;
- packet->servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIGGLE_SERVO_TC, (const char *)packet, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE WIGGLE_SERVO_TC UNPACKING
-
-
-/**
- * @brief Get field servo_id from wiggle_servo_tc message
- *
- * @return A member of the ServosList enum
- */
-static inline uint8_t mavlink_msg_wiggle_servo_tc_get_servo_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a wiggle_servo_tc message into a struct
- *
- * @param msg The message to decode
- * @param wiggle_servo_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_wiggle_servo_tc_decode(const mavlink_message_t* msg, mavlink_wiggle_servo_tc_t* wiggle_servo_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- wiggle_servo_tc->servo_id = mavlink_msg_wiggle_servo_tc_get_servo_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN? msg->len : MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN;
- memset(wiggle_servo_tc, 0, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN);
- memcpy(wiggle_servo_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/gemini/testsuite.h b/mavlink_lib/gemini/testsuite.h
deleted file mode 100644
index d3838f78d53e03cec0d61023cd88701fee78b576..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/testsuite.h
+++ /dev/null
@@ -1,3291 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol testsuite generated from gemini.xml
- * @see https://mavlink.io/en/
- */
-#pragma once
-#ifndef GEMINI_TESTSUITE_H
-#define GEMINI_TESTSUITE_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#ifndef MAVLINK_TEST_ALL
-#define MAVLINK_TEST_ALL
-
-static void mavlink_test_gemini(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_gemini(system_id, component_id, last_msg);
-}
-#endif
-
-
-
-
-static void mavlink_test_ping_tc(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_PING_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ping_tc_t packet_in = {
- 93372036854775807ULL
- };
- mavlink_ping_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_PING_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PING_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ping_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_pack(system_id, component_id, &msg , packet1.timestamp );
- mavlink_msg_ping_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp );
- mavlink_msg_ping_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ping_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_send(MAVLINK_COMM_1 , packet1.timestamp );
- mavlink_msg_ping_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("PING_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_PING_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_command_tc(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_COMMAND_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_command_tc_t packet_in = {
- 5
- };
- mavlink_command_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.command_id = packet_in.command_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_command_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_command_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_command_tc_pack(system_id, component_id, &msg , packet1.command_id );
- mavlink_msg_command_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_command_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.command_id );
- mavlink_msg_command_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_command_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_command_tc_send(MAVLINK_COMM_1 , packet1.command_id );
- mavlink_msg_command_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("COMMAND_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_COMMAND_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_system_tm_request_tc(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_SYSTEM_TM_REQUEST_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_system_tm_request_tc_t packet_in = {
- 5
- };
- mavlink_system_tm_request_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.tm_id = packet_in.tm_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_system_tm_request_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_system_tm_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_system_tm_request_tc_pack(system_id, component_id, &msg , packet1.tm_id );
- mavlink_msg_system_tm_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_system_tm_request_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.tm_id );
- mavlink_msg_system_tm_request_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_system_tm_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_system_tm_request_tc_send(MAVLINK_COMM_1 , packet1.tm_id );
- mavlink_msg_system_tm_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SYSTEM_TM_REQUEST_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_sensor_tm_request_tc(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_SENSOR_TM_REQUEST_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_sensor_tm_request_tc_t packet_in = {
- 5
- };
- mavlink_sensor_tm_request_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.sensor_name = packet_in.sensor_name;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_tm_request_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_sensor_tm_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_tm_request_tc_pack(system_id, component_id, &msg , packet1.sensor_name );
- mavlink_msg_sensor_tm_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_tm_request_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.sensor_name );
- mavlink_msg_sensor_tm_request_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_sensor_tm_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_tm_request_tc_send(MAVLINK_COMM_1 , packet1.sensor_name );
- mavlink_msg_sensor_tm_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SENSOR_TM_REQUEST_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_servo_tm_request_tc(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_SERVO_TM_REQUEST_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_servo_tm_request_tc_t packet_in = {
- 5
- };
- mavlink_servo_tm_request_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.servo_id = packet_in.servo_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_request_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_servo_tm_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_request_tc_pack(system_id, component_id, &msg , packet1.servo_id );
- mavlink_msg_servo_tm_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_request_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id );
- mavlink_msg_servo_tm_request_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_servo_tm_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_request_tc_send(MAVLINK_COMM_1 , packet1.servo_id );
- mavlink_msg_servo_tm_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SERVO_TM_REQUEST_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_servo_angle_tc(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_SET_SERVO_ANGLE_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_servo_angle_tc_t packet_in = {
- 17.0,17
- };
- mavlink_set_servo_angle_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.angle = packet_in.angle;
- packet1.servo_id = packet_in.servo_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_servo_angle_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_servo_angle_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_servo_angle_tc_pack(system_id, component_id, &msg , packet1.servo_id , packet1.angle );
- mavlink_msg_set_servo_angle_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_servo_angle_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id , packet1.angle );
- mavlink_msg_set_servo_angle_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_servo_angle_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_servo_angle_tc_send(MAVLINK_COMM_1 , packet1.servo_id , packet1.angle );
- mavlink_msg_set_servo_angle_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_SERVO_ANGLE_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_wiggle_servo_tc(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_WIGGLE_SERVO_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_wiggle_servo_tc_t packet_in = {
- 5
- };
- mavlink_wiggle_servo_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.servo_id = packet_in.servo_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_wiggle_servo_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_wiggle_servo_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_wiggle_servo_tc_pack(system_id, component_id, &msg , packet1.servo_id );
- mavlink_msg_wiggle_servo_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_wiggle_servo_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id );
- mavlink_msg_wiggle_servo_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_wiggle_servo_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_wiggle_servo_tc_send(MAVLINK_COMM_1 , packet1.servo_id );
- mavlink_msg_wiggle_servo_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("WIGGLE_SERVO_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_WIGGLE_SERVO_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_reset_servo_tc(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_RESET_SERVO_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_reset_servo_tc_t packet_in = {
- 5
- };
- mavlink_reset_servo_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.servo_id = packet_in.servo_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_reset_servo_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_reset_servo_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_reset_servo_tc_pack(system_id, component_id, &msg , packet1.servo_id );
- mavlink_msg_reset_servo_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_reset_servo_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id );
- mavlink_msg_reset_servo_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_reset_servo_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_reset_servo_tc_send(MAVLINK_COMM_1 , packet1.servo_id );
- mavlink_msg_reset_servo_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("RESET_SERVO_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_RESET_SERVO_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_reference_altitude_tc(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_SET_REFERENCE_ALTITUDE_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_reference_altitude_tc_t packet_in = {
- 17.0
- };
- mavlink_set_reference_altitude_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.ref_altitude = packet_in.ref_altitude;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_altitude_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_reference_altitude_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_altitude_tc_pack(system_id, component_id, &msg , packet1.ref_altitude );
- mavlink_msg_set_reference_altitude_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_altitude_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.ref_altitude );
- mavlink_msg_set_reference_altitude_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_reference_altitude_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_altitude_tc_send(MAVLINK_COMM_1 , packet1.ref_altitude );
- mavlink_msg_set_reference_altitude_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_REFERENCE_ALTITUDE_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_reference_temperature_tc(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_SET_REFERENCE_TEMPERATURE_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_reference_temperature_tc_t packet_in = {
- 17.0
- };
- mavlink_set_reference_temperature_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.ref_temp = packet_in.ref_temp;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_temperature_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_reference_temperature_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_temperature_tc_pack(system_id, component_id, &msg , packet1.ref_temp );
- mavlink_msg_set_reference_temperature_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_temperature_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.ref_temp );
- mavlink_msg_set_reference_temperature_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_reference_temperature_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_temperature_tc_send(MAVLINK_COMM_1 , packet1.ref_temp );
- mavlink_msg_set_reference_temperature_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_REFERENCE_TEMPERATURE_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_orientation_tc(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_SET_ORIENTATION_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_orientation_tc_t packet_in = {
- 17.0,45.0,73.0
- };
- mavlink_set_orientation_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.yaw = packet_in.yaw;
- packet1.pitch = packet_in.pitch;
- packet1.roll = packet_in.roll;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_orientation_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_orientation_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_orientation_tc_pack(system_id, component_id, &msg , packet1.yaw , packet1.pitch , packet1.roll );
- mavlink_msg_set_orientation_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_orientation_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.yaw , packet1.pitch , packet1.roll );
- mavlink_msg_set_orientation_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_orientation_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_orientation_tc_send(MAVLINK_COMM_1 , packet1.yaw , packet1.pitch , packet1.roll );
- mavlink_msg_set_orientation_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_ORIENTATION_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_ORIENTATION_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_coordinates_tc(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_SET_COORDINATES_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_coordinates_tc_t packet_in = {
- 17.0,45.0
- };
- mavlink_set_coordinates_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.latitude = packet_in.latitude;
- packet1.longitude = packet_in.longitude;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_coordinates_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_coordinates_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_coordinates_tc_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude );
- mavlink_msg_set_coordinates_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_coordinates_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude );
- mavlink_msg_set_coordinates_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_coordinates_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_coordinates_tc_send(MAVLINK_COMM_1 , packet1.latitude , packet1.longitude );
- mavlink_msg_set_coordinates_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_COORDINATES_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_COORDINATES_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_raw_event_tc(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_RAW_EVENT_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_raw_event_tc_t packet_in = {
- 5,72
- };
- mavlink_raw_event_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.topic_id = packet_in.topic_id;
- packet1.event_id = packet_in.event_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_raw_event_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_pack(system_id, component_id, &msg , packet1.topic_id , packet1.event_id );
- mavlink_msg_raw_event_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.topic_id , packet1.event_id );
- mavlink_msg_raw_event_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_raw_event_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_send(MAVLINK_COMM_1 , packet1.topic_id , packet1.event_id );
- mavlink_msg_raw_event_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("RAW_EVENT_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_RAW_EVENT_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_deployment_altitude_tc(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_SET_DEPLOYMENT_ALTITUDE_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_deployment_altitude_tc_t packet_in = {
- 17.0
- };
- mavlink_set_deployment_altitude_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.dpl_altitude = packet_in.dpl_altitude;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_deployment_altitude_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_deployment_altitude_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_deployment_altitude_tc_pack(system_id, component_id, &msg , packet1.dpl_altitude );
- mavlink_msg_set_deployment_altitude_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_deployment_altitude_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.dpl_altitude );
- mavlink_msg_set_deployment_altitude_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_deployment_altitude_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_deployment_altitude_tc_send(MAVLINK_COMM_1 , packet1.dpl_altitude );
- mavlink_msg_set_deployment_altitude_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_DEPLOYMENT_ALTITUDE_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_target_coordinates_tc(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_SET_TARGET_COORDINATES_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_target_coordinates_tc_t packet_in = {
- 17.0,45.0
- };
- mavlink_set_target_coordinates_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.latitude = packet_in.latitude;
- packet1.longitude = packet_in.longitude;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_target_coordinates_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_target_coordinates_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_target_coordinates_tc_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude );
- mavlink_msg_set_target_coordinates_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_target_coordinates_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude );
- mavlink_msg_set_target_coordinates_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_target_coordinates_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_target_coordinates_tc_send(MAVLINK_COMM_1 , packet1.latitude , packet1.longitude );
- mavlink_msg_set_target_coordinates_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_TARGET_COORDINATES_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_algorithm_tc(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_SET_ALGORITHM_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_algorithm_tc_t packet_in = {
- 5
- };
- mavlink_set_algorithm_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.algorithm_number = packet_in.algorithm_number;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_algorithm_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_algorithm_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_algorithm_tc_pack(system_id, component_id, &msg , packet1.algorithm_number );
- mavlink_msg_set_algorithm_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_algorithm_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.algorithm_number );
- mavlink_msg_set_algorithm_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_algorithm_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_algorithm_tc_send(MAVLINK_COMM_1 , packet1.algorithm_number );
- mavlink_msg_set_algorithm_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_ALGORITHM_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_ALGORITHM_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_atomic_valve_timing_tc(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_SET_ATOMIC_VALVE_TIMING_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_atomic_valve_timing_tc_t packet_in = {
- 963497464,17
- };
- mavlink_set_atomic_valve_timing_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.maximum_timing = packet_in.maximum_timing;
- packet1.servo_id = packet_in.servo_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_atomic_valve_timing_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_atomic_valve_timing_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_atomic_valve_timing_tc_pack(system_id, component_id, &msg , packet1.servo_id , packet1.maximum_timing );
- mavlink_msg_set_atomic_valve_timing_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_atomic_valve_timing_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id , packet1.maximum_timing );
- mavlink_msg_set_atomic_valve_timing_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_atomic_valve_timing_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_atomic_valve_timing_tc_send(MAVLINK_COMM_1 , packet1.servo_id , packet1.maximum_timing );
- mavlink_msg_set_atomic_valve_timing_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_ATOMIC_VALVE_TIMING_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_valve_maximum_aperture_tc(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_SET_VALVE_MAXIMUM_APERTURE_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_valve_maximum_aperture_tc_t packet_in = {
- 17.0,17
- };
- mavlink_set_valve_maximum_aperture_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.maximum_aperture = packet_in.maximum_aperture;
- packet1.servo_id = packet_in.servo_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_valve_maximum_aperture_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_valve_maximum_aperture_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_valve_maximum_aperture_tc_pack(system_id, component_id, &msg , packet1.servo_id , packet1.maximum_aperture );
- mavlink_msg_set_valve_maximum_aperture_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_valve_maximum_aperture_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id , packet1.maximum_aperture );
- mavlink_msg_set_valve_maximum_aperture_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_valve_maximum_aperture_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_valve_maximum_aperture_tc_send(MAVLINK_COMM_1 , packet1.servo_id , packet1.maximum_aperture );
- mavlink_msg_set_valve_maximum_aperture_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_VALVE_MAXIMUM_APERTURE_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_conrig_state_tc(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_CONRIG_STATE_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_conrig_state_tc_t packet_in = {
- 5,72,139,206,17,84,151
- };
- mavlink_conrig_state_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.ignition_btn = packet_in.ignition_btn;
- packet1.filling_valve_btn = packet_in.filling_valve_btn;
- packet1.venting_valve_btn = packet_in.venting_valve_btn;
- packet1.release_pressure_btn = packet_in.release_pressure_btn;
- packet1.quick_connector_btn = packet_in.quick_connector_btn;
- packet1.start_tars_btn = packet_in.start_tars_btn;
- packet1.arm_switch = packet_in.arm_switch;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_conrig_state_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_conrig_state_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_conrig_state_tc_pack(system_id, component_id, &msg , packet1.ignition_btn , packet1.filling_valve_btn , packet1.venting_valve_btn , packet1.release_pressure_btn , packet1.quick_connector_btn , packet1.start_tars_btn , packet1.arm_switch );
- mavlink_msg_conrig_state_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_conrig_state_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.ignition_btn , packet1.filling_valve_btn , packet1.venting_valve_btn , packet1.release_pressure_btn , packet1.quick_connector_btn , packet1.start_tars_btn , packet1.arm_switch );
- mavlink_msg_conrig_state_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_conrig_state_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_conrig_state_tc_send(MAVLINK_COMM_1 , packet1.ignition_btn , packet1.filling_valve_btn , packet1.venting_valve_btn , packet1.release_pressure_btn , packet1.quick_connector_btn , packet1.start_tars_btn , packet1.arm_switch );
- mavlink_msg_conrig_state_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("CONRIG_STATE_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_CONRIG_STATE_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_ignition_time_tc(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_SET_IGNITION_TIME_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_ignition_time_tc_t packet_in = {
- 963497464
- };
- mavlink_set_ignition_time_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timing = packet_in.timing;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_ignition_time_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_ignition_time_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_ignition_time_tc_pack(system_id, component_id, &msg , packet1.timing );
- mavlink_msg_set_ignition_time_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_ignition_time_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timing );
- mavlink_msg_set_ignition_time_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_ignition_time_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_ignition_time_tc_send(MAVLINK_COMM_1 , packet1.timing );
- mavlink_msg_set_ignition_time_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_IGNITION_TIME_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_IGNITION_TIME_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_ack_tm(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_ACK_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ack_tm_t packet_in = {
- 5,72
- };
- mavlink_ack_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.recv_msgid = packet_in.recv_msgid;
- packet1.seq_ack = packet_in.seq_ack;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_ACK_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ACK_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_pack(system_id, component_id, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_ack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_ack_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_send(MAVLINK_COMM_1 , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_ack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("ACK_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ACK_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_nack_tm(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_NACK_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_nack_tm_t packet_in = {
- 5,72
- };
- mavlink_nack_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.recv_msgid = packet_in.recv_msgid;
- packet1.seq_ack = packet_in.seq_ack;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_NACK_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NACK_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nack_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_nack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nack_tm_pack(system_id, component_id, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_nack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nack_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_nack_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_nack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nack_tm_send(MAVLINK_COMM_1 , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_nack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("NACK_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_NACK_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_gps_tm(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_GPS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_gps_tm_t packet_in = {
- 93372036854775807ULL,179.0,235.0,291.0,241.0,269.0,297.0,325.0,353.0,"ABCDEFGHIJKLMNOPQRS",221,32
- };
- mavlink_gps_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.latitude = packet_in.latitude;
- packet1.longitude = packet_in.longitude;
- packet1.height = packet_in.height;
- packet1.vel_north = packet_in.vel_north;
- packet1.vel_east = packet_in.vel_east;
- packet1.vel_down = packet_in.vel_down;
- packet1.speed = packet_in.speed;
- packet1.track = packet_in.track;
- packet1.fix = packet_in.fix;
- packet1.n_satellites = packet_in.n_satellites;
-
- mav_array_memcpy(packet1.sensor_name, packet_in.sensor_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_GPS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gps_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_gps_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gps_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_name , packet1.fix , packet1.latitude , packet1.longitude , packet1.height , packet1.vel_north , packet1.vel_east , packet1.vel_down , packet1.speed , packet1.track , packet1.n_satellites );
- mavlink_msg_gps_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gps_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_name , packet1.fix , packet1.latitude , packet1.longitude , packet1.height , packet1.vel_north , packet1.vel_east , packet1.vel_down , packet1.speed , packet1.track , packet1.n_satellites );
- mavlink_msg_gps_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_gps_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gps_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_name , packet1.fix , packet1.latitude , packet1.longitude , packet1.height , packet1.vel_north , packet1.vel_east , packet1.vel_down , packet1.speed , packet1.track , packet1.n_satellites );
- mavlink_msg_gps_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("GPS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_GPS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_imu_tm(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_IMU_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_imu_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,"STUVWXYZABCDEFGHIJK"
- };
- mavlink_imu_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.acc_x = packet_in.acc_x;
- packet1.acc_y = packet_in.acc_y;
- packet1.acc_z = packet_in.acc_z;
- packet1.gyro_x = packet_in.gyro_x;
- packet1.gyro_y = packet_in.gyro_y;
- packet1.gyro_z = packet_in.gyro_z;
- packet1.mag_x = packet_in.mag_x;
- packet1.mag_y = packet_in.mag_y;
- packet1.mag_z = packet_in.mag_z;
-
- mav_array_memcpy(packet1.sensor_name, packet_in.sensor_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_IMU_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_IMU_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_imu_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_imu_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_imu_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_name , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z );
- mavlink_msg_imu_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_imu_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_name , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z );
- mavlink_msg_imu_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_imu_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_imu_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_name , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z );
- mavlink_msg_imu_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("IMU_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_IMU_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_pressure_tm(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_PRESSURE_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_pressure_tm_t packet_in = {
- 93372036854775807ULL,73.0,"MNOPQRSTUVWXYZABCDE"
- };
- mavlink_pressure_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.pressure = packet_in.pressure;
-
- mav_array_memcpy(packet1.sensor_name, packet_in.sensor_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_PRESSURE_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pressure_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_pressure_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pressure_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_name , packet1.pressure );
- mavlink_msg_pressure_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pressure_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_name , packet1.pressure );
- mavlink_msg_pressure_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_pressure_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pressure_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_name , packet1.pressure );
- mavlink_msg_pressure_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("PRESSURE_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_PRESSURE_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_adc_tm(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_ADC_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_adc_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,"OPQRSTUVWXYZABCDEFG"
- };
- mavlink_adc_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.channel_0 = packet_in.channel_0;
- packet1.channel_1 = packet_in.channel_1;
- packet1.channel_2 = packet_in.channel_2;
- packet1.channel_3 = packet_in.channel_3;
- packet1.channel_4 = packet_in.channel_4;
- packet1.channel_5 = packet_in.channel_5;
- packet1.channel_6 = packet_in.channel_6;
- packet1.channel_7 = packet_in.channel_7;
-
- mav_array_memcpy(packet1.sensor_name, packet_in.sensor_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_ADC_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ADC_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adc_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_adc_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adc_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_name , packet1.channel_0 , packet1.channel_1 , packet1.channel_2 , packet1.channel_3 , packet1.channel_4 , packet1.channel_5 , packet1.channel_6 , packet1.channel_7 );
- mavlink_msg_adc_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adc_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_name , packet1.channel_0 , packet1.channel_1 , packet1.channel_2 , packet1.channel_3 , packet1.channel_4 , packet1.channel_5 , packet1.channel_6 , packet1.channel_7 );
- mavlink_msg_adc_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_adc_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adc_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_name , packet1.channel_0 , packet1.channel_1 , packet1.channel_2 , packet1.channel_3 , packet1.channel_4 , packet1.channel_5 , packet1.channel_6 , packet1.channel_7 );
- mavlink_msg_adc_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("ADC_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ADC_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_voltage_tm(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_VOLTAGE_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_voltage_tm_t packet_in = {
- 93372036854775807ULL,73.0,"MNOPQRSTUVWXYZABCDE"
- };
- mavlink_voltage_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.voltage = packet_in.voltage;
-
- mav_array_memcpy(packet1.sensor_name, packet_in.sensor_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_VOLTAGE_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_voltage_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_voltage_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_voltage_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_name , packet1.voltage );
- mavlink_msg_voltage_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_voltage_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_name , packet1.voltage );
- mavlink_msg_voltage_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_voltage_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_voltage_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_name , packet1.voltage );
- mavlink_msg_voltage_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("VOLTAGE_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_VOLTAGE_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_current_tm(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_CURRENT_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_current_tm_t packet_in = {
- 93372036854775807ULL,73.0,"MNOPQRSTUVWXYZABCDE"
- };
- mavlink_current_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.current = packet_in.current;
-
- mav_array_memcpy(packet1.sensor_name, packet_in.sensor_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_CURRENT_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_current_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_current_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_current_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_name , packet1.current );
- mavlink_msg_current_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_current_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_name , packet1.current );
- mavlink_msg_current_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_current_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_current_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_name , packet1.current );
- mavlink_msg_current_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("CURRENT_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_CURRENT_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_temp_tm(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_TEMP_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_temp_tm_t packet_in = {
- 93372036854775807ULL,73.0,"MNOPQRSTUVWXYZABCDE"
- };
- mavlink_temp_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.temperature = packet_in.temperature;
-
- mav_array_memcpy(packet1.sensor_name, packet_in.sensor_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_TEMP_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TEMP_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_temp_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_temp_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_temp_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_name , packet1.temperature );
- mavlink_msg_temp_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_temp_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_name , packet1.temperature );
- mavlink_msg_temp_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_temp_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_temp_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_name , packet1.temperature );
- mavlink_msg_temp_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("TEMP_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_TEMP_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_load_tm(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_LOAD_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_load_tm_t packet_in = {
- 93372036854775807ULL,73.0,"MNOPQRSTUVWXYZABCDE"
- };
- mavlink_load_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.load = packet_in.load;
-
- mav_array_memcpy(packet1.sensor_name, packet_in.sensor_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_LOAD_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOAD_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_load_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_load_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_load_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_name , packet1.load );
- mavlink_msg_load_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_load_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_name , packet1.load );
- mavlink_msg_load_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_load_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_load_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_name , packet1.load );
- mavlink_msg_load_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("LOAD_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_LOAD_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_attitude_tm(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_ATTITUDE_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_attitude_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,"KLMNOPQRSTUVWXYZABC"
- };
- mavlink_attitude_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.roll = packet_in.roll;
- packet1.pitch = packet_in.pitch;
- packet1.yaw = packet_in.yaw;
- packet1.quat_x = packet_in.quat_x;
- packet1.quat_y = packet_in.quat_y;
- packet1.quat_z = packet_in.quat_z;
- packet1.quat_w = packet_in.quat_w;
-
- mav_array_memcpy(packet1.sensor_name, packet_in.sensor_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_ATTITUDE_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_attitude_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_attitude_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_attitude_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_name , packet1.roll , packet1.pitch , packet1.yaw , packet1.quat_x , packet1.quat_y , packet1.quat_z , packet1.quat_w );
- mavlink_msg_attitude_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_attitude_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_name , packet1.roll , packet1.pitch , packet1.yaw , packet1.quat_x , packet1.quat_y , packet1.quat_z , packet1.quat_w );
- mavlink_msg_attitude_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_attitude_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_attitude_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_name , packet1.roll , packet1.pitch , packet1.yaw , packet1.quat_x , packet1.quat_y , packet1.quat_z , packet1.quat_w );
- mavlink_msg_attitude_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("ATTITUDE_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ATTITUDE_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_sensor_state_tm(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_SENSOR_STATE_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_sensor_state_tm_t packet_in = {
- "ABCDEFGHIJKLMNOPQRS",65
- };
- mavlink_sensor_state_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.state = packet_in.state;
-
- mav_array_memcpy(packet1.sensor_name, packet_in.sensor_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_SENSOR_STATE_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_state_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_sensor_state_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_state_tm_pack(system_id, component_id, &msg , packet1.sensor_name , packet1.state );
- mavlink_msg_sensor_state_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_state_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.sensor_name , packet1.state );
- mavlink_msg_sensor_state_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_sensor_state_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_state_tm_send(MAVLINK_COMM_1 , packet1.sensor_name , packet1.state );
- mavlink_msg_sensor_state_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SENSOR_STATE_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SENSOR_STATE_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_servo_tm(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_SERVO_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_servo_tm_t packet_in = {
- 17.0,17
- };
- mavlink_servo_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.servo_position = packet_in.servo_position;
- packet1.servo_id = packet_in.servo_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SERVO_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SERVO_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_servo_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_pack(system_id, component_id, &msg , packet1.servo_id , packet1.servo_position );
- mavlink_msg_servo_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id , packet1.servo_position );
- mavlink_msg_servo_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_servo_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_send(MAVLINK_COMM_1 , packet1.servo_id , packet1.servo_position );
- mavlink_msg_servo_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SERVO_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SERVO_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_pin_tm(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_PIN_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_pin_tm_t packet_in = {
- 93372036854775807ULL,93372036854776311ULL,53,120,187
- };
- mavlink_pin_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.last_change_timestamp = packet_in.last_change_timestamp;
- packet1.pin_id = packet_in.pin_id;
- packet1.changes_counter = packet_in.changes_counter;
- packet1.current_state = packet_in.current_state;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_PIN_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PIN_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pin_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_pin_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pin_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.pin_id , packet1.last_change_timestamp , packet1.changes_counter , packet1.current_state );
- mavlink_msg_pin_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pin_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.pin_id , packet1.last_change_timestamp , packet1.changes_counter , packet1.current_state );
- mavlink_msg_pin_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_pin_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pin_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.pin_id , packet1.last_change_timestamp , packet1.changes_counter , packet1.current_state );
- mavlink_msg_pin_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("PIN_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_PIN_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_receiver_tm(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_RECEIVER_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_receiver_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,18691,18795,18899,19003,19107,19211,19315,19419,19523,19627,149,216,27,94
- };
- mavlink_receiver_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.main_rx_rssi = packet_in.main_rx_rssi;
- packet1.main_rx_fei = packet_in.main_rx_fei;
- packet1.payload_rx_rssi = packet_in.payload_rx_rssi;
- packet1.payload_rx_fei = packet_in.payload_rx_fei;
- packet1.battery_voltage = packet_in.battery_voltage;
- packet1.main_packet_tx_error_count = packet_in.main_packet_tx_error_count;
- packet1.main_tx_bitrate = packet_in.main_tx_bitrate;
- packet1.main_packet_rx_success_count = packet_in.main_packet_rx_success_count;
- packet1.main_packet_rx_drop_count = packet_in.main_packet_rx_drop_count;
- packet1.main_rx_bitrate = packet_in.main_rx_bitrate;
- packet1.payload_packet_tx_error_count = packet_in.payload_packet_tx_error_count;
- packet1.payload_tx_bitrate = packet_in.payload_tx_bitrate;
- packet1.payload_packet_rx_success_count = packet_in.payload_packet_rx_success_count;
- packet1.payload_packet_rx_drop_count = packet_in.payload_packet_rx_drop_count;
- packet1.payload_rx_bitrate = packet_in.payload_rx_bitrate;
- packet1.main_radio_present = packet_in.main_radio_present;
- packet1.payload_radio_present = packet_in.payload_radio_present;
- packet1.ethernet_present = packet_in.ethernet_present;
- packet1.ethernet_status = packet_in.ethernet_status;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_receiver_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_receiver_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_receiver_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.main_rx_fei , packet1.payload_radio_present , packet1.payload_packet_tx_error_count , packet1.payload_tx_bitrate , packet1.payload_packet_rx_success_count , packet1.payload_packet_rx_drop_count , packet1.payload_rx_bitrate , packet1.payload_rx_rssi , packet1.payload_rx_fei , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
- mavlink_msg_receiver_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_receiver_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.main_rx_fei , packet1.payload_radio_present , packet1.payload_packet_tx_error_count , packet1.payload_tx_bitrate , packet1.payload_packet_rx_success_count , packet1.payload_packet_rx_drop_count , packet1.payload_rx_bitrate , packet1.payload_rx_rssi , packet1.payload_rx_fei , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
- mavlink_msg_receiver_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_receiver_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_receiver_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.main_rx_fei , packet1.payload_radio_present , packet1.payload_packet_tx_error_count , packet1.payload_tx_bitrate , packet1.payload_packet_rx_success_count , packet1.payload_packet_rx_drop_count , packet1.payload_rx_bitrate , packet1.payload_rx_rssi , packet1.payload_rx_fei , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
- mavlink_msg_receiver_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("RECEIVER_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_RECEIVER_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_sys_tm(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_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_sys_tm_t packet_in = {
- 93372036854775807ULL,29,96,163,230,41,108
- };
- mavlink_sys_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.logger = packet_in.logger;
- packet1.event_broker = packet_in.event_broker;
- packet1.radio = packet_in.radio;
- packet1.pin_observer = packet_in.pin_observer;
- packet1.sensors = packet_in.sensors;
- packet1.board_scheduler = packet_in.board_scheduler;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SYS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SYS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sys_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_sys_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sys_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.logger , packet1.event_broker , packet1.radio , packet1.pin_observer , packet1.sensors , packet1.board_scheduler );
- mavlink_msg_sys_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sys_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.logger , packet1.event_broker , packet1.radio , packet1.pin_observer , packet1.sensors , packet1.board_scheduler );
- mavlink_msg_sys_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_sys_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sys_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.logger , packet1.event_broker , packet1.radio , packet1.pin_observer , packet1.sensors , packet1.board_scheduler );
- mavlink_msg_sys_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SYS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SYS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_fsm_tm(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_FSM_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_fsm_tm_t packet_in = {
- 93372036854775807ULL,29,96,163,230,41,108
- };
- mavlink_fsm_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.ada_state = packet_in.ada_state;
- packet1.abk_state = packet_in.abk_state;
- packet1.dpl_state = packet_in.dpl_state;
- packet1.fmm_state = packet_in.fmm_state;
- packet1.nas_state = packet_in.nas_state;
- packet1.wes_state = packet_in.wes_state;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_FSM_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FSM_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_fsm_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_fsm_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_fsm_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.ada_state , packet1.abk_state , packet1.dpl_state , packet1.fmm_state , packet1.nas_state , packet1.wes_state );
- mavlink_msg_fsm_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_fsm_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.ada_state , packet1.abk_state , packet1.dpl_state , packet1.fmm_state , packet1.nas_state , packet1.wes_state );
- mavlink_msg_fsm_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_fsm_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_fsm_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.ada_state , packet1.abk_state , packet1.dpl_state , packet1.fmm_state , packet1.nas_state , packet1.wes_state );
- mavlink_msg_fsm_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("FSM_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_FSM_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_logger_tm(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_LOGGER_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_logger_tm_t packet_in = {
- 93372036854775807ULL,963497880,963498088,963498296,963498504,963498712,963498920,963499128,963499336,963499544,19523
- };
- mavlink_logger_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.too_large_samples = packet_in.too_large_samples;
- packet1.dropped_samples = packet_in.dropped_samples;
- packet1.queued_samples = packet_in.queued_samples;
- packet1.buffers_filled = packet_in.buffers_filled;
- packet1.buffers_written = packet_in.buffers_written;
- packet1.writes_failed = packet_in.writes_failed;
- packet1.last_write_error = packet_in.last_write_error;
- packet1.average_write_time = packet_in.average_write_time;
- packet1.max_write_time = packet_in.max_write_time;
- packet1.log_number = packet_in.log_number;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_logger_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_logger_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_logger_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.log_number , packet1.too_large_samples , packet1.dropped_samples , packet1.queued_samples , packet1.buffers_filled , packet1.buffers_written , packet1.writes_failed , packet1.last_write_error , packet1.average_write_time , packet1.max_write_time );
- mavlink_msg_logger_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_logger_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.log_number , packet1.too_large_samples , packet1.dropped_samples , packet1.queued_samples , packet1.buffers_filled , packet1.buffers_written , packet1.writes_failed , packet1.last_write_error , packet1.average_write_time , packet1.max_write_time );
- mavlink_msg_logger_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_logger_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_logger_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.log_number , packet1.too_large_samples , packet1.dropped_samples , packet1.queued_samples , packet1.buffers_filled , packet1.buffers_written , packet1.writes_failed , packet1.last_write_error , packet1.average_write_time , packet1.max_write_time );
- mavlink_msg_logger_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("LOGGER_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_LOGGER_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_mavlink_stats_tm(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_MAVLINK_STATS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_mavlink_stats_tm_t packet_in = {
- 93372036854775807ULL,963497880,17859,17963,18067,18171,18275,199,10,77,144,211,22
- };
- mavlink_mavlink_stats_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.parse_state = packet_in.parse_state;
- packet1.n_send_queue = packet_in.n_send_queue;
- packet1.max_send_queue = packet_in.max_send_queue;
- packet1.n_send_errors = packet_in.n_send_errors;
- packet1.packet_rx_success_count = packet_in.packet_rx_success_count;
- packet1.packet_rx_drop_count = packet_in.packet_rx_drop_count;
- packet1.msg_received = packet_in.msg_received;
- packet1.buffer_overrun = packet_in.buffer_overrun;
- packet1.parse_error = packet_in.parse_error;
- packet1.packet_idx = packet_in.packet_idx;
- packet1.current_rx_seq = packet_in.current_rx_seq;
- packet1.current_tx_seq = packet_in.current_tx_seq;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mavlink_stats_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_mavlink_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mavlink_stats_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.n_send_queue , packet1.max_send_queue , packet1.n_send_errors , packet1.msg_received , packet1.buffer_overrun , packet1.parse_error , packet1.parse_state , packet1.packet_idx , packet1.current_rx_seq , packet1.current_tx_seq , packet1.packet_rx_success_count , packet1.packet_rx_drop_count );
- mavlink_msg_mavlink_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mavlink_stats_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.n_send_queue , packet1.max_send_queue , packet1.n_send_errors , packet1.msg_received , packet1.buffer_overrun , packet1.parse_error , packet1.parse_state , packet1.packet_idx , packet1.current_rx_seq , packet1.current_tx_seq , packet1.packet_rx_success_count , packet1.packet_rx_drop_count );
- mavlink_msg_mavlink_stats_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_mavlink_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mavlink_stats_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.n_send_queue , packet1.max_send_queue , packet1.n_send_errors , packet1.msg_received , packet1.buffer_overrun , packet1.parse_error , packet1.parse_state , packet1.packet_idx , packet1.current_rx_seq , packet1.current_tx_seq , packet1.packet_rx_success_count , packet1.packet_rx_drop_count );
- mavlink_msg_mavlink_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("MAVLINK_STATS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_MAVLINK_STATS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_task_stats_tm(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_TASK_STATS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_task_stats_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,18483,211
- };
- mavlink_task_stats_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.task_min = packet_in.task_min;
- packet1.task_max = packet_in.task_max;
- packet1.task_mean = packet_in.task_mean;
- packet1.task_stddev = packet_in.task_stddev;
- packet1.task_period = packet_in.task_period;
- packet1.task_id = packet_in.task_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_task_stats_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_task_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_task_stats_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.task_id , packet1.task_period , packet1.task_min , packet1.task_max , packet1.task_mean , packet1.task_stddev );
- mavlink_msg_task_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_task_stats_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.task_id , packet1.task_period , packet1.task_min , packet1.task_max , packet1.task_mean , packet1.task_stddev );
- mavlink_msg_task_stats_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_task_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_task_stats_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.task_id , packet1.task_period , packet1.task_min , packet1.task_max , packet1.task_mean , packet1.task_stddev );
- mavlink_msg_task_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("TASK_STATS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_TASK_STATS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_ada_tm(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_ADA_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ada_tm_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,161
- };
- mavlink_ada_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.kalman_x0 = packet_in.kalman_x0;
- packet1.kalman_x1 = packet_in.kalman_x1;
- packet1.kalman_x2 = packet_in.kalman_x2;
- packet1.vertical_speed = packet_in.vertical_speed;
- packet1.msl_altitude = packet_in.msl_altitude;
- packet1.ref_pressure = packet_in.ref_pressure;
- packet1.ref_altitude = packet_in.ref_altitude;
- packet1.ref_temperature = packet_in.ref_temperature;
- packet1.msl_pressure = packet_in.msl_pressure;
- packet1.msl_temperature = packet_in.msl_temperature;
- packet1.dpl_altitude = packet_in.dpl_altitude;
- 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_ADA_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ADA_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ada_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ada_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ada_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.vertical_speed , packet1.msl_altitude , packet1.ref_pressure , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_pressure , packet1.msl_temperature , packet1.dpl_altitude );
- mavlink_msg_ada_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ada_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.vertical_speed , packet1.msl_altitude , packet1.ref_pressure , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_pressure , packet1.msl_temperature , packet1.dpl_altitude );
- mavlink_msg_ada_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ada_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ada_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.vertical_speed , packet1.msl_altitude , packet1.ref_pressure , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_pressure , packet1.msl_temperature , packet1.dpl_altitude );
- mavlink_msg_ada_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("ADA_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ADA_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_nas_tm(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_NAS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_nas_tm_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,437.0,465.0,493.0,521.0,233
- };
- mavlink_nas_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.nas_n = packet_in.nas_n;
- packet1.nas_e = packet_in.nas_e;
- packet1.nas_d = packet_in.nas_d;
- packet1.nas_vn = packet_in.nas_vn;
- packet1.nas_ve = packet_in.nas_ve;
- packet1.nas_vd = packet_in.nas_vd;
- packet1.nas_qx = packet_in.nas_qx;
- packet1.nas_qy = packet_in.nas_qy;
- packet1.nas_qz = packet_in.nas_qz;
- packet1.nas_qw = packet_in.nas_qw;
- packet1.nas_bias_x = packet_in.nas_bias_x;
- packet1.nas_bias_y = packet_in.nas_bias_y;
- packet1.nas_bias_z = packet_in.nas_bias_z;
- packet1.ref_pressure = packet_in.ref_pressure;
- packet1.ref_temperature = packet_in.ref_temperature;
- packet1.ref_latitude = packet_in.ref_latitude;
- packet1.ref_longitude = packet_in.ref_longitude;
- 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_NAS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NAS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nas_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_nas_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nas_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.ref_pressure , packet1.ref_temperature , packet1.ref_latitude , packet1.ref_longitude );
- mavlink_msg_nas_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nas_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.ref_pressure , packet1.ref_temperature , packet1.ref_latitude , packet1.ref_longitude );
- mavlink_msg_nas_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_nas_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nas_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.ref_pressure , packet1.ref_temperature , packet1.ref_latitude , packet1.ref_longitude );
- mavlink_msg_nas_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("NAS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_NAS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_mea_tm(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_MEA_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_mea_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,89
- };
- mavlink_mea_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.kalman_x0 = packet_in.kalman_x0;
- packet1.kalman_x1 = packet_in.kalman_x1;
- packet1.kalman_x2 = packet_in.kalman_x2;
- packet1.mass = packet_in.mass;
- packet1.corrected_pressure = packet_in.corrected_pressure;
- 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_MEA_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MEA_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mea_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_mea_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mea_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.mass , packet1.corrected_pressure );
- mavlink_msg_mea_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mea_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.mass , packet1.corrected_pressure );
- mavlink_msg_mea_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_mea_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mea_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.mass , packet1.corrected_pressure );
- mavlink_msg_mea_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("MEA_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_MEA_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_rocket_flight_tm(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_ROCKET_FLIGHT_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_rocket_flight_tm_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,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,1081.0,1109.0,1137.0,241,52,119,186,253,64,131,198,9,76,143,210
- };
- mavlink_rocket_flight_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.pressure_ada = packet_in.pressure_ada;
- packet1.pressure_digi = packet_in.pressure_digi;
- packet1.pressure_static = packet_in.pressure_static;
- packet1.pressure_dpl = packet_in.pressure_dpl;
- packet1.airspeed_pitot = packet_in.airspeed_pitot;
- packet1.altitude_agl = packet_in.altitude_agl;
- packet1.ada_vert_speed = packet_in.ada_vert_speed;
- packet1.mea_mass = packet_in.mea_mass;
- packet1.acc_x = packet_in.acc_x;
- packet1.acc_y = packet_in.acc_y;
- packet1.acc_z = packet_in.acc_z;
- packet1.gyro_x = packet_in.gyro_x;
- packet1.gyro_y = packet_in.gyro_y;
- packet1.gyro_z = packet_in.gyro_z;
- packet1.mag_x = packet_in.mag_x;
- packet1.mag_y = packet_in.mag_y;
- packet1.mag_z = packet_in.mag_z;
- packet1.gps_lat = packet_in.gps_lat;
- packet1.gps_lon = packet_in.gps_lon;
- packet1.gps_alt = packet_in.gps_alt;
- packet1.abk_angle = packet_in.abk_angle;
- packet1.nas_n = packet_in.nas_n;
- packet1.nas_e = packet_in.nas_e;
- packet1.nas_d = packet_in.nas_d;
- packet1.nas_vn = packet_in.nas_vn;
- packet1.nas_ve = packet_in.nas_ve;
- packet1.nas_vd = packet_in.nas_vd;
- packet1.nas_qx = packet_in.nas_qx;
- packet1.nas_qy = packet_in.nas_qy;
- packet1.nas_qz = packet_in.nas_qz;
- packet1.nas_qw = packet_in.nas_qw;
- packet1.nas_bias_x = packet_in.nas_bias_x;
- packet1.nas_bias_y = packet_in.nas_bias_y;
- packet1.nas_bias_z = packet_in.nas_bias_z;
- packet1.pin_quick_connector = packet_in.pin_quick_connector;
- packet1.battery_voltage = packet_in.battery_voltage;
- packet1.cam_battery_voltage = packet_in.cam_battery_voltage;
- packet1.current_consumption = packet_in.current_consumption;
- packet1.temperature = packet_in.temperature;
- packet1.ada_state = packet_in.ada_state;
- packet1.fmm_state = packet_in.fmm_state;
- packet1.dpl_state = packet_in.dpl_state;
- packet1.abk_state = packet_in.abk_state;
- packet1.nas_state = packet_in.nas_state;
- packet1.mea_state = packet_in.mea_state;
- packet1.gps_fix = packet_in.gps_fix;
- packet1.pin_launch = packet_in.pin_launch;
- packet1.pin_nosecone = packet_in.pin_nosecone;
- packet1.pin_expulsion = packet_in.pin_expulsion;
- packet1.cutter_presence = packet_in.cutter_presence;
- packet1.logger_error = packet_in.logger_error;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_flight_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_rocket_flight_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_quick_connector , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.temperature , packet1.logger_error );
- mavlink_msg_rocket_flight_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_quick_connector , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.temperature , packet1.logger_error );
- mavlink_msg_rocket_flight_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_rocket_flight_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_quick_connector , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.temperature , packet1.logger_error );
- mavlink_msg_rocket_flight_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("ROCKET_FLIGHT_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ROCKET_FLIGHT_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_payload_flight_tm(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_PAYLOAD_FLIGHT_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_payload_flight_tm_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,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,1081.0,217,28,95,162,229,40,107
- };
- mavlink_payload_flight_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.pressure_digi = packet_in.pressure_digi;
- packet1.pressure_static = packet_in.pressure_static;
- packet1.airspeed_pitot = packet_in.airspeed_pitot;
- packet1.altitude_agl = packet_in.altitude_agl;
- packet1.acc_x = packet_in.acc_x;
- packet1.acc_y = packet_in.acc_y;
- packet1.acc_z = packet_in.acc_z;
- packet1.gyro_x = packet_in.gyro_x;
- packet1.gyro_y = packet_in.gyro_y;
- packet1.gyro_z = packet_in.gyro_z;
- packet1.mag_x = packet_in.mag_x;
- packet1.mag_y = packet_in.mag_y;
- packet1.mag_z = packet_in.mag_z;
- packet1.gps_lat = packet_in.gps_lat;
- packet1.gps_lon = packet_in.gps_lon;
- packet1.gps_alt = packet_in.gps_alt;
- packet1.left_servo_angle = packet_in.left_servo_angle;
- packet1.right_servo_angle = packet_in.right_servo_angle;
- packet1.nas_n = packet_in.nas_n;
- packet1.nas_e = packet_in.nas_e;
- packet1.nas_d = packet_in.nas_d;
- packet1.nas_vn = packet_in.nas_vn;
- packet1.nas_ve = packet_in.nas_ve;
- packet1.nas_vd = packet_in.nas_vd;
- packet1.nas_qx = packet_in.nas_qx;
- packet1.nas_qy = packet_in.nas_qy;
- packet1.nas_qz = packet_in.nas_qz;
- packet1.nas_qw = packet_in.nas_qw;
- packet1.nas_bias_x = packet_in.nas_bias_x;
- packet1.nas_bias_y = packet_in.nas_bias_y;
- packet1.nas_bias_z = packet_in.nas_bias_z;
- packet1.wes_n = packet_in.wes_n;
- packet1.wes_e = packet_in.wes_e;
- packet1.battery_voltage = packet_in.battery_voltage;
- packet1.cam_battery_voltage = packet_in.cam_battery_voltage;
- packet1.current_consumption = packet_in.current_consumption;
- packet1.temperature = packet_in.temperature;
- packet1.fmm_state = packet_in.fmm_state;
- packet1.nas_state = packet_in.nas_state;
- packet1.wes_state = packet_in.wes_state;
- packet1.gps_fix = packet_in.gps_fix;
- packet1.pin_nosecone = packet_in.pin_nosecone;
- packet1.cutter_presence = packet_in.cutter_presence;
- packet1.logger_error = packet_in.logger_error;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_flight_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_payload_flight_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.cutter_presence , packet1.temperature , packet1.logger_error );
- mavlink_msg_payload_flight_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.cutter_presence , packet1.temperature , packet1.logger_error );
- mavlink_msg_payload_flight_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_payload_flight_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.cutter_presence , packet1.temperature , packet1.logger_error );
- mavlink_msg_payload_flight_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("PAYLOAD_FLIGHT_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_rocket_stats_tm(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_ROCKET_STATS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_rocket_stats_tm_t packet_in = {
- 93372036854775807ULL,93372036854776311ULL,93372036854776815ULL,93372036854777319ULL,93372036854777823ULL,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,605.0,963502040
- };
- mavlink_rocket_stats_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.liftoff_ts = packet_in.liftoff_ts;
- packet1.liftoff_max_acc_ts = packet_in.liftoff_max_acc_ts;
- packet1.dpl_ts = packet_in.dpl_ts;
- packet1.max_z_speed_ts = packet_in.max_z_speed_ts;
- packet1.apogee_ts = packet_in.apogee_ts;
- packet1.liftoff_max_acc = packet_in.liftoff_max_acc;
- packet1.dpl_max_acc = packet_in.dpl_max_acc;
- packet1.max_z_speed = packet_in.max_z_speed;
- packet1.max_airspeed_pitot = packet_in.max_airspeed_pitot;
- packet1.max_speed_altitude = packet_in.max_speed_altitude;
- packet1.apogee_lat = packet_in.apogee_lat;
- packet1.apogee_lon = packet_in.apogee_lon;
- packet1.apogee_alt = packet_in.apogee_alt;
- packet1.min_pressure = packet_in.min_pressure;
- packet1.ada_min_pressure = packet_in.ada_min_pressure;
- packet1.dpl_vane_max_pressure = packet_in.dpl_vane_max_pressure;
- packet1.cpu_load = packet_in.cpu_load;
- packet1.free_heap = packet_in.free_heap;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_stats_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_rocket_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_stats_tm_pack(system_id, component_id, &msg , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.ada_min_pressure , packet1.dpl_vane_max_pressure , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_rocket_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_stats_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.ada_min_pressure , packet1.dpl_vane_max_pressure , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_rocket_stats_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_rocket_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_stats_tm_send(MAVLINK_COMM_1 , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.ada_min_pressure , packet1.dpl_vane_max_pressure , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_rocket_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("ROCKET_STATS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ROCKET_STATS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_payload_stats_tm(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_PAYLOAD_STATS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_payload_stats_tm_t packet_in = {
- 93372036854775807ULL,93372036854776311ULL,93372036854776815ULL,93372036854777319ULL,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,963501208
- };
- mavlink_payload_stats_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.liftoff_max_acc_ts = packet_in.liftoff_max_acc_ts;
- packet1.dpl_ts = packet_in.dpl_ts;
- packet1.max_z_speed_ts = packet_in.max_z_speed_ts;
- packet1.apogee_ts = packet_in.apogee_ts;
- packet1.liftoff_max_acc = packet_in.liftoff_max_acc;
- packet1.dpl_max_acc = packet_in.dpl_max_acc;
- packet1.max_z_speed = packet_in.max_z_speed;
- packet1.max_airspeed_pitot = packet_in.max_airspeed_pitot;
- packet1.max_speed_altitude = packet_in.max_speed_altitude;
- packet1.apogee_lat = packet_in.apogee_lat;
- packet1.apogee_lon = packet_in.apogee_lon;
- packet1.apogee_alt = packet_in.apogee_alt;
- packet1.min_pressure = packet_in.min_pressure;
- packet1.cpu_load = packet_in.cpu_load;
- packet1.free_heap = packet_in.free_heap;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_stats_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_payload_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_stats_tm_pack(system_id, component_id, &msg , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_payload_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_stats_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_payload_stats_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_payload_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_stats_tm_send(MAVLINK_COMM_1 , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_payload_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("PAYLOAD_STATS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_PAYLOAD_STATS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_gse_tm(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_GSE_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_gse_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,101,168,235,46,113,180,247,58,125,192
- };
- mavlink_gse_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.loadcell_rocket = packet_in.loadcell_rocket;
- packet1.loadcell_vessel = packet_in.loadcell_vessel;
- packet1.filling_pressure = packet_in.filling_pressure;
- packet1.vessel_pressure = packet_in.vessel_pressure;
- packet1.battery_voltage = packet_in.battery_voltage;
- packet1.current_consumption = packet_in.current_consumption;
- packet1.arming_state = packet_in.arming_state;
- packet1.filling_valve_state = packet_in.filling_valve_state;
- packet1.venting_valve_state = packet_in.venting_valve_state;
- packet1.release_valve_state = packet_in.release_valve_state;
- packet1.main_valve_state = packet_in.main_valve_state;
- packet1.ignition_state = packet_in.ignition_state;
- packet1.tars_state = packet_in.tars_state;
- packet1.main_board_status = packet_in.main_board_status;
- packet1.payload_board_status = packet_in.payload_board_status;
- packet1.motor_board_status = packet_in.motor_board_status;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_GSE_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GSE_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gse_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_gse_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gse_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.loadcell_rocket , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.ignition_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption , packet1.main_board_status , packet1.payload_board_status , packet1.motor_board_status );
- mavlink_msg_gse_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gse_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.loadcell_rocket , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.ignition_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption , packet1.main_board_status , packet1.payload_board_status , packet1.motor_board_status );
- mavlink_msg_gse_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_gse_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gse_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.loadcell_rocket , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.ignition_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption , packet1.main_board_status , packet1.payload_board_status , packet1.motor_board_status );
- mavlink_msg_gse_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("GSE_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_GSE_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_motor_tm(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_MOTOR_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_motor_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,101,168,235
- };
- mavlink_motor_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.top_tank_pressure = packet_in.top_tank_pressure;
- packet1.bottom_tank_pressure = packet_in.bottom_tank_pressure;
- packet1.combustion_chamber_pressure = packet_in.combustion_chamber_pressure;
- packet1.tank_temperature = packet_in.tank_temperature;
- packet1.battery_voltage = packet_in.battery_voltage;
- packet1.current_consumption = packet_in.current_consumption;
- packet1.floating_level = packet_in.floating_level;
- packet1.main_valve_state = packet_in.main_valve_state;
- packet1.venting_valve_state = packet_in.venting_valve_state;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_motor_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_motor_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_motor_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.floating_level , packet1.tank_temperature , packet1.main_valve_state , packet1.venting_valve_state , packet1.battery_voltage , packet1.current_consumption );
- mavlink_msg_motor_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_motor_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.floating_level , packet1.tank_temperature , packet1.main_valve_state , packet1.venting_valve_state , packet1.battery_voltage , packet1.current_consumption );
- mavlink_msg_motor_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_motor_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_motor_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.floating_level , packet1.tank_temperature , packet1.main_valve_state , packet1.venting_valve_state , packet1.battery_voltage , packet1.current_consumption );
- mavlink_msg_motor_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("MOTOR_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_MOTOR_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_gemini(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
-{
- mavlink_test_ping_tc(system_id, component_id, last_msg);
- mavlink_test_command_tc(system_id, component_id, last_msg);
- mavlink_test_system_tm_request_tc(system_id, component_id, last_msg);
- mavlink_test_sensor_tm_request_tc(system_id, component_id, last_msg);
- mavlink_test_servo_tm_request_tc(system_id, component_id, last_msg);
- mavlink_test_set_servo_angle_tc(system_id, component_id, last_msg);
- mavlink_test_wiggle_servo_tc(system_id, component_id, last_msg);
- mavlink_test_reset_servo_tc(system_id, component_id, last_msg);
- mavlink_test_set_reference_altitude_tc(system_id, component_id, last_msg);
- mavlink_test_set_reference_temperature_tc(system_id, component_id, last_msg);
- mavlink_test_set_orientation_tc(system_id, component_id, last_msg);
- mavlink_test_set_coordinates_tc(system_id, component_id, last_msg);
- mavlink_test_raw_event_tc(system_id, component_id, last_msg);
- mavlink_test_set_deployment_altitude_tc(system_id, component_id, last_msg);
- mavlink_test_set_target_coordinates_tc(system_id, component_id, last_msg);
- mavlink_test_set_algorithm_tc(system_id, component_id, last_msg);
- mavlink_test_set_atomic_valve_timing_tc(system_id, component_id, last_msg);
- mavlink_test_set_valve_maximum_aperture_tc(system_id, component_id, last_msg);
- mavlink_test_conrig_state_tc(system_id, component_id, last_msg);
- mavlink_test_set_ignition_time_tc(system_id, component_id, last_msg);
- mavlink_test_ack_tm(system_id, component_id, last_msg);
- mavlink_test_nack_tm(system_id, component_id, last_msg);
- mavlink_test_gps_tm(system_id, component_id, last_msg);
- mavlink_test_imu_tm(system_id, component_id, last_msg);
- mavlink_test_pressure_tm(system_id, component_id, last_msg);
- mavlink_test_adc_tm(system_id, component_id, last_msg);
- mavlink_test_voltage_tm(system_id, component_id, last_msg);
- mavlink_test_current_tm(system_id, component_id, last_msg);
- mavlink_test_temp_tm(system_id, component_id, last_msg);
- mavlink_test_load_tm(system_id, component_id, last_msg);
- mavlink_test_attitude_tm(system_id, component_id, last_msg);
- mavlink_test_sensor_state_tm(system_id, component_id, last_msg);
- mavlink_test_servo_tm(system_id, component_id, last_msg);
- mavlink_test_pin_tm(system_id, component_id, last_msg);
- mavlink_test_receiver_tm(system_id, component_id, last_msg);
- mavlink_test_sys_tm(system_id, component_id, last_msg);
- mavlink_test_fsm_tm(system_id, component_id, last_msg);
- mavlink_test_logger_tm(system_id, component_id, last_msg);
- mavlink_test_mavlink_stats_tm(system_id, component_id, last_msg);
- mavlink_test_task_stats_tm(system_id, component_id, last_msg);
- mavlink_test_ada_tm(system_id, component_id, last_msg);
- mavlink_test_nas_tm(system_id, component_id, last_msg);
- mavlink_test_mea_tm(system_id, component_id, last_msg);
- mavlink_test_rocket_flight_tm(system_id, component_id, last_msg);
- mavlink_test_payload_flight_tm(system_id, component_id, last_msg);
- mavlink_test_rocket_stats_tm(system_id, component_id, last_msg);
- mavlink_test_payload_stats_tm(system_id, component_id, last_msg);
- mavlink_test_gse_tm(system_id, component_id, last_msg);
- mavlink_test_motor_tm(system_id, component_id, last_msg);
-}
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // GEMINI_TESTSUITE_H
diff --git a/mavlink_lib/gemini/version.h b/mavlink_lib/gemini/version.h
deleted file mode 100644
index f4f68c4f78292ce762029dae3cb375b8e2d84d9c..0000000000000000000000000000000000000000
--- a/mavlink_lib/gemini/version.h
+++ /dev/null
@@ -1,14 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol built from gemini.xml
- * @see http://mavlink.org
- */
-#pragma once
-
-#ifndef MAVLINK_VERSION_H
-#define MAVLINK_VERSION_H
-
-#define MAVLINK_BUILD_DATE "Wed Sep 13 2023"
-#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
-#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 176
-
-#endif // MAVLINK_VERSION_H
diff --git a/mavlink_lib/hermes/StatusRepos.h b/mavlink_lib/hermes/StatusRepos.h
deleted file mode 100644
index afb541ae14b5c65fdf0efeeee763798dc31e1b53..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/StatusRepos.h
+++ /dev/null
@@ -1,130 +0,0 @@
-/** @file
- * @brief Skyward Status Repository
- */
-#pragma once
-
-namespace StatusRepo
-{
- /* Enumeration of all possible TMs */
- enum MavTMList: uint8_t
- {
- MAV_ACK_TM_ID,
- MAV_NACK_TM_ID,
- MAV_SYS_TM_ID,
- MAV_FMM_TM_ID,
- MAV_LOGGER_TM_ID,
- MAV_TMTC_TM_ID,
- MAV_SM_TM_ID,
- MAV_IGN_TM_ID,
- MAV_DPL_TM_ID,
- MAV_ADA_TM_ID,
- MAV_CAN_TM_ID,
- MAV_ADC_TM_ID,
- MAV_ADIS_TM_ID,
- MAV_MPU_TM_ID,
- MAV_GPS_TM_ID,
- MAV_HR_TM_ID,
- MAV_LR_TM_ID,
- MAV_TEST_TM_ID,
-
- };
-
- /* Struct containing all tms in the form of mavlink structs */
- static struct status_repo_t
- {
- mavlink_ack_tm_t ack_tm;
- mavlink_nack_tm_t nack_tm;
- mavlink_sys_tm_t sys_tm;
- mavlink_fmm_tm_t fmm_tm;
- mavlink_logger_tm_t logger_tm;
- mavlink_tmtc_tm_t tmtc_tm;
- mavlink_sm_tm_t sm_tm;
- mavlink_ign_tm_t ign_tm;
- mavlink_dpl_tm_t dpl_tm;
- mavlink_ada_tm_t ada_tm;
- mavlink_can_tm_t can_tm;
- mavlink_adc_tm_t adc_tm;
- mavlink_adis_tm_t adis_tm;
- mavlink_mpu_tm_t mpu_tm;
- mavlink_gps_tm_t gps_tm;
- mavlink_hr_tm_t hr_tm;
- mavlink_lr_tm_t lr_tm;
- mavlink_test_tm_t test_tm;
-
- } status repo;
-
- /**
- * Retrieve one of the telemetry structs
- * @req_tm required telemetry
- * @return packed mavlink struct of that telemetry
- */
- static mavlink_message_t getTM(uint8_t req_tm, uint8_t sys_id, uint8_t comp_id)
- {
- mavlink_message_t m;
-
- switch (req_tm)
- {
- case MavTMList::MAV_ACK_TM_ID:
- mavlink_msg_ack_tm_encode(sys_id, comp_id, &m, &(repo.ack_tm));
- break;
- case MavTMList::MAV_NACK_TM_ID:
- mavlink_msg_nack_tm_encode(sys_id, comp_id, &m, &(repo.nack_tm));
- break;
- case MavTMList::MAV_SYS_TM_ID:
- mavlink_msg_sys_tm_encode(sys_id, comp_id, &m, &(repo.sys_tm));
- break;
- case MavTMList::MAV_FMM_TM_ID:
- mavlink_msg_fmm_tm_encode(sys_id, comp_id, &m, &(repo.fmm_tm));
- break;
- case MavTMList::MAV_LOGGER_TM_ID:
- mavlink_msg_logger_tm_encode(sys_id, comp_id, &m, &(repo.logger_tm));
- break;
- case MavTMList::MAV_TMTC_TM_ID:
- mavlink_msg_tmtc_tm_encode(sys_id, comp_id, &m, &(repo.tmtc_tm));
- break;
- case MavTMList::MAV_SM_TM_ID:
- mavlink_msg_sm_tm_encode(sys_id, comp_id, &m, &(repo.sm_tm));
- break;
- case MavTMList::MAV_IGN_TM_ID:
- mavlink_msg_ign_tm_encode(sys_id, comp_id, &m, &(repo.ign_tm));
- break;
- case MavTMList::MAV_DPL_TM_ID:
- mavlink_msg_dpl_tm_encode(sys_id, comp_id, &m, &(repo.dpl_tm));
- break;
- case MavTMList::MAV_ADA_TM_ID:
- mavlink_msg_ada_tm_encode(sys_id, comp_id, &m, &(repo.ada_tm));
- break;
- case MavTMList::MAV_CAN_TM_ID:
- mavlink_msg_can_tm_encode(sys_id, comp_id, &m, &(repo.can_tm));
- break;
- case MavTMList::MAV_ADC_TM_ID:
- mavlink_msg_adc_tm_encode(sys_id, comp_id, &m, &(repo.adc_tm));
- break;
- case MavTMList::MAV_ADIS_TM_ID:
- mavlink_msg_adis_tm_encode(sys_id, comp_id, &m, &(repo.adis_tm));
- break;
- case MavTMList::MAV_MPU_TM_ID:
- mavlink_msg_mpu_tm_encode(sys_id, comp_id, &m, &(repo.mpu_tm));
- break;
- case MavTMList::MAV_GPS_TM_ID:
- mavlink_msg_gps_tm_encode(sys_id, comp_id, &m, &(repo.gps_tm));
- break;
- case MavTMList::MAV_HR_TM_ID:
- mavlink_msg_hr_tm_encode(sys_id, comp_id, &m, &(repo.hr_tm));
- break;
- case MavTMList::MAV_LR_TM_ID:
- mavlink_msg_lr_tm_encode(sys_id, comp_id, &m, &(repo.lr_tm));
- break;
- case MavTMList::MAV_TEST_TM_ID:
- mavlink_msg_test_tm_encode(sys_id, comp_id, &m, &(repo.test_tm));
- break;
-
- default:
- // TODO: manage error
- break;
- }
-
- return m;
- }
-
-}
diff --git a/mavlink_lib/hermes/hermes.h b/mavlink_lib/hermes/hermes.h
deleted file mode 100644
index 2a7c92f21c3a755292f772707aaccce6c18b1dcb..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/hermes.h
+++ /dev/null
@@ -1,156 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol generated from hermes.xml
- * @see http://mavlink.org
- */
-#pragma once
-#ifndef MAVLINK_HERMES_H
-#define MAVLINK_HERMES_H
-
-#ifndef MAVLINK_H
- #error Wrong include order: MAVLINK_HERMES.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
-
-#undef MAVLINK_THIS_XML_IDX
-#define MAVLINK_THIS_XML_IDX 0
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-// MESSAGE LENGTHS AND CRCS
-
-#ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {0, 8, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 5, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 29, 46, 28, 59, 17, 18, 69, 22, 38, 56, 48, 53, 0, 0, 0, 0, 0, 0, 0, 104, 40, 29, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
-#endif
-
-#ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {0, 136, 0, 0, 0, 0, 0, 0, 0, 0, 77, 0, 0, 0, 0, 0, 0, 0, 0, 0, 43, 90, 0, 0, 0, 0, 0, 0, 0, 0, 105, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 191, 87, 163, 164, 154, 196, 240, 204, 92, 230, 35, 57, 204, 0, 0, 0, 0, 0, 0, 0, 142, 249, 126, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
-#endif
-
-#include "../protocol.h"
-
-#define MAVLINK_ENABLED_HERMES
-
-// ENUM DEFINITIONS
-
-
-/** @brief Enum list for all the telemetries that can be requested from ground. */
-#ifndef HAVE_ENUM_MavTMList
-#define HAVE_ENUM_MavTMList
-typedef enum MavTMList
-{
- MAV_SYS_TM_ID=1, /* State of system components and FMM | */
- MAV_FMM_TM_ID=2, /* State of system components and FMM | */
- MAV_LOGGER_TM_ID=3, /* SD Logger stats | */
- MAV_TMTC_TM_ID=4, /* TMTC status (mavlink + queue) | */
- MAV_SM_TM_ID=5, /* Sensor Manager Status | */
- MAV_IGN_TM_ID=6, /* Ignition system Status | */
- MAV_DPL_TM_ID=7, /* Deployment System Status | */
- MAV_ADA_TM_ID=8, /* ADA Status | */
- MAV_CAN_TM_ID=9, /* Canbus stats | */
- MAV_ADC_TM_ID=10, /* Analog Digital Converter data | */
- MAV_ADIS_TM_ID=11, /* ADIS data | */
- MAV_MPU_TM_ID=12, /* MPU9250 data | */
- MAV_GPS_TM_ID=13, /* Piksi GPS data | */
- MAV_HR_TM_ID=20, /* High Rate telemetry | */
- MAV_LR_TM_ID=21, /* Low Rate telemetry | */
- MAV_TEST_TM_ID=22, /* Test telemetry | */
- MavTMList_ENUM_END=23, /* | */
-} MavTMList;
-#endif
-
-/** @brief Enum of the commands that don't have any message payload. */
-#ifndef HAVE_ENUM_MavCommandList
-#define HAVE_ENUM_MavCommandList
-typedef enum MavCommandList
-{
- MAV_CMD_ARM=10, /* Command to arm the rocket. | */
- MAV_CMD_DISARM=15, /* Command to disarm the rocket. | */
- MAV_CMD_FORCE_LAUNCH=16, /* Command to disarm the rocket. | */
- MAV_CMD_CALIBRATE_ADA=23, /* Command to set the reference altitude. | */
- MAV_CMD_FORCE_INIT=52, /* Command to force the initialization even if there where errors. | */
- MAV_CMD_NOSECONE_OPEN=60, /* Command to open the nosecone. | */
- MAV_CMD_RESET_SERVO=61, /* Command to reset the deployment servo-motor to the "closed" position | */
- MAV_CMD_WIGGLE_SERVO=62, /* Command to wiggle the deployment servo-motor to check if it's working | */
- MAV_CMD_CUT_DROGUE=65, /* Command to activate the thermal cutters and cut the drogue, activating both thermal cutters sequentially | */
- MAV_CMD_CUT_PRIMARY=66, /* Command to activate the primary cutter | */
- MAV_CMD_CUT_BACKUP=67, /* Command to activate the backup cutter | */
- MAV_CMD_TEST_PRIMARY_CUTTER=68, /* Command to test the primary cutter | */
- MAV_CMD_TEST_BACKUP_CUTTER=69, /* Command to test the backup cutter | */
- MAV_CMD_START_LOGGING=70, /* Command to enable sensor logging. | */
- MAV_CMD_STOP_LOGGING=71, /* Command to disable sensor logging. | */
- MAV_CMD_CLOSE_LOG=72, /* Command to permanently close the log file. | */
- MAV_CMD_END_MISSION=100, /* Command to communicate the end of the mission and close the file descriptors in the SD card. | */
- MAV_CMD_TEST_MODE=200, /* Command to enter the test mode. | */
- MAV_CMD_BOARD_RESET=201, /* Command to reset the board from test status. | */
- MavCommandList_ENUM_END=202, /* | */
-} MavCommandList;
-#endif
-
-/** @brief Enum of the commands that don't have any message payload. */
-#ifndef HAVE_ENUM_MavSettingList
-#define HAVE_ENUM_MavSettingList
-typedef enum MavSettingList
-{
- MAV_SET_DEPLOYMENT_ALTITUDE=1, /* Command to arm the rocket. | */
- MAV_SET_REFERENCE_TEMP=2, /* Command to set the reference temperature. | */
- MAV_SET_REFERENCE_ALTITUDE=3, /* Command to set the reference altitude. | */
- MavSettingList_ENUM_END=4, /* | */
-} MavSettingList;
-#endif
-
-// MAVLINK VERSION
-
-#ifndef MAVLINK_VERSION
-#define MAVLINK_VERSION 2
-#endif
-
-#if (MAVLINK_VERSION == 0)
-#undef MAVLINK_VERSION
-#define MAVLINK_VERSION 2
-#endif
-
-// MESSAGE DEFINITIONS
-#include "./mavlink_msg_ping_tc.h"
-#include "./mavlink_msg_noarg_tc.h"
-#include "./mavlink_msg_start_launch_tc.h"
-#include "./mavlink_msg_upload_setting_tc.h"
-#include "./mavlink_msg_telemetry_request_tc.h"
-#include "./mavlink_msg_raw_event_tc.h"
-#include "./mavlink_msg_ack_tm.h"
-#include "./mavlink_msg_nack_tm.h"
-#include "./mavlink_msg_sys_tm.h"
-#include "./mavlink_msg_fmm_tm.h"
-#include "./mavlink_msg_logger_tm.h"
-#include "./mavlink_msg_tmtc_tm.h"
-#include "./mavlink_msg_sm_tm.h"
-#include "./mavlink_msg_ign_tm.h"
-#include "./mavlink_msg_dpl_tm.h"
-#include "./mavlink_msg_ada_tm.h"
-#include "./mavlink_msg_can_tm.h"
-#include "./mavlink_msg_adc_tm.h"
-#include "./mavlink_msg_adis_tm.h"
-#include "./mavlink_msg_mpu_tm.h"
-#include "./mavlink_msg_gps_tm.h"
-#include "./mavlink_msg_hr_tm.h"
-#include "./mavlink_msg_lr_tm.h"
-#include "./mavlink_msg_test_tm.h"
-
-// base include
-
-
-#undef MAVLINK_THIS_XML_IDX
-#define MAVLINK_THIS_XML_IDX 0
-
-#if MAVLINK_THIS_XML_IDX == MAVLINK_PRIMARY_XML_IDX
-# define MAVLINK_MESSAGE_INFO {{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_NOARG_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_START_LAUNCH_TC, MAVLINK_MESSAGE_INFO_UPLOAD_SETTING_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_TELEMETRY_REQUEST_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_RAW_EVENT_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACK_TM, MAVLINK_MESSAGE_INFO_NACK_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_TM, MAVLINK_MESSAGE_INFO_FMM_TM, MAVLINK_MESSAGE_INFO_LOGGER_TM, MAVLINK_MESSAGE_INFO_TMTC_TM, MAVLINK_MESSAGE_INFO_SM_TM, MAVLINK_MESSAGE_INFO_IGN_TM, MAVLINK_MESSAGE_INFO_DPL_TM, MAVLINK_MESSAGE_INFO_ADA_TM, MAVLINK_MESSAGE_INFO_CAN_TM, MAVLINK_MESSAGE_INFO_ADC_TM, MAVLINK_MESSAGE_INFO_ADIS_TM, MAVLINK_MESSAGE_INFO_MPU_TM, MAVLINK_MESSAGE_INFO_GPS_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_HR_TM, MAVLINK_MESSAGE_INFO_LR_TM, MAVLINK_MESSAGE_INFO_TEST_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
-# define MAVLINK_MESSAGE_NAMES {{ "ACK_TM", 130 }, { "ADA_TM", 167 }, { "ADC_TM", 169 }, { "ADIS_TM", 170 }, { "CAN_TM", 168 }, { "DPL_TM", 166 }, { "FMM_TM", 161 }, { "GPS_TM", 172 }, { "HR_TM", 180 }, { "IGN_TM", 165 }, { "LOGGER_TM", 162 }, { "LR_TM", 181 }, { "MPU_TM", 171 }, { "NACK_TM", 131 }, { "NOARG_TC", 10 }, { "PING_TC", 1 }, { "RAW_EVENT_TC", 80 }, { "SM_TM", 164 }, { "START_LAUNCH_TC", 20 }, { "SYS_TM", 160 }, { "TELEMETRY_REQUEST_TC", 30 }, { "TEST_TM", 182 }, { "TMTC_TM", 163 }, { "UPLOAD_SETTING_TC", 21 }}
-# if MAVLINK_COMMAND_24BIT
-# include "../mavlink_get_info.h"
-# endif
-#endif
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // MAVLINK_HERMES_H
diff --git a/mavlink_lib/hermes/mavlink.h b/mavlink_lib/hermes/mavlink.h
deleted file mode 100644
index d737a9c35f574305af39ee9d73aa9c590f120511..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink.h
+++ /dev/null
@@ -1,34 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol built from hermes.xml
- * @see http://mavlink.org
- */
-#pragma once
-#ifndef MAVLINK_H
-#define MAVLINK_H
-
-#define MAVLINK_PRIMARY_XML_IDX 0
-
-#ifndef MAVLINK_STX
-#define MAVLINK_STX 254
-#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 0
-#endif
-
-#include "version.h"
-#include "hermes.h"
-
-#endif // MAVLINK_H
diff --git a/mavlink_lib/hermes/mavlink_msg_ack_tm.h b/mavlink_lib/hermes/mavlink_msg_ack_tm.h
deleted file mode 100644
index cde26ee2c5160270c275dc1ab1c228d0890bc741..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_ack_tm.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE ACK_TM PACKING
-
-#define MAVLINK_MSG_ID_ACK_TM 130
-
-MAVPACKED(
-typedef struct __mavlink_ack_tm_t {
- uint8_t recv_msgid; /*< Message id of the received message.*/
- uint8_t seq_ack; /*< Sequence number of the received message.*/
-}) mavlink_ack_tm_t;
-
-#define MAVLINK_MSG_ID_ACK_TM_LEN 2
-#define MAVLINK_MSG_ID_ACK_TM_MIN_LEN 2
-#define MAVLINK_MSG_ID_130_LEN 2
-#define MAVLINK_MSG_ID_130_MIN_LEN 2
-
-#define MAVLINK_MSG_ID_ACK_TM_CRC 50
-#define MAVLINK_MSG_ID_130_CRC 50
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ACK_TM { \
- 130, \
- "ACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_ack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_ack_tm_t, seq_ack) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ACK_TM { \
- "ACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_ack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_ack_tm_t, seq_ack) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ack_tm 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 recv_msgid Message id of the received message.
- * @param seq_ack Sequence number of the received message.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ack_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACK_TM_LEN);
-#else
- mavlink_ack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ACK_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-}
-
-/**
- * @brief Pack a ack_tm 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 recv_msgid Message id of the received message.
- * @param seq_ack Sequence number of the received message.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ack_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t recv_msgid,uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACK_TM_LEN);
-#else
- mavlink_ack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ACK_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-}
-
-/**
- * @brief Encode a ack_tm 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 ack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ack_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ack_tm_t* ack_tm)
-{
- return mavlink_msg_ack_tm_pack(system_id, component_id, msg, ack_tm->recv_msgid, ack_tm->seq_ack);
-}
-
-/**
- * @brief Encode a ack_tm 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 ack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ack_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ack_tm_t* ack_tm)
-{
- return mavlink_msg_ack_tm_pack_chan(system_id, component_id, chan, msg, ack_tm->recv_msgid, ack_tm->seq_ack);
-}
-
-/**
- * @brief Send a ack_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param recv_msgid Message id of the received message.
- * @param seq_ack Sequence number of the received message.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ack_tm_send(mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, buf, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#else
- mavlink_ack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, (const char *)&packet, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a ack_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ack_tm_send_struct(mavlink_channel_t chan, const mavlink_ack_tm_t* ack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ack_tm_send(chan, ack_tm->recv_msgid, ack_tm->seq_ack);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, (const char *)ack_tm, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ACK_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_ack_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, buf, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#else
- mavlink_ack_tm_t *packet = (mavlink_ack_tm_t *)msgbuf;
- packet->recv_msgid = recv_msgid;
- packet->seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, (const char *)packet, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ACK_TM UNPACKING
-
-
-/**
- * @brief Get field recv_msgid from ack_tm message
- *
- * @return Message id of the received message.
- */
-static inline uint8_t mavlink_msg_ack_tm_get_recv_msgid(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field seq_ack from ack_tm message
- *
- * @return Sequence number of the received message.
- */
-static inline uint8_t mavlink_msg_ack_tm_get_seq_ack(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Decode a ack_tm message into a struct
- *
- * @param msg The message to decode
- * @param ack_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ack_tm_decode(const mavlink_message_t* msg, mavlink_ack_tm_t* ack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ack_tm->recv_msgid = mavlink_msg_ack_tm_get_recv_msgid(msg);
- ack_tm->seq_ack = mavlink_msg_ack_tm_get_seq_ack(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ACK_TM_LEN? msg->len : MAVLINK_MSG_ID_ACK_TM_LEN;
- memset(ack_tm, 0, MAVLINK_MSG_ID_ACK_TM_LEN);
- memcpy(ack_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_ada_tm.h b/mavlink_lib/hermes/mavlink_msg_ada_tm.h
deleted file mode 100644
index 623d9baf5202a916ed3752e477513836ec62d848..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_ada_tm.h
+++ /dev/null
@@ -1,613 +0,0 @@
-#pragma once
-// MESSAGE ADA_TM PACKING
-
-#define MAVLINK_MSG_ID_ADA_TM 167
-
-MAVPACKED(
-typedef struct __mavlink_ada_tm_t {
- uint64_t timestamp; /*< When was this logged*/
- float target_dpl_altitude; /*< Target deployment altitude*/
- float kalman_x0; /*< Kalman state variable 0 (pressure)*/
- float kalman_x1; /*< Kalman state variable 1 (pressure velocity)*/
- float kalman_x2; /*< Kalman state variable 2 (pressure acceleration)*/
- float kalman_acc_x0; /*< Kalman2 (acc) state variable 0 (altitude)*/
- float kalman_acc_x1; /*< Kalman2 (acc) state variable 1 (Vertical speed)*/
- float kalman_acc_x2; /*< Kalman2 (acc) state variable 2 (Vertical acceleration)*/
- float ref_pressure; /*< Calibration pressure*/
- float msl_pressure; /*< Expected pressure at mean sea level*/
- float ref_pressure_mean; /*< Calibration pressure mean*/
- float ref_pressure_stddev; /*< Calibration pressure std deviation*/
- uint32_t ref_pressure_nsamples; /*< Calibration pressure number of samples*/
- float ref_altitude; /*< Calibration altitude*/
- float ref_temperature; /*< Calibration temperature*/
- float msl_temperature; /*< Expected temperature at mean sea level*/
- uint8_t state; /*< ADA current state*/
-}) mavlink_ada_tm_t;
-
-#define MAVLINK_MSG_ID_ADA_TM_LEN 69
-#define MAVLINK_MSG_ID_ADA_TM_MIN_LEN 69
-#define MAVLINK_MSG_ID_167_LEN 69
-#define MAVLINK_MSG_ID_167_MIN_LEN 69
-
-#define MAVLINK_MSG_ID_ADA_TM_CRC 204
-#define MAVLINK_MSG_ID_167_CRC 204
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ADA_TM { \
- 167, \
- "ADA_TM", \
- 17, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ada_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 68, offsetof(mavlink_ada_tm_t, state) }, \
- { "target_dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ada_tm_t, target_dpl_altitude) }, \
- { "kalman_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ada_tm_t, kalman_x0) }, \
- { "kalman_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ada_tm_t, kalman_x1) }, \
- { "kalman_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ada_tm_t, kalman_x2) }, \
- { "kalman_acc_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ada_tm_t, kalman_acc_x0) }, \
- { "kalman_acc_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_ada_tm_t, kalman_acc_x1) }, \
- { "kalman_acc_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_ada_tm_t, kalman_acc_x2) }, \
- { "ref_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_ada_tm_t, ref_pressure) }, \
- { "msl_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_ada_tm_t, msl_pressure) }, \
- { "ref_pressure_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_ada_tm_t, ref_pressure_mean) }, \
- { "ref_pressure_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_ada_tm_t, ref_pressure_stddev) }, \
- { "ref_pressure_nsamples", NULL, MAVLINK_TYPE_UINT32_T, 0, 52, offsetof(mavlink_ada_tm_t, ref_pressure_nsamples) }, \
- { "ref_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_ada_tm_t, ref_altitude) }, \
- { "ref_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_ada_tm_t, ref_temperature) }, \
- { "msl_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_ada_tm_t, msl_temperature) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ADA_TM { \
- "ADA_TM", \
- 17, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ada_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 68, offsetof(mavlink_ada_tm_t, state) }, \
- { "target_dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ada_tm_t, target_dpl_altitude) }, \
- { "kalman_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ada_tm_t, kalman_x0) }, \
- { "kalman_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ada_tm_t, kalman_x1) }, \
- { "kalman_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ada_tm_t, kalman_x2) }, \
- { "kalman_acc_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ada_tm_t, kalman_acc_x0) }, \
- { "kalman_acc_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_ada_tm_t, kalman_acc_x1) }, \
- { "kalman_acc_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_ada_tm_t, kalman_acc_x2) }, \
- { "ref_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_ada_tm_t, ref_pressure) }, \
- { "msl_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_ada_tm_t, msl_pressure) }, \
- { "ref_pressure_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_ada_tm_t, ref_pressure_mean) }, \
- { "ref_pressure_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_ada_tm_t, ref_pressure_stddev) }, \
- { "ref_pressure_nsamples", NULL, MAVLINK_TYPE_UINT32_T, 0, 52, offsetof(mavlink_ada_tm_t, ref_pressure_nsamples) }, \
- { "ref_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_ada_tm_t, ref_altitude) }, \
- { "ref_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_ada_tm_t, ref_temperature) }, \
- { "msl_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_ada_tm_t, msl_temperature) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ada_tm 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 When was this logged
- * @param state ADA current state
- * @param target_dpl_altitude Target deployment altitude
- * @param kalman_x0 Kalman state variable 0 (pressure)
- * @param kalman_x1 Kalman state variable 1 (pressure velocity)
- * @param kalman_x2 Kalman state variable 2 (pressure acceleration)
- * @param kalman_acc_x0 Kalman2 (acc) state variable 0 (altitude)
- * @param kalman_acc_x1 Kalman2 (acc) state variable 1 (Vertical speed)
- * @param kalman_acc_x2 Kalman2 (acc) state variable 2 (Vertical acceleration)
- * @param ref_pressure Calibration pressure
- * @param msl_pressure Expected pressure at mean sea level
- * @param ref_pressure_mean Calibration pressure mean
- * @param ref_pressure_stddev Calibration pressure std deviation
- * @param ref_pressure_nsamples Calibration pressure number of samples
- * @param ref_altitude Calibration altitude
- * @param ref_temperature Calibration temperature
- * @param msl_temperature Expected temperature at mean sea level
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ada_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t state, float target_dpl_altitude, float kalman_x0, float kalman_x1, float kalman_x2, float kalman_acc_x0, float kalman_acc_x1, float kalman_acc_x2, float ref_pressure, float msl_pressure, float ref_pressure_mean, float ref_pressure_stddev, uint32_t ref_pressure_nsamples, float ref_altitude, float ref_temperature, float msl_temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, target_dpl_altitude);
- _mav_put_float(buf, 12, kalman_x0);
- _mav_put_float(buf, 16, kalman_x1);
- _mav_put_float(buf, 20, kalman_x2);
- _mav_put_float(buf, 24, kalman_acc_x0);
- _mav_put_float(buf, 28, kalman_acc_x1);
- _mav_put_float(buf, 32, kalman_acc_x2);
- _mav_put_float(buf, 36, ref_pressure);
- _mav_put_float(buf, 40, msl_pressure);
- _mav_put_float(buf, 44, ref_pressure_mean);
- _mav_put_float(buf, 48, ref_pressure_stddev);
- _mav_put_uint32_t(buf, 52, ref_pressure_nsamples);
- _mav_put_float(buf, 56, ref_altitude);
- _mav_put_float(buf, 60, ref_temperature);
- _mav_put_float(buf, 64, msl_temperature);
- _mav_put_uint8_t(buf, 68, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADA_TM_LEN);
-#else
- mavlink_ada_tm_t packet;
- packet.timestamp = timestamp;
- packet.target_dpl_altitude = target_dpl_altitude;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.kalman_acc_x0 = kalman_acc_x0;
- packet.kalman_acc_x1 = kalman_acc_x1;
- packet.kalman_acc_x2 = kalman_acc_x2;
- packet.ref_pressure = ref_pressure;
- packet.msl_pressure = msl_pressure;
- packet.ref_pressure_mean = ref_pressure_mean;
- packet.ref_pressure_stddev = ref_pressure_stddev;
- packet.ref_pressure_nsamples = ref_pressure_nsamples;
- packet.ref_altitude = ref_altitude;
- packet.ref_temperature = ref_temperature;
- packet.msl_temperature = msl_temperature;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADA_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADA_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-}
-
-/**
- * @brief Pack a ada_tm 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 When was this logged
- * @param state ADA current state
- * @param target_dpl_altitude Target deployment altitude
- * @param kalman_x0 Kalman state variable 0 (pressure)
- * @param kalman_x1 Kalman state variable 1 (pressure velocity)
- * @param kalman_x2 Kalman state variable 2 (pressure acceleration)
- * @param kalman_acc_x0 Kalman2 (acc) state variable 0 (altitude)
- * @param kalman_acc_x1 Kalman2 (acc) state variable 1 (Vertical speed)
- * @param kalman_acc_x2 Kalman2 (acc) state variable 2 (Vertical acceleration)
- * @param ref_pressure Calibration pressure
- * @param msl_pressure Expected pressure at mean sea level
- * @param ref_pressure_mean Calibration pressure mean
- * @param ref_pressure_stddev Calibration pressure std deviation
- * @param ref_pressure_nsamples Calibration pressure number of samples
- * @param ref_altitude Calibration altitude
- * @param ref_temperature Calibration temperature
- * @param msl_temperature Expected temperature at mean sea level
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ada_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t state,float target_dpl_altitude,float kalman_x0,float kalman_x1,float kalman_x2,float kalman_acc_x0,float kalman_acc_x1,float kalman_acc_x2,float ref_pressure,float msl_pressure,float ref_pressure_mean,float ref_pressure_stddev,uint32_t ref_pressure_nsamples,float ref_altitude,float ref_temperature,float msl_temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, target_dpl_altitude);
- _mav_put_float(buf, 12, kalman_x0);
- _mav_put_float(buf, 16, kalman_x1);
- _mav_put_float(buf, 20, kalman_x2);
- _mav_put_float(buf, 24, kalman_acc_x0);
- _mav_put_float(buf, 28, kalman_acc_x1);
- _mav_put_float(buf, 32, kalman_acc_x2);
- _mav_put_float(buf, 36, ref_pressure);
- _mav_put_float(buf, 40, msl_pressure);
- _mav_put_float(buf, 44, ref_pressure_mean);
- _mav_put_float(buf, 48, ref_pressure_stddev);
- _mav_put_uint32_t(buf, 52, ref_pressure_nsamples);
- _mav_put_float(buf, 56, ref_altitude);
- _mav_put_float(buf, 60, ref_temperature);
- _mav_put_float(buf, 64, msl_temperature);
- _mav_put_uint8_t(buf, 68, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADA_TM_LEN);
-#else
- mavlink_ada_tm_t packet;
- packet.timestamp = timestamp;
- packet.target_dpl_altitude = target_dpl_altitude;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.kalman_acc_x0 = kalman_acc_x0;
- packet.kalman_acc_x1 = kalman_acc_x1;
- packet.kalman_acc_x2 = kalman_acc_x2;
- packet.ref_pressure = ref_pressure;
- packet.msl_pressure = msl_pressure;
- packet.ref_pressure_mean = ref_pressure_mean;
- packet.ref_pressure_stddev = ref_pressure_stddev;
- packet.ref_pressure_nsamples = ref_pressure_nsamples;
- packet.ref_altitude = ref_altitude;
- packet.ref_temperature = ref_temperature;
- packet.msl_temperature = msl_temperature;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADA_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADA_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-}
-
-/**
- * @brief Encode a ada_tm 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 ada_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ada_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ada_tm_t* ada_tm)
-{
- return mavlink_msg_ada_tm_pack(system_id, component_id, msg, ada_tm->timestamp, ada_tm->state, ada_tm->target_dpl_altitude, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->kalman_acc_x0, ada_tm->kalman_acc_x1, ada_tm->kalman_acc_x2, ada_tm->ref_pressure, ada_tm->msl_pressure, ada_tm->ref_pressure_mean, ada_tm->ref_pressure_stddev, ada_tm->ref_pressure_nsamples, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_temperature);
-}
-
-/**
- * @brief Encode a ada_tm 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 ada_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ada_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ada_tm_t* ada_tm)
-{
- return mavlink_msg_ada_tm_pack_chan(system_id, component_id, chan, msg, ada_tm->timestamp, ada_tm->state, ada_tm->target_dpl_altitude, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->kalman_acc_x0, ada_tm->kalman_acc_x1, ada_tm->kalman_acc_x2, ada_tm->ref_pressure, ada_tm->msl_pressure, ada_tm->ref_pressure_mean, ada_tm->ref_pressure_stddev, ada_tm->ref_pressure_nsamples, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_temperature);
-}
-
-/**
- * @brief Send a ada_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp When was this logged
- * @param state ADA current state
- * @param target_dpl_altitude Target deployment altitude
- * @param kalman_x0 Kalman state variable 0 (pressure)
- * @param kalman_x1 Kalman state variable 1 (pressure velocity)
- * @param kalman_x2 Kalman state variable 2 (pressure acceleration)
- * @param kalman_acc_x0 Kalman2 (acc) state variable 0 (altitude)
- * @param kalman_acc_x1 Kalman2 (acc) state variable 1 (Vertical speed)
- * @param kalman_acc_x2 Kalman2 (acc) state variable 2 (Vertical acceleration)
- * @param ref_pressure Calibration pressure
- * @param msl_pressure Expected pressure at mean sea level
- * @param ref_pressure_mean Calibration pressure mean
- * @param ref_pressure_stddev Calibration pressure std deviation
- * @param ref_pressure_nsamples Calibration pressure number of samples
- * @param ref_altitude Calibration altitude
- * @param ref_temperature Calibration temperature
- * @param msl_temperature Expected temperature at mean sea level
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ada_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float target_dpl_altitude, float kalman_x0, float kalman_x1, float kalman_x2, float kalman_acc_x0, float kalman_acc_x1, float kalman_acc_x2, float ref_pressure, float msl_pressure, float ref_pressure_mean, float ref_pressure_stddev, uint32_t ref_pressure_nsamples, float ref_altitude, float ref_temperature, float msl_temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, target_dpl_altitude);
- _mav_put_float(buf, 12, kalman_x0);
- _mav_put_float(buf, 16, kalman_x1);
- _mav_put_float(buf, 20, kalman_x2);
- _mav_put_float(buf, 24, kalman_acc_x0);
- _mav_put_float(buf, 28, kalman_acc_x1);
- _mav_put_float(buf, 32, kalman_acc_x2);
- _mav_put_float(buf, 36, ref_pressure);
- _mav_put_float(buf, 40, msl_pressure);
- _mav_put_float(buf, 44, ref_pressure_mean);
- _mav_put_float(buf, 48, ref_pressure_stddev);
- _mav_put_uint32_t(buf, 52, ref_pressure_nsamples);
- _mav_put_float(buf, 56, ref_altitude);
- _mav_put_float(buf, 60, ref_temperature);
- _mav_put_float(buf, 64, msl_temperature);
- _mav_put_uint8_t(buf, 68, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, buf, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#else
- mavlink_ada_tm_t packet;
- packet.timestamp = timestamp;
- packet.target_dpl_altitude = target_dpl_altitude;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.kalman_acc_x0 = kalman_acc_x0;
- packet.kalman_acc_x1 = kalman_acc_x1;
- packet.kalman_acc_x2 = kalman_acc_x2;
- packet.ref_pressure = ref_pressure;
- packet.msl_pressure = msl_pressure;
- packet.ref_pressure_mean = ref_pressure_mean;
- packet.ref_pressure_stddev = ref_pressure_stddev;
- packet.ref_pressure_nsamples = ref_pressure_nsamples;
- packet.ref_altitude = ref_altitude;
- packet.ref_temperature = ref_temperature;
- packet.msl_temperature = msl_temperature;
- packet.state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, (const char *)&packet, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a ada_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ada_tm_send_struct(mavlink_channel_t chan, const mavlink_ada_tm_t* ada_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ada_tm_send(chan, ada_tm->timestamp, ada_tm->state, ada_tm->target_dpl_altitude, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->kalman_acc_x0, ada_tm->kalman_acc_x1, ada_tm->kalman_acc_x2, ada_tm->ref_pressure, ada_tm->msl_pressure, ada_tm->ref_pressure_mean, ada_tm->ref_pressure_stddev, ada_tm->ref_pressure_nsamples, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_temperature);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, (const char *)ada_tm, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ADA_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_ada_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float target_dpl_altitude, float kalman_x0, float kalman_x1, float kalman_x2, float kalman_acc_x0, float kalman_acc_x1, float kalman_acc_x2, float ref_pressure, float msl_pressure, float ref_pressure_mean, float ref_pressure_stddev, uint32_t ref_pressure_nsamples, float ref_altitude, float ref_temperature, float msl_temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, target_dpl_altitude);
- _mav_put_float(buf, 12, kalman_x0);
- _mav_put_float(buf, 16, kalman_x1);
- _mav_put_float(buf, 20, kalman_x2);
- _mav_put_float(buf, 24, kalman_acc_x0);
- _mav_put_float(buf, 28, kalman_acc_x1);
- _mav_put_float(buf, 32, kalman_acc_x2);
- _mav_put_float(buf, 36, ref_pressure);
- _mav_put_float(buf, 40, msl_pressure);
- _mav_put_float(buf, 44, ref_pressure_mean);
- _mav_put_float(buf, 48, ref_pressure_stddev);
- _mav_put_uint32_t(buf, 52, ref_pressure_nsamples);
- _mav_put_float(buf, 56, ref_altitude);
- _mav_put_float(buf, 60, ref_temperature);
- _mav_put_float(buf, 64, msl_temperature);
- _mav_put_uint8_t(buf, 68, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, buf, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#else
- mavlink_ada_tm_t *packet = (mavlink_ada_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->target_dpl_altitude = target_dpl_altitude;
- packet->kalman_x0 = kalman_x0;
- packet->kalman_x1 = kalman_x1;
- packet->kalman_x2 = kalman_x2;
- packet->kalman_acc_x0 = kalman_acc_x0;
- packet->kalman_acc_x1 = kalman_acc_x1;
- packet->kalman_acc_x2 = kalman_acc_x2;
- packet->ref_pressure = ref_pressure;
- packet->msl_pressure = msl_pressure;
- packet->ref_pressure_mean = ref_pressure_mean;
- packet->ref_pressure_stddev = ref_pressure_stddev;
- packet->ref_pressure_nsamples = ref_pressure_nsamples;
- packet->ref_altitude = ref_altitude;
- packet->ref_temperature = ref_temperature;
- packet->msl_temperature = msl_temperature;
- packet->state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, (const char *)packet, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ADA_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from ada_tm message
- *
- * @return When was this logged
- */
-static inline uint64_t mavlink_msg_ada_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field state from ada_tm message
- *
- * @return ADA current state
- */
-static inline uint8_t mavlink_msg_ada_tm_get_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 68);
-}
-
-/**
- * @brief Get field target_dpl_altitude from ada_tm message
- *
- * @return Target deployment altitude
- */
-static inline float mavlink_msg_ada_tm_get_target_dpl_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field kalman_x0 from ada_tm message
- *
- * @return Kalman state variable 0 (pressure)
- */
-static inline float mavlink_msg_ada_tm_get_kalman_x0(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field kalman_x1 from ada_tm message
- *
- * @return Kalman state variable 1 (pressure velocity)
- */
-static inline float mavlink_msg_ada_tm_get_kalman_x1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field kalman_x2 from ada_tm message
- *
- * @return Kalman state variable 2 (pressure acceleration)
- */
-static inline float mavlink_msg_ada_tm_get_kalman_x2(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field kalman_acc_x0 from ada_tm message
- *
- * @return Kalman2 (acc) state variable 0 (altitude)
- */
-static inline float mavlink_msg_ada_tm_get_kalman_acc_x0(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field kalman_acc_x1 from ada_tm message
- *
- * @return Kalman2 (acc) state variable 1 (Vertical speed)
- */
-static inline float mavlink_msg_ada_tm_get_kalman_acc_x1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field kalman_acc_x2 from ada_tm message
- *
- * @return Kalman2 (acc) state variable 2 (Vertical acceleration)
- */
-static inline float mavlink_msg_ada_tm_get_kalman_acc_x2(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field ref_pressure from ada_tm message
- *
- * @return Calibration pressure
- */
-static inline float mavlink_msg_ada_tm_get_ref_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field msl_pressure from ada_tm message
- *
- * @return Expected pressure at mean sea level
- */
-static inline float mavlink_msg_ada_tm_get_msl_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field ref_pressure_mean from ada_tm message
- *
- * @return Calibration pressure mean
- */
-static inline float mavlink_msg_ada_tm_get_ref_pressure_mean(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field ref_pressure_stddev from ada_tm message
- *
- * @return Calibration pressure std deviation
- */
-static inline float mavlink_msg_ada_tm_get_ref_pressure_stddev(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field ref_pressure_nsamples from ada_tm message
- *
- * @return Calibration pressure number of samples
- */
-static inline uint32_t mavlink_msg_ada_tm_get_ref_pressure_nsamples(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 52);
-}
-
-/**
- * @brief Get field ref_altitude from ada_tm message
- *
- * @return Calibration altitude
- */
-static inline float mavlink_msg_ada_tm_get_ref_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field ref_temperature from ada_tm message
- *
- * @return Calibration temperature
- */
-static inline float mavlink_msg_ada_tm_get_ref_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field msl_temperature from ada_tm message
- *
- * @return Expected temperature at mean sea level
- */
-static inline float mavlink_msg_ada_tm_get_msl_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Decode a ada_tm message into a struct
- *
- * @param msg The message to decode
- * @param ada_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ada_tm_decode(const mavlink_message_t* msg, mavlink_ada_tm_t* ada_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ada_tm->timestamp = mavlink_msg_ada_tm_get_timestamp(msg);
- ada_tm->target_dpl_altitude = mavlink_msg_ada_tm_get_target_dpl_altitude(msg);
- ada_tm->kalman_x0 = mavlink_msg_ada_tm_get_kalman_x0(msg);
- ada_tm->kalman_x1 = mavlink_msg_ada_tm_get_kalman_x1(msg);
- ada_tm->kalman_x2 = mavlink_msg_ada_tm_get_kalman_x2(msg);
- ada_tm->kalman_acc_x0 = mavlink_msg_ada_tm_get_kalman_acc_x0(msg);
- ada_tm->kalman_acc_x1 = mavlink_msg_ada_tm_get_kalman_acc_x1(msg);
- ada_tm->kalman_acc_x2 = mavlink_msg_ada_tm_get_kalman_acc_x2(msg);
- ada_tm->ref_pressure = mavlink_msg_ada_tm_get_ref_pressure(msg);
- ada_tm->msl_pressure = mavlink_msg_ada_tm_get_msl_pressure(msg);
- ada_tm->ref_pressure_mean = mavlink_msg_ada_tm_get_ref_pressure_mean(msg);
- ada_tm->ref_pressure_stddev = mavlink_msg_ada_tm_get_ref_pressure_stddev(msg);
- ada_tm->ref_pressure_nsamples = mavlink_msg_ada_tm_get_ref_pressure_nsamples(msg);
- ada_tm->ref_altitude = mavlink_msg_ada_tm_get_ref_altitude(msg);
- ada_tm->ref_temperature = mavlink_msg_ada_tm_get_ref_temperature(msg);
- ada_tm->msl_temperature = mavlink_msg_ada_tm_get_msl_temperature(msg);
- ada_tm->state = mavlink_msg_ada_tm_get_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ADA_TM_LEN? msg->len : MAVLINK_MSG_ID_ADA_TM_LEN;
- memset(ada_tm, 0, MAVLINK_MSG_ID_ADA_TM_LEN);
- memcpy(ada_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_adc_tm.h b/mavlink_lib/hermes/mavlink_msg_adc_tm.h
deleted file mode 100644
index e4d125f7941ad3409fa726fe2360609a5d50d068..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_adc_tm.h
+++ /dev/null
@@ -1,438 +0,0 @@
-#pragma once
-// MESSAGE ADC_TM PACKING
-
-#define MAVLINK_MSG_ID_ADC_TM 169
-
-MAVPACKED(
-typedef struct __mavlink_adc_tm_t {
- uint64_t timestamp; /*< When was this logged*/
- float hw_baro_volt; /*< Honeywell barometer voltage*/
- float nxp_baro_volt; /*< NXP barometer battery_voltage*/
- float hw_baro_pressure; /*< Honeywell barometer measured pressure*/
- float nxp_baro_pressure; /*< NXP barometer measured pressure*/
- float battery_voltage; /*< Battery voltage*/
- float current_sense_1; /*< Current Sense 1*/
- float current_sense_2; /*< Current Sense 2*/
- uint8_t hw_baro_flag; /*< Honeywell barometer flag*/
- uint8_t nxp_baro_flag; /*< NXP barometer flag*/
-}) mavlink_adc_tm_t;
-
-#define MAVLINK_MSG_ID_ADC_TM_LEN 38
-#define MAVLINK_MSG_ID_ADC_TM_MIN_LEN 38
-#define MAVLINK_MSG_ID_169_LEN 38
-#define MAVLINK_MSG_ID_169_MIN_LEN 38
-
-#define MAVLINK_MSG_ID_ADC_TM_CRC 230
-#define MAVLINK_MSG_ID_169_CRC 230
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ADC_TM { \
- 169, \
- "ADC_TM", \
- 10, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_adc_tm_t, timestamp) }, \
- { "hw_baro_volt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_adc_tm_t, hw_baro_volt) }, \
- { "nxp_baro_volt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_adc_tm_t, nxp_baro_volt) }, \
- { "hw_baro_flag", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_adc_tm_t, hw_baro_flag) }, \
- { "nxp_baro_flag", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_adc_tm_t, nxp_baro_flag) }, \
- { "hw_baro_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_adc_tm_t, hw_baro_pressure) }, \
- { "nxp_baro_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_adc_tm_t, nxp_baro_pressure) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_adc_tm_t, battery_voltage) }, \
- { "current_sense_1", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_adc_tm_t, current_sense_1) }, \
- { "current_sense_2", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_adc_tm_t, current_sense_2) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ADC_TM { \
- "ADC_TM", \
- 10, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_adc_tm_t, timestamp) }, \
- { "hw_baro_volt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_adc_tm_t, hw_baro_volt) }, \
- { "nxp_baro_volt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_adc_tm_t, nxp_baro_volt) }, \
- { "hw_baro_flag", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_adc_tm_t, hw_baro_flag) }, \
- { "nxp_baro_flag", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_adc_tm_t, nxp_baro_flag) }, \
- { "hw_baro_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_adc_tm_t, hw_baro_pressure) }, \
- { "nxp_baro_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_adc_tm_t, nxp_baro_pressure) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_adc_tm_t, battery_voltage) }, \
- { "current_sense_1", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_adc_tm_t, current_sense_1) }, \
- { "current_sense_2", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_adc_tm_t, current_sense_2) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a adc_tm 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 When was this logged
- * @param hw_baro_volt Honeywell barometer voltage
- * @param nxp_baro_volt NXP barometer battery_voltage
- * @param hw_baro_flag Honeywell barometer flag
- * @param nxp_baro_flag NXP barometer flag
- * @param hw_baro_pressure Honeywell barometer measured pressure
- * @param nxp_baro_pressure NXP barometer measured pressure
- * @param battery_voltage Battery voltage
- * @param current_sense_1 Current Sense 1
- * @param current_sense_2 Current Sense 2
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_adc_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, float hw_baro_volt, float nxp_baro_volt, uint8_t hw_baro_flag, uint8_t nxp_baro_flag, float hw_baro_pressure, float nxp_baro_pressure, float battery_voltage, float current_sense_1, float current_sense_2)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, hw_baro_volt);
- _mav_put_float(buf, 12, nxp_baro_volt);
- _mav_put_float(buf, 16, hw_baro_pressure);
- _mav_put_float(buf, 20, nxp_baro_pressure);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_float(buf, 28, current_sense_1);
- _mav_put_float(buf, 32, current_sense_2);
- _mav_put_uint8_t(buf, 36, hw_baro_flag);
- _mav_put_uint8_t(buf, 37, nxp_baro_flag);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADC_TM_LEN);
-#else
- mavlink_adc_tm_t packet;
- packet.timestamp = timestamp;
- packet.hw_baro_volt = hw_baro_volt;
- packet.nxp_baro_volt = nxp_baro_volt;
- packet.hw_baro_pressure = hw_baro_pressure;
- packet.nxp_baro_pressure = nxp_baro_pressure;
- packet.battery_voltage = battery_voltage;
- packet.current_sense_1 = current_sense_1;
- packet.current_sense_2 = current_sense_2;
- packet.hw_baro_flag = hw_baro_flag;
- packet.nxp_baro_flag = nxp_baro_flag;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADC_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADC_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-}
-
-/**
- * @brief Pack a adc_tm 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 When was this logged
- * @param hw_baro_volt Honeywell barometer voltage
- * @param nxp_baro_volt NXP barometer battery_voltage
- * @param hw_baro_flag Honeywell barometer flag
- * @param nxp_baro_flag NXP barometer flag
- * @param hw_baro_pressure Honeywell barometer measured pressure
- * @param nxp_baro_pressure NXP barometer measured pressure
- * @param battery_voltage Battery voltage
- * @param current_sense_1 Current Sense 1
- * @param current_sense_2 Current Sense 2
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_adc_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,float hw_baro_volt,float nxp_baro_volt,uint8_t hw_baro_flag,uint8_t nxp_baro_flag,float hw_baro_pressure,float nxp_baro_pressure,float battery_voltage,float current_sense_1,float current_sense_2)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, hw_baro_volt);
- _mav_put_float(buf, 12, nxp_baro_volt);
- _mav_put_float(buf, 16, hw_baro_pressure);
- _mav_put_float(buf, 20, nxp_baro_pressure);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_float(buf, 28, current_sense_1);
- _mav_put_float(buf, 32, current_sense_2);
- _mav_put_uint8_t(buf, 36, hw_baro_flag);
- _mav_put_uint8_t(buf, 37, nxp_baro_flag);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADC_TM_LEN);
-#else
- mavlink_adc_tm_t packet;
- packet.timestamp = timestamp;
- packet.hw_baro_volt = hw_baro_volt;
- packet.nxp_baro_volt = nxp_baro_volt;
- packet.hw_baro_pressure = hw_baro_pressure;
- packet.nxp_baro_pressure = nxp_baro_pressure;
- packet.battery_voltage = battery_voltage;
- packet.current_sense_1 = current_sense_1;
- packet.current_sense_2 = current_sense_2;
- packet.hw_baro_flag = hw_baro_flag;
- packet.nxp_baro_flag = nxp_baro_flag;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADC_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADC_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-}
-
-/**
- * @brief Encode a adc_tm 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 adc_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_adc_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_adc_tm_t* adc_tm)
-{
- return mavlink_msg_adc_tm_pack(system_id, component_id, msg, adc_tm->timestamp, adc_tm->hw_baro_volt, adc_tm->nxp_baro_volt, adc_tm->hw_baro_flag, adc_tm->nxp_baro_flag, adc_tm->hw_baro_pressure, adc_tm->nxp_baro_pressure, adc_tm->battery_voltage, adc_tm->current_sense_1, adc_tm->current_sense_2);
-}
-
-/**
- * @brief Encode a adc_tm 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 adc_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_adc_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_adc_tm_t* adc_tm)
-{
- return mavlink_msg_adc_tm_pack_chan(system_id, component_id, chan, msg, adc_tm->timestamp, adc_tm->hw_baro_volt, adc_tm->nxp_baro_volt, adc_tm->hw_baro_flag, adc_tm->nxp_baro_flag, adc_tm->hw_baro_pressure, adc_tm->nxp_baro_pressure, adc_tm->battery_voltage, adc_tm->current_sense_1, adc_tm->current_sense_2);
-}
-
-/**
- * @brief Send a adc_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp When was this logged
- * @param hw_baro_volt Honeywell barometer voltage
- * @param nxp_baro_volt NXP barometer battery_voltage
- * @param hw_baro_flag Honeywell barometer flag
- * @param nxp_baro_flag NXP barometer flag
- * @param hw_baro_pressure Honeywell barometer measured pressure
- * @param nxp_baro_pressure NXP barometer measured pressure
- * @param battery_voltage Battery voltage
- * @param current_sense_1 Current Sense 1
- * @param current_sense_2 Current Sense 2
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_adc_tm_send(mavlink_channel_t chan, uint64_t timestamp, float hw_baro_volt, float nxp_baro_volt, uint8_t hw_baro_flag, uint8_t nxp_baro_flag, float hw_baro_pressure, float nxp_baro_pressure, float battery_voltage, float current_sense_1, float current_sense_2)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, hw_baro_volt);
- _mav_put_float(buf, 12, nxp_baro_volt);
- _mav_put_float(buf, 16, hw_baro_pressure);
- _mav_put_float(buf, 20, nxp_baro_pressure);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_float(buf, 28, current_sense_1);
- _mav_put_float(buf, 32, current_sense_2);
- _mav_put_uint8_t(buf, 36, hw_baro_flag);
- _mav_put_uint8_t(buf, 37, nxp_baro_flag);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, buf, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#else
- mavlink_adc_tm_t packet;
- packet.timestamp = timestamp;
- packet.hw_baro_volt = hw_baro_volt;
- packet.nxp_baro_volt = nxp_baro_volt;
- packet.hw_baro_pressure = hw_baro_pressure;
- packet.nxp_baro_pressure = nxp_baro_pressure;
- packet.battery_voltage = battery_voltage;
- packet.current_sense_1 = current_sense_1;
- packet.current_sense_2 = current_sense_2;
- packet.hw_baro_flag = hw_baro_flag;
- packet.nxp_baro_flag = nxp_baro_flag;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)&packet, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a adc_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_adc_tm_send_struct(mavlink_channel_t chan, const mavlink_adc_tm_t* adc_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_adc_tm_send(chan, adc_tm->timestamp, adc_tm->hw_baro_volt, adc_tm->nxp_baro_volt, adc_tm->hw_baro_flag, adc_tm->nxp_baro_flag, adc_tm->hw_baro_pressure, adc_tm->nxp_baro_pressure, adc_tm->battery_voltage, adc_tm->current_sense_1, adc_tm->current_sense_2);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)adc_tm, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ADC_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_adc_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float hw_baro_volt, float nxp_baro_volt, uint8_t hw_baro_flag, uint8_t nxp_baro_flag, float hw_baro_pressure, float nxp_baro_pressure, float battery_voltage, float current_sense_1, float current_sense_2)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, hw_baro_volt);
- _mav_put_float(buf, 12, nxp_baro_volt);
- _mav_put_float(buf, 16, hw_baro_pressure);
- _mav_put_float(buf, 20, nxp_baro_pressure);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_float(buf, 28, current_sense_1);
- _mav_put_float(buf, 32, current_sense_2);
- _mav_put_uint8_t(buf, 36, hw_baro_flag);
- _mav_put_uint8_t(buf, 37, nxp_baro_flag);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, buf, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#else
- mavlink_adc_tm_t *packet = (mavlink_adc_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->hw_baro_volt = hw_baro_volt;
- packet->nxp_baro_volt = nxp_baro_volt;
- packet->hw_baro_pressure = hw_baro_pressure;
- packet->nxp_baro_pressure = nxp_baro_pressure;
- packet->battery_voltage = battery_voltage;
- packet->current_sense_1 = current_sense_1;
- packet->current_sense_2 = current_sense_2;
- packet->hw_baro_flag = hw_baro_flag;
- packet->nxp_baro_flag = nxp_baro_flag;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)packet, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ADC_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from adc_tm message
- *
- * @return When was this logged
- */
-static inline uint64_t mavlink_msg_adc_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field hw_baro_volt from adc_tm message
- *
- * @return Honeywell barometer voltage
- */
-static inline float mavlink_msg_adc_tm_get_hw_baro_volt(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field nxp_baro_volt from adc_tm message
- *
- * @return NXP barometer battery_voltage
- */
-static inline float mavlink_msg_adc_tm_get_nxp_baro_volt(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field hw_baro_flag from adc_tm message
- *
- * @return Honeywell barometer flag
- */
-static inline uint8_t mavlink_msg_adc_tm_get_hw_baro_flag(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 36);
-}
-
-/**
- * @brief Get field nxp_baro_flag from adc_tm message
- *
- * @return NXP barometer flag
- */
-static inline uint8_t mavlink_msg_adc_tm_get_nxp_baro_flag(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 37);
-}
-
-/**
- * @brief Get field hw_baro_pressure from adc_tm message
- *
- * @return Honeywell barometer measured pressure
- */
-static inline float mavlink_msg_adc_tm_get_hw_baro_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field nxp_baro_pressure from adc_tm message
- *
- * @return NXP barometer measured pressure
- */
-static inline float mavlink_msg_adc_tm_get_nxp_baro_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field battery_voltage from adc_tm message
- *
- * @return Battery voltage
- */
-static inline float mavlink_msg_adc_tm_get_battery_voltage(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field current_sense_1 from adc_tm message
- *
- * @return Current Sense 1
- */
-static inline float mavlink_msg_adc_tm_get_current_sense_1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field current_sense_2 from adc_tm message
- *
- * @return Current Sense 2
- */
-static inline float mavlink_msg_adc_tm_get_current_sense_2(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Decode a adc_tm message into a struct
- *
- * @param msg The message to decode
- * @param adc_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_adc_tm_decode(const mavlink_message_t* msg, mavlink_adc_tm_t* adc_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- adc_tm->timestamp = mavlink_msg_adc_tm_get_timestamp(msg);
- adc_tm->hw_baro_volt = mavlink_msg_adc_tm_get_hw_baro_volt(msg);
- adc_tm->nxp_baro_volt = mavlink_msg_adc_tm_get_nxp_baro_volt(msg);
- adc_tm->hw_baro_pressure = mavlink_msg_adc_tm_get_hw_baro_pressure(msg);
- adc_tm->nxp_baro_pressure = mavlink_msg_adc_tm_get_nxp_baro_pressure(msg);
- adc_tm->battery_voltage = mavlink_msg_adc_tm_get_battery_voltage(msg);
- adc_tm->current_sense_1 = mavlink_msg_adc_tm_get_current_sense_1(msg);
- adc_tm->current_sense_2 = mavlink_msg_adc_tm_get_current_sense_2(msg);
- adc_tm->hw_baro_flag = mavlink_msg_adc_tm_get_hw_baro_flag(msg);
- adc_tm->nxp_baro_flag = mavlink_msg_adc_tm_get_nxp_baro_flag(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ADC_TM_LEN? msg->len : MAVLINK_MSG_ID_ADC_TM_LEN;
- memset(adc_tm, 0, MAVLINK_MSG_ID_ADC_TM_LEN);
- memcpy(adc_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_adis_tm.h b/mavlink_lib/hermes/mavlink_msg_adis_tm.h
deleted file mode 100644
index eabe2f5afe4b7fce4e970e4db939e617315f8b38..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_adis_tm.h
+++ /dev/null
@@ -1,513 +0,0 @@
-#pragma once
-// MESSAGE ADIS_TM PACKING
-
-#define MAVLINK_MSG_ID_ADIS_TM 170
-
-MAVPACKED(
-typedef struct __mavlink_adis_tm_t {
- uint64_t timestamp; /*< When was this logged*/
- float acc_x; /*< X axis acceleration*/
- float acc_y; /*< Y axis acceleration*/
- float acc_z; /*< Z axis acceleration*/
- float gyro_x; /*< X axis gyro*/
- float gyro_y; /*< Y axis gyro*/
- float gyro_z; /*< Z axis gyro*/
- float compass_x; /*< X axis compass*/
- float compass_y; /*< Y axis compass*/
- float compass_z; /*< Z axis compass*/
- float temp; /*< Temperature*/
- float supply_out; /*< Supply voltage*/
- float aux_adc; /*< Auxilliary ADC*/
-}) mavlink_adis_tm_t;
-
-#define MAVLINK_MSG_ID_ADIS_TM_LEN 56
-#define MAVLINK_MSG_ID_ADIS_TM_MIN_LEN 56
-#define MAVLINK_MSG_ID_170_LEN 56
-#define MAVLINK_MSG_ID_170_MIN_LEN 56
-
-#define MAVLINK_MSG_ID_ADIS_TM_CRC 35
-#define MAVLINK_MSG_ID_170_CRC 35
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ADIS_TM { \
- 170, \
- "ADIS_TM", \
- 13, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_adis_tm_t, timestamp) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_adis_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_adis_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_adis_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_adis_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_adis_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_adis_tm_t, gyro_z) }, \
- { "compass_x", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_adis_tm_t, compass_x) }, \
- { "compass_y", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_adis_tm_t, compass_y) }, \
- { "compass_z", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_adis_tm_t, compass_z) }, \
- { "temp", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_adis_tm_t, temp) }, \
- { "supply_out", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_adis_tm_t, supply_out) }, \
- { "aux_adc", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_adis_tm_t, aux_adc) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ADIS_TM { \
- "ADIS_TM", \
- 13, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_adis_tm_t, timestamp) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_adis_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_adis_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_adis_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_adis_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_adis_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_adis_tm_t, gyro_z) }, \
- { "compass_x", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_adis_tm_t, compass_x) }, \
- { "compass_y", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_adis_tm_t, compass_y) }, \
- { "compass_z", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_adis_tm_t, compass_z) }, \
- { "temp", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_adis_tm_t, temp) }, \
- { "supply_out", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_adis_tm_t, supply_out) }, \
- { "aux_adc", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_adis_tm_t, aux_adc) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a adis_tm 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 When was this logged
- * @param acc_x X axis acceleration
- * @param acc_y Y axis acceleration
- * @param acc_z Z axis acceleration
- * @param gyro_x X axis gyro
- * @param gyro_y Y axis gyro
- * @param gyro_z Z axis gyro
- * @param compass_x X axis compass
- * @param compass_y Y axis compass
- * @param compass_z Z axis compass
- * @param temp Temperature
- * @param supply_out Supply voltage
- * @param aux_adc Auxilliary ADC
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_adis_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float compass_x, float compass_y, float compass_z, float temp, float supply_out, float aux_adc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADIS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, compass_x);
- _mav_put_float(buf, 36, compass_y);
- _mav_put_float(buf, 40, compass_z);
- _mav_put_float(buf, 44, temp);
- _mav_put_float(buf, 48, supply_out);
- _mav_put_float(buf, 52, aux_adc);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADIS_TM_LEN);
-#else
- mavlink_adis_tm_t packet;
- packet.timestamp = timestamp;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.compass_x = compass_x;
- packet.compass_y = compass_y;
- packet.compass_z = compass_z;
- packet.temp = temp;
- packet.supply_out = supply_out;
- packet.aux_adc = aux_adc;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADIS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADIS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADIS_TM_MIN_LEN, MAVLINK_MSG_ID_ADIS_TM_LEN, MAVLINK_MSG_ID_ADIS_TM_CRC);
-}
-
-/**
- * @brief Pack a adis_tm 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 When was this logged
- * @param acc_x X axis acceleration
- * @param acc_y Y axis acceleration
- * @param acc_z Z axis acceleration
- * @param gyro_x X axis gyro
- * @param gyro_y Y axis gyro
- * @param gyro_z Z axis gyro
- * @param compass_x X axis compass
- * @param compass_y Y axis compass
- * @param compass_z Z axis compass
- * @param temp Temperature
- * @param supply_out Supply voltage
- * @param aux_adc Auxilliary ADC
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_adis_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float compass_x,float compass_y,float compass_z,float temp,float supply_out,float aux_adc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADIS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, compass_x);
- _mav_put_float(buf, 36, compass_y);
- _mav_put_float(buf, 40, compass_z);
- _mav_put_float(buf, 44, temp);
- _mav_put_float(buf, 48, supply_out);
- _mav_put_float(buf, 52, aux_adc);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADIS_TM_LEN);
-#else
- mavlink_adis_tm_t packet;
- packet.timestamp = timestamp;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.compass_x = compass_x;
- packet.compass_y = compass_y;
- packet.compass_z = compass_z;
- packet.temp = temp;
- packet.supply_out = supply_out;
- packet.aux_adc = aux_adc;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADIS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADIS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADIS_TM_MIN_LEN, MAVLINK_MSG_ID_ADIS_TM_LEN, MAVLINK_MSG_ID_ADIS_TM_CRC);
-}
-
-/**
- * @brief Encode a adis_tm 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 adis_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_adis_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_adis_tm_t* adis_tm)
-{
- return mavlink_msg_adis_tm_pack(system_id, component_id, msg, adis_tm->timestamp, adis_tm->acc_x, adis_tm->acc_y, adis_tm->acc_z, adis_tm->gyro_x, adis_tm->gyro_y, adis_tm->gyro_z, adis_tm->compass_x, adis_tm->compass_y, adis_tm->compass_z, adis_tm->temp, adis_tm->supply_out, adis_tm->aux_adc);
-}
-
-/**
- * @brief Encode a adis_tm 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 adis_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_adis_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_adis_tm_t* adis_tm)
-{
- return mavlink_msg_adis_tm_pack_chan(system_id, component_id, chan, msg, adis_tm->timestamp, adis_tm->acc_x, adis_tm->acc_y, adis_tm->acc_z, adis_tm->gyro_x, adis_tm->gyro_y, adis_tm->gyro_z, adis_tm->compass_x, adis_tm->compass_y, adis_tm->compass_z, adis_tm->temp, adis_tm->supply_out, adis_tm->aux_adc);
-}
-
-/**
- * @brief Send a adis_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp When was this logged
- * @param acc_x X axis acceleration
- * @param acc_y Y axis acceleration
- * @param acc_z Z axis acceleration
- * @param gyro_x X axis gyro
- * @param gyro_y Y axis gyro
- * @param gyro_z Z axis gyro
- * @param compass_x X axis compass
- * @param compass_y Y axis compass
- * @param compass_z Z axis compass
- * @param temp Temperature
- * @param supply_out Supply voltage
- * @param aux_adc Auxilliary ADC
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_adis_tm_send(mavlink_channel_t chan, uint64_t timestamp, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float compass_x, float compass_y, float compass_z, float temp, float supply_out, float aux_adc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADIS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, compass_x);
- _mav_put_float(buf, 36, compass_y);
- _mav_put_float(buf, 40, compass_z);
- _mav_put_float(buf, 44, temp);
- _mav_put_float(buf, 48, supply_out);
- _mav_put_float(buf, 52, aux_adc);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADIS_TM, buf, MAVLINK_MSG_ID_ADIS_TM_MIN_LEN, MAVLINK_MSG_ID_ADIS_TM_LEN, MAVLINK_MSG_ID_ADIS_TM_CRC);
-#else
- mavlink_adis_tm_t packet;
- packet.timestamp = timestamp;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.compass_x = compass_x;
- packet.compass_y = compass_y;
- packet.compass_z = compass_z;
- packet.temp = temp;
- packet.supply_out = supply_out;
- packet.aux_adc = aux_adc;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADIS_TM, (const char *)&packet, MAVLINK_MSG_ID_ADIS_TM_MIN_LEN, MAVLINK_MSG_ID_ADIS_TM_LEN, MAVLINK_MSG_ID_ADIS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a adis_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_adis_tm_send_struct(mavlink_channel_t chan, const mavlink_adis_tm_t* adis_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_adis_tm_send(chan, adis_tm->timestamp, adis_tm->acc_x, adis_tm->acc_y, adis_tm->acc_z, adis_tm->gyro_x, adis_tm->gyro_y, adis_tm->gyro_z, adis_tm->compass_x, adis_tm->compass_y, adis_tm->compass_z, adis_tm->temp, adis_tm->supply_out, adis_tm->aux_adc);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADIS_TM, (const char *)adis_tm, MAVLINK_MSG_ID_ADIS_TM_MIN_LEN, MAVLINK_MSG_ID_ADIS_TM_LEN, MAVLINK_MSG_ID_ADIS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ADIS_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_adis_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float compass_x, float compass_y, float compass_z, float temp, float supply_out, float aux_adc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, compass_x);
- _mav_put_float(buf, 36, compass_y);
- _mav_put_float(buf, 40, compass_z);
- _mav_put_float(buf, 44, temp);
- _mav_put_float(buf, 48, supply_out);
- _mav_put_float(buf, 52, aux_adc);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADIS_TM, buf, MAVLINK_MSG_ID_ADIS_TM_MIN_LEN, MAVLINK_MSG_ID_ADIS_TM_LEN, MAVLINK_MSG_ID_ADIS_TM_CRC);
-#else
- mavlink_adis_tm_t *packet = (mavlink_adis_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->acc_x = acc_x;
- packet->acc_y = acc_y;
- packet->acc_z = acc_z;
- packet->gyro_x = gyro_x;
- packet->gyro_y = gyro_y;
- packet->gyro_z = gyro_z;
- packet->compass_x = compass_x;
- packet->compass_y = compass_y;
- packet->compass_z = compass_z;
- packet->temp = temp;
- packet->supply_out = supply_out;
- packet->aux_adc = aux_adc;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADIS_TM, (const char *)packet, MAVLINK_MSG_ID_ADIS_TM_MIN_LEN, MAVLINK_MSG_ID_ADIS_TM_LEN, MAVLINK_MSG_ID_ADIS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ADIS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from adis_tm message
- *
- * @return When was this logged
- */
-static inline uint64_t mavlink_msg_adis_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field acc_x from adis_tm message
- *
- * @return X axis acceleration
- */
-static inline float mavlink_msg_adis_tm_get_acc_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field acc_y from adis_tm message
- *
- * @return Y axis acceleration
- */
-static inline float mavlink_msg_adis_tm_get_acc_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field acc_z from adis_tm message
- *
- * @return Z axis acceleration
- */
-static inline float mavlink_msg_adis_tm_get_acc_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field gyro_x from adis_tm message
- *
- * @return X axis gyro
- */
-static inline float mavlink_msg_adis_tm_get_gyro_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field gyro_y from adis_tm message
- *
- * @return Y axis gyro
- */
-static inline float mavlink_msg_adis_tm_get_gyro_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field gyro_z from adis_tm message
- *
- * @return Z axis gyro
- */
-static inline float mavlink_msg_adis_tm_get_gyro_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field compass_x from adis_tm message
- *
- * @return X axis compass
- */
-static inline float mavlink_msg_adis_tm_get_compass_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field compass_y from adis_tm message
- *
- * @return Y axis compass
- */
-static inline float mavlink_msg_adis_tm_get_compass_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field compass_z from adis_tm message
- *
- * @return Z axis compass
- */
-static inline float mavlink_msg_adis_tm_get_compass_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field temp from adis_tm message
- *
- * @return Temperature
- */
-static inline float mavlink_msg_adis_tm_get_temp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field supply_out from adis_tm message
- *
- * @return Supply voltage
- */
-static inline float mavlink_msg_adis_tm_get_supply_out(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field aux_adc from adis_tm message
- *
- * @return Auxilliary ADC
- */
-static inline float mavlink_msg_adis_tm_get_aux_adc(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Decode a adis_tm message into a struct
- *
- * @param msg The message to decode
- * @param adis_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_adis_tm_decode(const mavlink_message_t* msg, mavlink_adis_tm_t* adis_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- adis_tm->timestamp = mavlink_msg_adis_tm_get_timestamp(msg);
- adis_tm->acc_x = mavlink_msg_adis_tm_get_acc_x(msg);
- adis_tm->acc_y = mavlink_msg_adis_tm_get_acc_y(msg);
- adis_tm->acc_z = mavlink_msg_adis_tm_get_acc_z(msg);
- adis_tm->gyro_x = mavlink_msg_adis_tm_get_gyro_x(msg);
- adis_tm->gyro_y = mavlink_msg_adis_tm_get_gyro_y(msg);
- adis_tm->gyro_z = mavlink_msg_adis_tm_get_gyro_z(msg);
- adis_tm->compass_x = mavlink_msg_adis_tm_get_compass_x(msg);
- adis_tm->compass_y = mavlink_msg_adis_tm_get_compass_y(msg);
- adis_tm->compass_z = mavlink_msg_adis_tm_get_compass_z(msg);
- adis_tm->temp = mavlink_msg_adis_tm_get_temp(msg);
- adis_tm->supply_out = mavlink_msg_adis_tm_get_supply_out(msg);
- adis_tm->aux_adc = mavlink_msg_adis_tm_get_aux_adc(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ADIS_TM_LEN? msg->len : MAVLINK_MSG_ID_ADIS_TM_LEN;
- memset(adis_tm, 0, MAVLINK_MSG_ID_ADIS_TM_LEN);
- memcpy(adis_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_can_tm.h b/mavlink_lib/hermes/mavlink_msg_can_tm.h
deleted file mode 100644
index 80d2e592cb3101e5a1b2b45e85a43448b07edd68..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_can_tm.h
+++ /dev/null
@@ -1,338 +0,0 @@
-#pragma once
-// MESSAGE CAN_TM PACKING
-
-#define MAVLINK_MSG_ID_CAN_TM 168
-
-MAVPACKED(
-typedef struct __mavlink_can_tm_t {
- uint64_t last_sent_ts; /*< Timestamp of the last sent message*/
- uint64_t last_rcv_ts; /*< Timestamp of the last received message*/
- uint16_t n_sent; /*< Number of sent messages*/
- uint16_t n_rcv; /*< Number of received messages*/
- uint8_t last_sent; /*< Id of the last sent message*/
- uint8_t last_rcv; /*< Id of the last received message*/
-}) mavlink_can_tm_t;
-
-#define MAVLINK_MSG_ID_CAN_TM_LEN 22
-#define MAVLINK_MSG_ID_CAN_TM_MIN_LEN 22
-#define MAVLINK_MSG_ID_168_LEN 22
-#define MAVLINK_MSG_ID_168_MIN_LEN 22
-
-#define MAVLINK_MSG_ID_CAN_TM_CRC 92
-#define MAVLINK_MSG_ID_168_CRC 92
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_CAN_TM { \
- 168, \
- "CAN_TM", \
- 6, \
- { { "n_sent", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_can_tm_t, n_sent) }, \
- { "n_rcv", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_can_tm_t, n_rcv) }, \
- { "last_sent", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_can_tm_t, last_sent) }, \
- { "last_rcv", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_can_tm_t, last_rcv) }, \
- { "last_sent_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_can_tm_t, last_sent_ts) }, \
- { "last_rcv_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_can_tm_t, last_rcv_ts) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_CAN_TM { \
- "CAN_TM", \
- 6, \
- { { "n_sent", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_can_tm_t, n_sent) }, \
- { "n_rcv", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_can_tm_t, n_rcv) }, \
- { "last_sent", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_can_tm_t, last_sent) }, \
- { "last_rcv", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_can_tm_t, last_rcv) }, \
- { "last_sent_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_can_tm_t, last_sent_ts) }, \
- { "last_rcv_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_can_tm_t, last_rcv_ts) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a can_tm 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 n_sent Number of sent messages
- * @param n_rcv Number of received messages
- * @param last_sent Id of the last sent message
- * @param last_rcv Id of the last received message
- * @param last_sent_ts Timestamp of the last sent message
- * @param last_rcv_ts Timestamp of the last received message
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_can_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint16_t n_sent, uint16_t n_rcv, uint8_t last_sent, uint8_t last_rcv, uint64_t last_sent_ts, uint64_t last_rcv_ts)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CAN_TM_LEN];
- _mav_put_uint64_t(buf, 0, last_sent_ts);
- _mav_put_uint64_t(buf, 8, last_rcv_ts);
- _mav_put_uint16_t(buf, 16, n_sent);
- _mav_put_uint16_t(buf, 18, n_rcv);
- _mav_put_uint8_t(buf, 20, last_sent);
- _mav_put_uint8_t(buf, 21, last_rcv);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAN_TM_LEN);
-#else
- mavlink_can_tm_t packet;
- packet.last_sent_ts = last_sent_ts;
- packet.last_rcv_ts = last_rcv_ts;
- packet.n_sent = n_sent;
- packet.n_rcv = n_rcv;
- packet.last_sent = last_sent;
- packet.last_rcv = last_rcv;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAN_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_CAN_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAN_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_TM_LEN, MAVLINK_MSG_ID_CAN_TM_CRC);
-}
-
-/**
- * @brief Pack a can_tm 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 n_sent Number of sent messages
- * @param n_rcv Number of received messages
- * @param last_sent Id of the last sent message
- * @param last_rcv Id of the last received message
- * @param last_sent_ts Timestamp of the last sent message
- * @param last_rcv_ts Timestamp of the last received message
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_can_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint16_t n_sent,uint16_t n_rcv,uint8_t last_sent,uint8_t last_rcv,uint64_t last_sent_ts,uint64_t last_rcv_ts)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CAN_TM_LEN];
- _mav_put_uint64_t(buf, 0, last_sent_ts);
- _mav_put_uint64_t(buf, 8, last_rcv_ts);
- _mav_put_uint16_t(buf, 16, n_sent);
- _mav_put_uint16_t(buf, 18, n_rcv);
- _mav_put_uint8_t(buf, 20, last_sent);
- _mav_put_uint8_t(buf, 21, last_rcv);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAN_TM_LEN);
-#else
- mavlink_can_tm_t packet;
- packet.last_sent_ts = last_sent_ts;
- packet.last_rcv_ts = last_rcv_ts;
- packet.n_sent = n_sent;
- packet.n_rcv = n_rcv;
- packet.last_sent = last_sent;
- packet.last_rcv = last_rcv;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAN_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_CAN_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAN_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_TM_LEN, MAVLINK_MSG_ID_CAN_TM_CRC);
-}
-
-/**
- * @brief Encode a can_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_can_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_can_tm_t* can_tm)
-{
- return mavlink_msg_can_tm_pack(system_id, component_id, msg, can_tm->n_sent, can_tm->n_rcv, can_tm->last_sent, can_tm->last_rcv, can_tm->last_sent_ts, can_tm->last_rcv_ts);
-}
-
-/**
- * @brief Encode a can_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_can_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_can_tm_t* can_tm)
-{
- return mavlink_msg_can_tm_pack_chan(system_id, component_id, chan, msg, can_tm->n_sent, can_tm->n_rcv, can_tm->last_sent, can_tm->last_rcv, can_tm->last_sent_ts, can_tm->last_rcv_ts);
-}
-
-/**
- * @brief Send a can_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param n_sent Number of sent messages
- * @param n_rcv Number of received messages
- * @param last_sent Id of the last sent message
- * @param last_rcv Id of the last received message
- * @param last_sent_ts Timestamp of the last sent message
- * @param last_rcv_ts Timestamp of the last received message
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_can_tm_send(mavlink_channel_t chan, uint16_t n_sent, uint16_t n_rcv, uint8_t last_sent, uint8_t last_rcv, uint64_t last_sent_ts, uint64_t last_rcv_ts)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CAN_TM_LEN];
- _mav_put_uint64_t(buf, 0, last_sent_ts);
- _mav_put_uint64_t(buf, 8, last_rcv_ts);
- _mav_put_uint16_t(buf, 16, n_sent);
- _mav_put_uint16_t(buf, 18, n_rcv);
- _mav_put_uint8_t(buf, 20, last_sent);
- _mav_put_uint8_t(buf, 21, last_rcv);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_TM, buf, MAVLINK_MSG_ID_CAN_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_TM_LEN, MAVLINK_MSG_ID_CAN_TM_CRC);
-#else
- mavlink_can_tm_t packet;
- packet.last_sent_ts = last_sent_ts;
- packet.last_rcv_ts = last_rcv_ts;
- packet.n_sent = n_sent;
- packet.n_rcv = n_rcv;
- packet.last_sent = last_sent;
- packet.last_rcv = last_rcv;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_TM, (const char *)&packet, MAVLINK_MSG_ID_CAN_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_TM_LEN, MAVLINK_MSG_ID_CAN_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a can_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_can_tm_send_struct(mavlink_channel_t chan, const mavlink_can_tm_t* can_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_can_tm_send(chan, can_tm->n_sent, can_tm->n_rcv, can_tm->last_sent, can_tm->last_rcv, can_tm->last_sent_ts, can_tm->last_rcv_ts);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_TM, (const char *)can_tm, MAVLINK_MSG_ID_CAN_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_TM_LEN, MAVLINK_MSG_ID_CAN_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_CAN_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t n_sent, uint16_t n_rcv, uint8_t last_sent, uint8_t last_rcv, uint64_t last_sent_ts, uint64_t last_rcv_ts)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, last_sent_ts);
- _mav_put_uint64_t(buf, 8, last_rcv_ts);
- _mav_put_uint16_t(buf, 16, n_sent);
- _mav_put_uint16_t(buf, 18, n_rcv);
- _mav_put_uint8_t(buf, 20, last_sent);
- _mav_put_uint8_t(buf, 21, last_rcv);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_TM, buf, MAVLINK_MSG_ID_CAN_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_TM_LEN, MAVLINK_MSG_ID_CAN_TM_CRC);
-#else
- mavlink_can_tm_t *packet = (mavlink_can_tm_t *)msgbuf;
- packet->last_sent_ts = last_sent_ts;
- packet->last_rcv_ts = last_rcv_ts;
- packet->n_sent = n_sent;
- packet->n_rcv = n_rcv;
- packet->last_sent = last_sent;
- packet->last_rcv = last_rcv;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_TM, (const char *)packet, MAVLINK_MSG_ID_CAN_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_TM_LEN, MAVLINK_MSG_ID_CAN_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE CAN_TM UNPACKING
-
-
-/**
- * @brief Get field n_sent from can_tm message
- *
- * @return Number of sent messages
- */
-static inline uint16_t mavlink_msg_can_tm_get_n_sent(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 16);
-}
-
-/**
- * @brief Get field n_rcv from can_tm message
- *
- * @return Number of received messages
- */
-static inline uint16_t mavlink_msg_can_tm_get_n_rcv(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 18);
-}
-
-/**
- * @brief Get field last_sent from can_tm message
- *
- * @return Id of the last sent message
- */
-static inline uint8_t mavlink_msg_can_tm_get_last_sent(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 20);
-}
-
-/**
- * @brief Get field last_rcv from can_tm message
- *
- * @return Id of the last received message
- */
-static inline uint8_t mavlink_msg_can_tm_get_last_rcv(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 21);
-}
-
-/**
- * @brief Get field last_sent_ts from can_tm message
- *
- * @return Timestamp of the last sent message
- */
-static inline uint64_t mavlink_msg_can_tm_get_last_sent_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field last_rcv_ts from can_tm message
- *
- * @return Timestamp of the last received message
- */
-static inline uint64_t mavlink_msg_can_tm_get_last_rcv_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 8);
-}
-
-/**
- * @brief Decode a can_tm message into a struct
- *
- * @param msg The message to decode
- * @param can_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_can_tm_decode(const mavlink_message_t* msg, mavlink_can_tm_t* can_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- can_tm->last_sent_ts = mavlink_msg_can_tm_get_last_sent_ts(msg);
- can_tm->last_rcv_ts = mavlink_msg_can_tm_get_last_rcv_ts(msg);
- can_tm->n_sent = mavlink_msg_can_tm_get_n_sent(msg);
- can_tm->n_rcv = mavlink_msg_can_tm_get_n_rcv(msg);
- can_tm->last_sent = mavlink_msg_can_tm_get_last_sent(msg);
- can_tm->last_rcv = mavlink_msg_can_tm_get_last_rcv(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_CAN_TM_LEN? msg->len : MAVLINK_MSG_ID_CAN_TM_LEN;
- memset(can_tm, 0, MAVLINK_MSG_ID_CAN_TM_LEN);
- memcpy(can_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_dpl_tm.h b/mavlink_lib/hermes/mavlink_msg_dpl_tm.h
deleted file mode 100644
index eeaf59732e21dd6c5c9418d39ccb2ebf2876cb09..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_dpl_tm.h
+++ /dev/null
@@ -1,313 +0,0 @@
-#pragma once
-// MESSAGE DPL_TM PACKING
-
-#define MAVLINK_MSG_ID_DPL_TM 166
-
-MAVPACKED(
-typedef struct __mavlink_dpl_tm_t {
- uint64_t timestamp; /*< When was this logged*/
- float cutter_1_test_current; /*< Mean current flowing through the primary cutter during the last cutter test*/
- float cutter_2_test_current; /*< Mean current flowing through the backup cutter during the last cutter test*/
- uint8_t fsm_state; /*< Current state of the dpl controller*/
- uint8_t cutter_state; /*< Cutter state*/
-}) mavlink_dpl_tm_t;
-
-#define MAVLINK_MSG_ID_DPL_TM_LEN 18
-#define MAVLINK_MSG_ID_DPL_TM_MIN_LEN 18
-#define MAVLINK_MSG_ID_166_LEN 18
-#define MAVLINK_MSG_ID_166_MIN_LEN 18
-
-#define MAVLINK_MSG_ID_DPL_TM_CRC 240
-#define MAVLINK_MSG_ID_166_CRC 240
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_DPL_TM { \
- 166, \
- "DPL_TM", \
- 5, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_dpl_tm_t, timestamp) }, \
- { "fsm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_dpl_tm_t, fsm_state) }, \
- { "cutter_1_test_current", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_dpl_tm_t, cutter_1_test_current) }, \
- { "cutter_2_test_current", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_dpl_tm_t, cutter_2_test_current) }, \
- { "cutter_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_dpl_tm_t, cutter_state) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_DPL_TM { \
- "DPL_TM", \
- 5, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_dpl_tm_t, timestamp) }, \
- { "fsm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_dpl_tm_t, fsm_state) }, \
- { "cutter_1_test_current", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_dpl_tm_t, cutter_1_test_current) }, \
- { "cutter_2_test_current", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_dpl_tm_t, cutter_2_test_current) }, \
- { "cutter_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_dpl_tm_t, cutter_state) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a dpl_tm 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 When was this logged
- * @param fsm_state Current state of the dpl controller
- * @param cutter_1_test_current Mean current flowing through the primary cutter during the last cutter test
- * @param cutter_2_test_current Mean current flowing through the backup cutter during the last cutter test
- * @param cutter_state Cutter state
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_dpl_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t fsm_state, float cutter_1_test_current, float cutter_2_test_current, uint8_t cutter_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_DPL_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, cutter_1_test_current);
- _mav_put_float(buf, 12, cutter_2_test_current);
- _mav_put_uint8_t(buf, 16, fsm_state);
- _mav_put_uint8_t(buf, 17, cutter_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DPL_TM_LEN);
-#else
- mavlink_dpl_tm_t packet;
- packet.timestamp = timestamp;
- packet.cutter_1_test_current = cutter_1_test_current;
- packet.cutter_2_test_current = cutter_2_test_current;
- packet.fsm_state = fsm_state;
- packet.cutter_state = cutter_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DPL_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_DPL_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DPL_TM_MIN_LEN, MAVLINK_MSG_ID_DPL_TM_LEN, MAVLINK_MSG_ID_DPL_TM_CRC);
-}
-
-/**
- * @brief Pack a dpl_tm 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 When was this logged
- * @param fsm_state Current state of the dpl controller
- * @param cutter_1_test_current Mean current flowing through the primary cutter during the last cutter test
- * @param cutter_2_test_current Mean current flowing through the backup cutter during the last cutter test
- * @param cutter_state Cutter state
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_dpl_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t fsm_state,float cutter_1_test_current,float cutter_2_test_current,uint8_t cutter_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_DPL_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, cutter_1_test_current);
- _mav_put_float(buf, 12, cutter_2_test_current);
- _mav_put_uint8_t(buf, 16, fsm_state);
- _mav_put_uint8_t(buf, 17, cutter_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DPL_TM_LEN);
-#else
- mavlink_dpl_tm_t packet;
- packet.timestamp = timestamp;
- packet.cutter_1_test_current = cutter_1_test_current;
- packet.cutter_2_test_current = cutter_2_test_current;
- packet.fsm_state = fsm_state;
- packet.cutter_state = cutter_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DPL_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_DPL_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DPL_TM_MIN_LEN, MAVLINK_MSG_ID_DPL_TM_LEN, MAVLINK_MSG_ID_DPL_TM_CRC);
-}
-
-/**
- * @brief Encode a dpl_tm 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 dpl_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_dpl_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_dpl_tm_t* dpl_tm)
-{
- return mavlink_msg_dpl_tm_pack(system_id, component_id, msg, dpl_tm->timestamp, dpl_tm->fsm_state, dpl_tm->cutter_1_test_current, dpl_tm->cutter_2_test_current, dpl_tm->cutter_state);
-}
-
-/**
- * @brief Encode a dpl_tm 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 dpl_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_dpl_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_dpl_tm_t* dpl_tm)
-{
- return mavlink_msg_dpl_tm_pack_chan(system_id, component_id, chan, msg, dpl_tm->timestamp, dpl_tm->fsm_state, dpl_tm->cutter_1_test_current, dpl_tm->cutter_2_test_current, dpl_tm->cutter_state);
-}
-
-/**
- * @brief Send a dpl_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp When was this logged
- * @param fsm_state Current state of the dpl controller
- * @param cutter_1_test_current Mean current flowing through the primary cutter during the last cutter test
- * @param cutter_2_test_current Mean current flowing through the backup cutter during the last cutter test
- * @param cutter_state Cutter state
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_dpl_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t fsm_state, float cutter_1_test_current, float cutter_2_test_current, uint8_t cutter_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_DPL_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, cutter_1_test_current);
- _mav_put_float(buf, 12, cutter_2_test_current);
- _mav_put_uint8_t(buf, 16, fsm_state);
- _mav_put_uint8_t(buf, 17, cutter_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DPL_TM, buf, MAVLINK_MSG_ID_DPL_TM_MIN_LEN, MAVLINK_MSG_ID_DPL_TM_LEN, MAVLINK_MSG_ID_DPL_TM_CRC);
-#else
- mavlink_dpl_tm_t packet;
- packet.timestamp = timestamp;
- packet.cutter_1_test_current = cutter_1_test_current;
- packet.cutter_2_test_current = cutter_2_test_current;
- packet.fsm_state = fsm_state;
- packet.cutter_state = cutter_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DPL_TM, (const char *)&packet, MAVLINK_MSG_ID_DPL_TM_MIN_LEN, MAVLINK_MSG_ID_DPL_TM_LEN, MAVLINK_MSG_ID_DPL_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a dpl_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_dpl_tm_send_struct(mavlink_channel_t chan, const mavlink_dpl_tm_t* dpl_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_dpl_tm_send(chan, dpl_tm->timestamp, dpl_tm->fsm_state, dpl_tm->cutter_1_test_current, dpl_tm->cutter_2_test_current, dpl_tm->cutter_state);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DPL_TM, (const char *)dpl_tm, MAVLINK_MSG_ID_DPL_TM_MIN_LEN, MAVLINK_MSG_ID_DPL_TM_LEN, MAVLINK_MSG_ID_DPL_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_DPL_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_dpl_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t fsm_state, float cutter_1_test_current, float cutter_2_test_current, uint8_t cutter_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, cutter_1_test_current);
- _mav_put_float(buf, 12, cutter_2_test_current);
- _mav_put_uint8_t(buf, 16, fsm_state);
- _mav_put_uint8_t(buf, 17, cutter_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DPL_TM, buf, MAVLINK_MSG_ID_DPL_TM_MIN_LEN, MAVLINK_MSG_ID_DPL_TM_LEN, MAVLINK_MSG_ID_DPL_TM_CRC);
-#else
- mavlink_dpl_tm_t *packet = (mavlink_dpl_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->cutter_1_test_current = cutter_1_test_current;
- packet->cutter_2_test_current = cutter_2_test_current;
- packet->fsm_state = fsm_state;
- packet->cutter_state = cutter_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DPL_TM, (const char *)packet, MAVLINK_MSG_ID_DPL_TM_MIN_LEN, MAVLINK_MSG_ID_DPL_TM_LEN, MAVLINK_MSG_ID_DPL_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE DPL_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from dpl_tm message
- *
- * @return When was this logged
- */
-static inline uint64_t mavlink_msg_dpl_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field fsm_state from dpl_tm message
- *
- * @return Current state of the dpl controller
- */
-static inline uint8_t mavlink_msg_dpl_tm_get_fsm_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 16);
-}
-
-/**
- * @brief Get field cutter_1_test_current from dpl_tm message
- *
- * @return Mean current flowing through the primary cutter during the last cutter test
- */
-static inline float mavlink_msg_dpl_tm_get_cutter_1_test_current(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field cutter_2_test_current from dpl_tm message
- *
- * @return Mean current flowing through the backup cutter during the last cutter test
- */
-static inline float mavlink_msg_dpl_tm_get_cutter_2_test_current(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field cutter_state from dpl_tm message
- *
- * @return Cutter state
- */
-static inline uint8_t mavlink_msg_dpl_tm_get_cutter_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 17);
-}
-
-/**
- * @brief Decode a dpl_tm message into a struct
- *
- * @param msg The message to decode
- * @param dpl_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_dpl_tm_decode(const mavlink_message_t* msg, mavlink_dpl_tm_t* dpl_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- dpl_tm->timestamp = mavlink_msg_dpl_tm_get_timestamp(msg);
- dpl_tm->cutter_1_test_current = mavlink_msg_dpl_tm_get_cutter_1_test_current(msg);
- dpl_tm->cutter_2_test_current = mavlink_msg_dpl_tm_get_cutter_2_test_current(msg);
- dpl_tm->fsm_state = mavlink_msg_dpl_tm_get_fsm_state(msg);
- dpl_tm->cutter_state = mavlink_msg_dpl_tm_get_cutter_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_DPL_TM_LEN? msg->len : MAVLINK_MSG_ID_DPL_TM_LEN;
- memset(dpl_tm, 0, MAVLINK_MSG_ID_DPL_TM_LEN);
- memcpy(dpl_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_fmm_tm.h b/mavlink_lib/hermes/mavlink_msg_fmm_tm.h
deleted file mode 100644
index 615ca66186b6073ef3c9d04212a2eca5c439a194..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_fmm_tm.h
+++ /dev/null
@@ -1,388 +0,0 @@
-#pragma once
-// MESSAGE FMM_TM PACKING
-
-#define MAVLINK_MSG_ID_FMM_TM 161
-
-MAVPACKED(
-typedef struct __mavlink_fmm_tm_t {
- uint64_t timestamp; /*< Timestamp*/
- uint64_t pin_launch_last_change; /*< Last change of launch pin*/
- uint64_t pin_nosecone_last_change; /*< Last change of nosecone pin*/
- uint8_t state; /*< FMM State*/
- uint8_t pin_launch_num_changes; /*< Number of changes of the launch pin*/
- uint8_t pin_launch_state; /*< Current state of the launch pin*/
- uint8_t pin_nosecone_num_changes; /*< Number of changes of the nosecone pin*/
- uint8_t pin_nosecone_state; /*< Current state of the nosecone pin*/
-}) mavlink_fmm_tm_t;
-
-#define MAVLINK_MSG_ID_FMM_TM_LEN 29
-#define MAVLINK_MSG_ID_FMM_TM_MIN_LEN 29
-#define MAVLINK_MSG_ID_161_LEN 29
-#define MAVLINK_MSG_ID_161_MIN_LEN 29
-
-#define MAVLINK_MSG_ID_FMM_TM_CRC 87
-#define MAVLINK_MSG_ID_161_CRC 87
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_FMM_TM { \
- 161, \
- "FMM_TM", \
- 8, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_fmm_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_fmm_tm_t, state) }, \
- { "pin_launch_last_change", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_fmm_tm_t, pin_launch_last_change) }, \
- { "pin_launch_num_changes", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_fmm_tm_t, pin_launch_num_changes) }, \
- { "pin_launch_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_fmm_tm_t, pin_launch_state) }, \
- { "pin_nosecone_last_change", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_fmm_tm_t, pin_nosecone_last_change) }, \
- { "pin_nosecone_num_changes", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_fmm_tm_t, pin_nosecone_num_changes) }, \
- { "pin_nosecone_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_fmm_tm_t, pin_nosecone_state) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_FMM_TM { \
- "FMM_TM", \
- 8, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_fmm_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_fmm_tm_t, state) }, \
- { "pin_launch_last_change", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_fmm_tm_t, pin_launch_last_change) }, \
- { "pin_launch_num_changes", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_fmm_tm_t, pin_launch_num_changes) }, \
- { "pin_launch_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_fmm_tm_t, pin_launch_state) }, \
- { "pin_nosecone_last_change", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_fmm_tm_t, pin_nosecone_last_change) }, \
- { "pin_nosecone_num_changes", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_fmm_tm_t, pin_nosecone_num_changes) }, \
- { "pin_nosecone_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_fmm_tm_t, pin_nosecone_state) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a fmm_tm 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 Timestamp
- * @param state FMM State
- * @param pin_launch_last_change Last change of launch pin
- * @param pin_launch_num_changes Number of changes of the launch pin
- * @param pin_launch_state Current state of the launch pin
- * @param pin_nosecone_last_change Last change of nosecone pin
- * @param pin_nosecone_num_changes Number of changes of the nosecone pin
- * @param pin_nosecone_state Current state of the nosecone pin
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_fmm_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t state, uint64_t pin_launch_last_change, uint8_t pin_launch_num_changes, uint8_t pin_launch_state, uint64_t pin_nosecone_last_change, uint8_t pin_nosecone_num_changes, uint8_t pin_nosecone_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_FMM_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, pin_launch_last_change);
- _mav_put_uint64_t(buf, 16, pin_nosecone_last_change);
- _mav_put_uint8_t(buf, 24, state);
- _mav_put_uint8_t(buf, 25, pin_launch_num_changes);
- _mav_put_uint8_t(buf, 26, pin_launch_state);
- _mav_put_uint8_t(buf, 27, pin_nosecone_num_changes);
- _mav_put_uint8_t(buf, 28, pin_nosecone_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FMM_TM_LEN);
-#else
- mavlink_fmm_tm_t packet;
- packet.timestamp = timestamp;
- packet.pin_launch_last_change = pin_launch_last_change;
- packet.pin_nosecone_last_change = pin_nosecone_last_change;
- packet.state = state;
- packet.pin_launch_num_changes = pin_launch_num_changes;
- packet.pin_launch_state = pin_launch_state;
- packet.pin_nosecone_num_changes = pin_nosecone_num_changes;
- packet.pin_nosecone_state = pin_nosecone_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FMM_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_FMM_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FMM_TM_MIN_LEN, MAVLINK_MSG_ID_FMM_TM_LEN, MAVLINK_MSG_ID_FMM_TM_CRC);
-}
-
-/**
- * @brief Pack a fmm_tm 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 Timestamp
- * @param state FMM State
- * @param pin_launch_last_change Last change of launch pin
- * @param pin_launch_num_changes Number of changes of the launch pin
- * @param pin_launch_state Current state of the launch pin
- * @param pin_nosecone_last_change Last change of nosecone pin
- * @param pin_nosecone_num_changes Number of changes of the nosecone pin
- * @param pin_nosecone_state Current state of the nosecone pin
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_fmm_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t state,uint64_t pin_launch_last_change,uint8_t pin_launch_num_changes,uint8_t pin_launch_state,uint64_t pin_nosecone_last_change,uint8_t pin_nosecone_num_changes,uint8_t pin_nosecone_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_FMM_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, pin_launch_last_change);
- _mav_put_uint64_t(buf, 16, pin_nosecone_last_change);
- _mav_put_uint8_t(buf, 24, state);
- _mav_put_uint8_t(buf, 25, pin_launch_num_changes);
- _mav_put_uint8_t(buf, 26, pin_launch_state);
- _mav_put_uint8_t(buf, 27, pin_nosecone_num_changes);
- _mav_put_uint8_t(buf, 28, pin_nosecone_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FMM_TM_LEN);
-#else
- mavlink_fmm_tm_t packet;
- packet.timestamp = timestamp;
- packet.pin_launch_last_change = pin_launch_last_change;
- packet.pin_nosecone_last_change = pin_nosecone_last_change;
- packet.state = state;
- packet.pin_launch_num_changes = pin_launch_num_changes;
- packet.pin_launch_state = pin_launch_state;
- packet.pin_nosecone_num_changes = pin_nosecone_num_changes;
- packet.pin_nosecone_state = pin_nosecone_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FMM_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_FMM_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FMM_TM_MIN_LEN, MAVLINK_MSG_ID_FMM_TM_LEN, MAVLINK_MSG_ID_FMM_TM_CRC);
-}
-
-/**
- * @brief Encode a fmm_tm 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 fmm_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_fmm_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fmm_tm_t* fmm_tm)
-{
- return mavlink_msg_fmm_tm_pack(system_id, component_id, msg, fmm_tm->timestamp, fmm_tm->state, fmm_tm->pin_launch_last_change, fmm_tm->pin_launch_num_changes, fmm_tm->pin_launch_state, fmm_tm->pin_nosecone_last_change, fmm_tm->pin_nosecone_num_changes, fmm_tm->pin_nosecone_state);
-}
-
-/**
- * @brief Encode a fmm_tm 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 fmm_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_fmm_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fmm_tm_t* fmm_tm)
-{
- return mavlink_msg_fmm_tm_pack_chan(system_id, component_id, chan, msg, fmm_tm->timestamp, fmm_tm->state, fmm_tm->pin_launch_last_change, fmm_tm->pin_launch_num_changes, fmm_tm->pin_launch_state, fmm_tm->pin_nosecone_last_change, fmm_tm->pin_nosecone_num_changes, fmm_tm->pin_nosecone_state);
-}
-
-/**
- * @brief Send a fmm_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp Timestamp
- * @param state FMM State
- * @param pin_launch_last_change Last change of launch pin
- * @param pin_launch_num_changes Number of changes of the launch pin
- * @param pin_launch_state Current state of the launch pin
- * @param pin_nosecone_last_change Last change of nosecone pin
- * @param pin_nosecone_num_changes Number of changes of the nosecone pin
- * @param pin_nosecone_state Current state of the nosecone pin
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_fmm_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state, uint64_t pin_launch_last_change, uint8_t pin_launch_num_changes, uint8_t pin_launch_state, uint64_t pin_nosecone_last_change, uint8_t pin_nosecone_num_changes, uint8_t pin_nosecone_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_FMM_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, pin_launch_last_change);
- _mav_put_uint64_t(buf, 16, pin_nosecone_last_change);
- _mav_put_uint8_t(buf, 24, state);
- _mav_put_uint8_t(buf, 25, pin_launch_num_changes);
- _mav_put_uint8_t(buf, 26, pin_launch_state);
- _mav_put_uint8_t(buf, 27, pin_nosecone_num_changes);
- _mav_put_uint8_t(buf, 28, pin_nosecone_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FMM_TM, buf, MAVLINK_MSG_ID_FMM_TM_MIN_LEN, MAVLINK_MSG_ID_FMM_TM_LEN, MAVLINK_MSG_ID_FMM_TM_CRC);
-#else
- mavlink_fmm_tm_t packet;
- packet.timestamp = timestamp;
- packet.pin_launch_last_change = pin_launch_last_change;
- packet.pin_nosecone_last_change = pin_nosecone_last_change;
- packet.state = state;
- packet.pin_launch_num_changes = pin_launch_num_changes;
- packet.pin_launch_state = pin_launch_state;
- packet.pin_nosecone_num_changes = pin_nosecone_num_changes;
- packet.pin_nosecone_state = pin_nosecone_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FMM_TM, (const char *)&packet, MAVLINK_MSG_ID_FMM_TM_MIN_LEN, MAVLINK_MSG_ID_FMM_TM_LEN, MAVLINK_MSG_ID_FMM_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a fmm_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_fmm_tm_send_struct(mavlink_channel_t chan, const mavlink_fmm_tm_t* fmm_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_fmm_tm_send(chan, fmm_tm->timestamp, fmm_tm->state, fmm_tm->pin_launch_last_change, fmm_tm->pin_launch_num_changes, fmm_tm->pin_launch_state, fmm_tm->pin_nosecone_last_change, fmm_tm->pin_nosecone_num_changes, fmm_tm->pin_nosecone_state);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FMM_TM, (const char *)fmm_tm, MAVLINK_MSG_ID_FMM_TM_MIN_LEN, MAVLINK_MSG_ID_FMM_TM_LEN, MAVLINK_MSG_ID_FMM_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_FMM_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_fmm_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t state, uint64_t pin_launch_last_change, uint8_t pin_launch_num_changes, uint8_t pin_launch_state, uint64_t pin_nosecone_last_change, uint8_t pin_nosecone_num_changes, uint8_t pin_nosecone_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, pin_launch_last_change);
- _mav_put_uint64_t(buf, 16, pin_nosecone_last_change);
- _mav_put_uint8_t(buf, 24, state);
- _mav_put_uint8_t(buf, 25, pin_launch_num_changes);
- _mav_put_uint8_t(buf, 26, pin_launch_state);
- _mav_put_uint8_t(buf, 27, pin_nosecone_num_changes);
- _mav_put_uint8_t(buf, 28, pin_nosecone_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FMM_TM, buf, MAVLINK_MSG_ID_FMM_TM_MIN_LEN, MAVLINK_MSG_ID_FMM_TM_LEN, MAVLINK_MSG_ID_FMM_TM_CRC);
-#else
- mavlink_fmm_tm_t *packet = (mavlink_fmm_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->pin_launch_last_change = pin_launch_last_change;
- packet->pin_nosecone_last_change = pin_nosecone_last_change;
- packet->state = state;
- packet->pin_launch_num_changes = pin_launch_num_changes;
- packet->pin_launch_state = pin_launch_state;
- packet->pin_nosecone_num_changes = pin_nosecone_num_changes;
- packet->pin_nosecone_state = pin_nosecone_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FMM_TM, (const char *)packet, MAVLINK_MSG_ID_FMM_TM_MIN_LEN, MAVLINK_MSG_ID_FMM_TM_LEN, MAVLINK_MSG_ID_FMM_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE FMM_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from fmm_tm message
- *
- * @return Timestamp
- */
-static inline uint64_t mavlink_msg_fmm_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field state from fmm_tm message
- *
- * @return FMM State
- */
-static inline uint8_t mavlink_msg_fmm_tm_get_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 24);
-}
-
-/**
- * @brief Get field pin_launch_last_change from fmm_tm message
- *
- * @return Last change of launch pin
- */
-static inline uint64_t mavlink_msg_fmm_tm_get_pin_launch_last_change(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 8);
-}
-
-/**
- * @brief Get field pin_launch_num_changes from fmm_tm message
- *
- * @return Number of changes of the launch pin
- */
-static inline uint8_t mavlink_msg_fmm_tm_get_pin_launch_num_changes(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 25);
-}
-
-/**
- * @brief Get field pin_launch_state from fmm_tm message
- *
- * @return Current state of the launch pin
- */
-static inline uint8_t mavlink_msg_fmm_tm_get_pin_launch_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 26);
-}
-
-/**
- * @brief Get field pin_nosecone_last_change from fmm_tm message
- *
- * @return Last change of nosecone pin
- */
-static inline uint64_t mavlink_msg_fmm_tm_get_pin_nosecone_last_change(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 16);
-}
-
-/**
- * @brief Get field pin_nosecone_num_changes from fmm_tm message
- *
- * @return Number of changes of the nosecone pin
- */
-static inline uint8_t mavlink_msg_fmm_tm_get_pin_nosecone_num_changes(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 27);
-}
-
-/**
- * @brief Get field pin_nosecone_state from fmm_tm message
- *
- * @return Current state of the nosecone pin
- */
-static inline uint8_t mavlink_msg_fmm_tm_get_pin_nosecone_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 28);
-}
-
-/**
- * @brief Decode a fmm_tm message into a struct
- *
- * @param msg The message to decode
- * @param fmm_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_fmm_tm_decode(const mavlink_message_t* msg, mavlink_fmm_tm_t* fmm_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- fmm_tm->timestamp = mavlink_msg_fmm_tm_get_timestamp(msg);
- fmm_tm->pin_launch_last_change = mavlink_msg_fmm_tm_get_pin_launch_last_change(msg);
- fmm_tm->pin_nosecone_last_change = mavlink_msg_fmm_tm_get_pin_nosecone_last_change(msg);
- fmm_tm->state = mavlink_msg_fmm_tm_get_state(msg);
- fmm_tm->pin_launch_num_changes = mavlink_msg_fmm_tm_get_pin_launch_num_changes(msg);
- fmm_tm->pin_launch_state = mavlink_msg_fmm_tm_get_pin_launch_state(msg);
- fmm_tm->pin_nosecone_num_changes = mavlink_msg_fmm_tm_get_pin_nosecone_num_changes(msg);
- fmm_tm->pin_nosecone_state = mavlink_msg_fmm_tm_get_pin_nosecone_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_FMM_TM_LEN? msg->len : MAVLINK_MSG_ID_FMM_TM_LEN;
- memset(fmm_tm, 0, MAVLINK_MSG_ID_FMM_TM_LEN);
- memcpy(fmm_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_gps_tm.h b/mavlink_lib/hermes/mavlink_msg_gps_tm.h
deleted file mode 100644
index 9e0fd4f5a3ad0b4dca328657a1c7b1d4d4ed977f..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_gps_tm.h
+++ /dev/null
@@ -1,438 +0,0 @@
-#pragma once
-// MESSAGE GPS_TM PACKING
-
-#define MAVLINK_MSG_ID_GPS_TM 172
-
-MAVPACKED(
-typedef struct __mavlink_gps_tm_t {
- uint64_t timestamp; /*< When was this logged*/
- double lat; /*< Latitude*/
- double lon; /*< Longitude*/
- double altitude; /*< Altitude*/
- float vel_north; /*< Velocity in NED frame (north)*/
- float vel_east; /*< Velocity in NED frame (east)*/
- float vel_down; /*< Velocity in NED frame (down)*/
- float vel_mag; /*< Speed*/
- int32_t n_satellites; /*< Number of connected satellites*/
- uint8_t fix; /*< Wether the GPS has a FIX*/
-}) mavlink_gps_tm_t;
-
-#define MAVLINK_MSG_ID_GPS_TM_LEN 53
-#define MAVLINK_MSG_ID_GPS_TM_MIN_LEN 53
-#define MAVLINK_MSG_ID_172_LEN 53
-#define MAVLINK_MSG_ID_172_MIN_LEN 53
-
-#define MAVLINK_MSG_ID_GPS_TM_CRC 204
-#define MAVLINK_MSG_ID_172_CRC 204
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_GPS_TM { \
- 172, \
- "GPS_TM", \
- 10, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_tm_t, timestamp) }, \
- { "fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_gps_tm_t, fix) }, \
- { "lat", NULL, MAVLINK_TYPE_DOUBLE, 0, 8, offsetof(mavlink_gps_tm_t, lat) }, \
- { "lon", NULL, MAVLINK_TYPE_DOUBLE, 0, 16, offsetof(mavlink_gps_tm_t, lon) }, \
- { "altitude", NULL, MAVLINK_TYPE_DOUBLE, 0, 24, offsetof(mavlink_gps_tm_t, altitude) }, \
- { "vel_north", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_tm_t, vel_north) }, \
- { "vel_east", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gps_tm_t, vel_east) }, \
- { "vel_down", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gps_tm_t, vel_down) }, \
- { "vel_mag", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_tm_t, vel_mag) }, \
- { "n_satellites", NULL, MAVLINK_TYPE_INT32_T, 0, 48, offsetof(mavlink_gps_tm_t, n_satellites) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_GPS_TM { \
- "GPS_TM", \
- 10, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_tm_t, timestamp) }, \
- { "fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_gps_tm_t, fix) }, \
- { "lat", NULL, MAVLINK_TYPE_DOUBLE, 0, 8, offsetof(mavlink_gps_tm_t, lat) }, \
- { "lon", NULL, MAVLINK_TYPE_DOUBLE, 0, 16, offsetof(mavlink_gps_tm_t, lon) }, \
- { "altitude", NULL, MAVLINK_TYPE_DOUBLE, 0, 24, offsetof(mavlink_gps_tm_t, altitude) }, \
- { "vel_north", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_tm_t, vel_north) }, \
- { "vel_east", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gps_tm_t, vel_east) }, \
- { "vel_down", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gps_tm_t, vel_down) }, \
- { "vel_mag", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_tm_t, vel_mag) }, \
- { "n_satellites", NULL, MAVLINK_TYPE_INT32_T, 0, 48, offsetof(mavlink_gps_tm_t, n_satellites) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a gps_tm 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 When was this logged
- * @param fix Wether the GPS has a FIX
- * @param lat Latitude
- * @param lon Longitude
- * @param altitude Altitude
- * @param vel_north Velocity in NED frame (north)
- * @param vel_east Velocity in NED frame (east)
- * @param vel_down Velocity in NED frame (down)
- * @param vel_mag Speed
- * @param n_satellites Number of connected satellites
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_gps_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t fix, double lat, double lon, double altitude, float vel_north, float vel_east, float vel_down, float vel_mag, int32_t n_satellites)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GPS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, lat);
- _mav_put_double(buf, 16, lon);
- _mav_put_double(buf, 24, altitude);
- _mav_put_float(buf, 32, vel_north);
- _mav_put_float(buf, 36, vel_east);
- _mav_put_float(buf, 40, vel_down);
- _mav_put_float(buf, 44, vel_mag);
- _mav_put_int32_t(buf, 48, n_satellites);
- _mav_put_uint8_t(buf, 52, fix);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_TM_LEN);
-#else
- mavlink_gps_tm_t packet;
- packet.timestamp = timestamp;
- packet.lat = lat;
- packet.lon = lon;
- packet.altitude = altitude;
- packet.vel_north = vel_north;
- packet.vel_east = vel_east;
- packet.vel_down = vel_down;
- packet.vel_mag = vel_mag;
- packet.n_satellites = n_satellites;
- packet.fix = fix;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_GPS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-}
-
-/**
- * @brief Pack a gps_tm 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 When was this logged
- * @param fix Wether the GPS has a FIX
- * @param lat Latitude
- * @param lon Longitude
- * @param altitude Altitude
- * @param vel_north Velocity in NED frame (north)
- * @param vel_east Velocity in NED frame (east)
- * @param vel_down Velocity in NED frame (down)
- * @param vel_mag Speed
- * @param n_satellites Number of connected satellites
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_gps_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t fix,double lat,double lon,double altitude,float vel_north,float vel_east,float vel_down,float vel_mag,int32_t n_satellites)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GPS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, lat);
- _mav_put_double(buf, 16, lon);
- _mav_put_double(buf, 24, altitude);
- _mav_put_float(buf, 32, vel_north);
- _mav_put_float(buf, 36, vel_east);
- _mav_put_float(buf, 40, vel_down);
- _mav_put_float(buf, 44, vel_mag);
- _mav_put_int32_t(buf, 48, n_satellites);
- _mav_put_uint8_t(buf, 52, fix);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_TM_LEN);
-#else
- mavlink_gps_tm_t packet;
- packet.timestamp = timestamp;
- packet.lat = lat;
- packet.lon = lon;
- packet.altitude = altitude;
- packet.vel_north = vel_north;
- packet.vel_east = vel_east;
- packet.vel_down = vel_down;
- packet.vel_mag = vel_mag;
- packet.n_satellites = n_satellites;
- packet.fix = fix;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_GPS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-}
-
-/**
- * @brief Encode a gps_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_gps_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_tm_t* gps_tm)
-{
- return mavlink_msg_gps_tm_pack(system_id, component_id, msg, gps_tm->timestamp, gps_tm->fix, gps_tm->lat, gps_tm->lon, gps_tm->altitude, gps_tm->vel_north, gps_tm->vel_east, gps_tm->vel_down, gps_tm->vel_mag, gps_tm->n_satellites);
-}
-
-/**
- * @brief Encode a gps_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_gps_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_tm_t* gps_tm)
-{
- return mavlink_msg_gps_tm_pack_chan(system_id, component_id, chan, msg, gps_tm->timestamp, gps_tm->fix, gps_tm->lat, gps_tm->lon, gps_tm->altitude, gps_tm->vel_north, gps_tm->vel_east, gps_tm->vel_down, gps_tm->vel_mag, gps_tm->n_satellites);
-}
-
-/**
- * @brief Send a gps_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp When was this logged
- * @param fix Wether the GPS has a FIX
- * @param lat Latitude
- * @param lon Longitude
- * @param altitude Altitude
- * @param vel_north Velocity in NED frame (north)
- * @param vel_east Velocity in NED frame (east)
- * @param vel_down Velocity in NED frame (down)
- * @param vel_mag Speed
- * @param n_satellites Number of connected satellites
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_gps_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t fix, double lat, double lon, double altitude, float vel_north, float vel_east, float vel_down, float vel_mag, int32_t n_satellites)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GPS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, lat);
- _mav_put_double(buf, 16, lon);
- _mav_put_double(buf, 24, altitude);
- _mav_put_float(buf, 32, vel_north);
- _mav_put_float(buf, 36, vel_east);
- _mav_put_float(buf, 40, vel_down);
- _mav_put_float(buf, 44, vel_mag);
- _mav_put_int32_t(buf, 48, n_satellites);
- _mav_put_uint8_t(buf, 52, fix);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, buf, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#else
- mavlink_gps_tm_t packet;
- packet.timestamp = timestamp;
- packet.lat = lat;
- packet.lon = lon;
- packet.altitude = altitude;
- packet.vel_north = vel_north;
- packet.vel_east = vel_east;
- packet.vel_down = vel_down;
- packet.vel_mag = vel_mag;
- packet.n_satellites = n_satellites;
- packet.fix = fix;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, (const char *)&packet, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a gps_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_gps_tm_send_struct(mavlink_channel_t chan, const mavlink_gps_tm_t* gps_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_gps_tm_send(chan, gps_tm->timestamp, gps_tm->fix, gps_tm->lat, gps_tm->lon, gps_tm->altitude, gps_tm->vel_north, gps_tm->vel_east, gps_tm->vel_down, gps_tm->vel_mag, gps_tm->n_satellites);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, (const char *)gps_tm, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_GPS_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t fix, double lat, double lon, double altitude, float vel_north, float vel_east, float vel_down, float vel_mag, int32_t n_satellites)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, lat);
- _mav_put_double(buf, 16, lon);
- _mav_put_double(buf, 24, altitude);
- _mav_put_float(buf, 32, vel_north);
- _mav_put_float(buf, 36, vel_east);
- _mav_put_float(buf, 40, vel_down);
- _mav_put_float(buf, 44, vel_mag);
- _mav_put_int32_t(buf, 48, n_satellites);
- _mav_put_uint8_t(buf, 52, fix);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, buf, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#else
- mavlink_gps_tm_t *packet = (mavlink_gps_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->lat = lat;
- packet->lon = lon;
- packet->altitude = altitude;
- packet->vel_north = vel_north;
- packet->vel_east = vel_east;
- packet->vel_down = vel_down;
- packet->vel_mag = vel_mag;
- packet->n_satellites = n_satellites;
- packet->fix = fix;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, (const char *)packet, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE GPS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from gps_tm message
- *
- * @return When was this logged
- */
-static inline uint64_t mavlink_msg_gps_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field fix from gps_tm message
- *
- * @return Wether the GPS has a FIX
- */
-static inline uint8_t mavlink_msg_gps_tm_get_fix(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 52);
-}
-
-/**
- * @brief Get field lat from gps_tm message
- *
- * @return Latitude
- */
-static inline double mavlink_msg_gps_tm_get_lat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_double(msg, 8);
-}
-
-/**
- * @brief Get field lon from gps_tm message
- *
- * @return Longitude
- */
-static inline double mavlink_msg_gps_tm_get_lon(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_double(msg, 16);
-}
-
-/**
- * @brief Get field altitude from gps_tm message
- *
- * @return Altitude
- */
-static inline double mavlink_msg_gps_tm_get_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_double(msg, 24);
-}
-
-/**
- * @brief Get field vel_north from gps_tm message
- *
- * @return Velocity in NED frame (north)
- */
-static inline float mavlink_msg_gps_tm_get_vel_north(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field vel_east from gps_tm message
- *
- * @return Velocity in NED frame (east)
- */
-static inline float mavlink_msg_gps_tm_get_vel_east(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field vel_down from gps_tm message
- *
- * @return Velocity in NED frame (down)
- */
-static inline float mavlink_msg_gps_tm_get_vel_down(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field vel_mag from gps_tm message
- *
- * @return Speed
- */
-static inline float mavlink_msg_gps_tm_get_vel_mag(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field n_satellites from gps_tm message
- *
- * @return Number of connected satellites
- */
-static inline int32_t mavlink_msg_gps_tm_get_n_satellites(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 48);
-}
-
-/**
- * @brief Decode a gps_tm message into a struct
- *
- * @param msg The message to decode
- * @param gps_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_gps_tm_decode(const mavlink_message_t* msg, mavlink_gps_tm_t* gps_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- gps_tm->timestamp = mavlink_msg_gps_tm_get_timestamp(msg);
- gps_tm->lat = mavlink_msg_gps_tm_get_lat(msg);
- gps_tm->lon = mavlink_msg_gps_tm_get_lon(msg);
- gps_tm->altitude = mavlink_msg_gps_tm_get_altitude(msg);
- gps_tm->vel_north = mavlink_msg_gps_tm_get_vel_north(msg);
- gps_tm->vel_east = mavlink_msg_gps_tm_get_vel_east(msg);
- gps_tm->vel_down = mavlink_msg_gps_tm_get_vel_down(msg);
- gps_tm->vel_mag = mavlink_msg_gps_tm_get_vel_mag(msg);
- gps_tm->n_satellites = mavlink_msg_gps_tm_get_n_satellites(msg);
- gps_tm->fix = mavlink_msg_gps_tm_get_fix(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_TM_LEN? msg->len : MAVLINK_MSG_ID_GPS_TM_LEN;
- memset(gps_tm, 0, MAVLINK_MSG_ID_GPS_TM_LEN);
- memcpy(gps_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_hr_tm.h b/mavlink_lib/hermes/mavlink_msg_hr_tm.h
deleted file mode 100644
index 2c0e82ee798efac6ada2cb5edb2832d556d1e047..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_hr_tm.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE HR_TM PACKING
-
-#define MAVLINK_MSG_ID_HR_TM 180
-
-MAVPACKED(
-typedef struct __mavlink_hr_tm_t {
- uint8_t payload[104]; /*< Payload of the packet. Payload contains various bit-packet data*/
-}) mavlink_hr_tm_t;
-
-#define MAVLINK_MSG_ID_HR_TM_LEN 104
-#define MAVLINK_MSG_ID_HR_TM_MIN_LEN 104
-#define MAVLINK_MSG_ID_180_LEN 104
-#define MAVLINK_MSG_ID_180_MIN_LEN 104
-
-#define MAVLINK_MSG_ID_HR_TM_CRC 142
-#define MAVLINK_MSG_ID_180_CRC 142
-
-#define MAVLINK_MSG_HR_TM_FIELD_PAYLOAD_LEN 104
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_HR_TM { \
- 180, \
- "HR_TM", \
- 1, \
- { { "payload", NULL, MAVLINK_TYPE_UINT8_T, 104, 0, offsetof(mavlink_hr_tm_t, payload) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_HR_TM { \
- "HR_TM", \
- 1, \
- { { "payload", NULL, MAVLINK_TYPE_UINT8_T, 104, 0, offsetof(mavlink_hr_tm_t, payload) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a hr_tm 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 payload Payload of the packet. Payload contains various bit-packet data
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_hr_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- const uint8_t *payload)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_HR_TM_LEN];
-
- _mav_put_uint8_t_array(buf, 0, payload, 104);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HR_TM_LEN);
-#else
- mavlink_hr_tm_t packet;
-
- mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*104);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HR_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_HR_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HR_TM_MIN_LEN, MAVLINK_MSG_ID_HR_TM_LEN, MAVLINK_MSG_ID_HR_TM_CRC);
-}
-
-/**
- * @brief Pack a hr_tm 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 payload Payload of the packet. Payload contains various bit-packet data
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_hr_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- const uint8_t *payload)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_HR_TM_LEN];
-
- _mav_put_uint8_t_array(buf, 0, payload, 104);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HR_TM_LEN);
-#else
- mavlink_hr_tm_t packet;
-
- mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*104);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HR_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_HR_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HR_TM_MIN_LEN, MAVLINK_MSG_ID_HR_TM_LEN, MAVLINK_MSG_ID_HR_TM_CRC);
-}
-
-/**
- * @brief Encode a hr_tm 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 hr_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_hr_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hr_tm_t* hr_tm)
-{
- return mavlink_msg_hr_tm_pack(system_id, component_id, msg, hr_tm->payload);
-}
-
-/**
- * @brief Encode a hr_tm 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 hr_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_hr_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hr_tm_t* hr_tm)
-{
- return mavlink_msg_hr_tm_pack_chan(system_id, component_id, chan, msg, hr_tm->payload);
-}
-
-/**
- * @brief Send a hr_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param payload Payload of the packet. Payload contains various bit-packet data
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_hr_tm_send(mavlink_channel_t chan, const uint8_t *payload)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_HR_TM_LEN];
-
- _mav_put_uint8_t_array(buf, 0, payload, 104);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HR_TM, buf, MAVLINK_MSG_ID_HR_TM_MIN_LEN, MAVLINK_MSG_ID_HR_TM_LEN, MAVLINK_MSG_ID_HR_TM_CRC);
-#else
- mavlink_hr_tm_t packet;
-
- mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*104);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HR_TM, (const char *)&packet, MAVLINK_MSG_ID_HR_TM_MIN_LEN, MAVLINK_MSG_ID_HR_TM_LEN, MAVLINK_MSG_ID_HR_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a hr_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_hr_tm_send_struct(mavlink_channel_t chan, const mavlink_hr_tm_t* hr_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_hr_tm_send(chan, hr_tm->payload);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HR_TM, (const char *)hr_tm, MAVLINK_MSG_ID_HR_TM_MIN_LEN, MAVLINK_MSG_ID_HR_TM_LEN, MAVLINK_MSG_ID_HR_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_HR_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_hr_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint8_t *payload)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
-
- _mav_put_uint8_t_array(buf, 0, payload, 104);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HR_TM, buf, MAVLINK_MSG_ID_HR_TM_MIN_LEN, MAVLINK_MSG_ID_HR_TM_LEN, MAVLINK_MSG_ID_HR_TM_CRC);
-#else
- mavlink_hr_tm_t *packet = (mavlink_hr_tm_t *)msgbuf;
-
- mav_array_memcpy(packet->payload, payload, sizeof(uint8_t)*104);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HR_TM, (const char *)packet, MAVLINK_MSG_ID_HR_TM_MIN_LEN, MAVLINK_MSG_ID_HR_TM_LEN, MAVLINK_MSG_ID_HR_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE HR_TM UNPACKING
-
-
-/**
- * @brief Get field payload from hr_tm message
- *
- * @return Payload of the packet. Payload contains various bit-packet data
- */
-static inline uint16_t mavlink_msg_hr_tm_get_payload(const mavlink_message_t* msg, uint8_t *payload)
-{
- return _MAV_RETURN_uint8_t_array(msg, payload, 104, 0);
-}
-
-/**
- * @brief Decode a hr_tm message into a struct
- *
- * @param msg The message to decode
- * @param hr_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_hr_tm_decode(const mavlink_message_t* msg, mavlink_hr_tm_t* hr_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_hr_tm_get_payload(msg, hr_tm->payload);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_HR_TM_LEN? msg->len : MAVLINK_MSG_ID_HR_TM_LEN;
- memset(hr_tm, 0, MAVLINK_MSG_ID_HR_TM_LEN);
- memcpy(hr_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_ign_tm.h b/mavlink_lib/hermes/mavlink_msg_ign_tm.h
deleted file mode 100644
index a9ae96c56c3b01f3d1d7ceabb1669ab9740612e5..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_ign_tm.h
+++ /dev/null
@@ -1,388 +0,0 @@
-#pragma once
-// MESSAGE IGN_TM PACKING
-
-#define MAVLINK_MSG_ID_IGN_TM 165
-
-MAVPACKED(
-typedef struct __mavlink_ign_tm_t {
- uint64_t timestamp; /*< When was this logged*/
- uint16_t n_sent_messages; /*< Number of sent messages on the Canbus*/
- uint16_t n_rcv_message; /*< Number of messages received over the Canbus*/
- uint8_t fsm_state; /*< State of the Controller's FSM*/
- uint8_t last_event; /*< Last event received*/
- uint8_t cmd_bitfield; /*< (LSB)launch_sent, abort_sent, abort_rcv(MSB)*/
- uint8_t stm32_bitfield; /*< STM32 micro status bitfield*/
- uint8_t avr_bitfield; /*< AVR micro status bitfield*/
-}) mavlink_ign_tm_t;
-
-#define MAVLINK_MSG_ID_IGN_TM_LEN 17
-#define MAVLINK_MSG_ID_IGN_TM_MIN_LEN 17
-#define MAVLINK_MSG_ID_165_LEN 17
-#define MAVLINK_MSG_ID_165_MIN_LEN 17
-
-#define MAVLINK_MSG_ID_IGN_TM_CRC 196
-#define MAVLINK_MSG_ID_165_CRC 196
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_IGN_TM { \
- 165, \
- "IGN_TM", \
- 8, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ign_tm_t, timestamp) }, \
- { "fsm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_ign_tm_t, fsm_state) }, \
- { "last_event", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_ign_tm_t, last_event) }, \
- { "n_sent_messages", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_ign_tm_t, n_sent_messages) }, \
- { "n_rcv_message", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_ign_tm_t, n_rcv_message) }, \
- { "cmd_bitfield", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_ign_tm_t, cmd_bitfield) }, \
- { "stm32_bitfield", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_ign_tm_t, stm32_bitfield) }, \
- { "avr_bitfield", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_ign_tm_t, avr_bitfield) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_IGN_TM { \
- "IGN_TM", \
- 8, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ign_tm_t, timestamp) }, \
- { "fsm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_ign_tm_t, fsm_state) }, \
- { "last_event", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_ign_tm_t, last_event) }, \
- { "n_sent_messages", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_ign_tm_t, n_sent_messages) }, \
- { "n_rcv_message", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_ign_tm_t, n_rcv_message) }, \
- { "cmd_bitfield", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_ign_tm_t, cmd_bitfield) }, \
- { "stm32_bitfield", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_ign_tm_t, stm32_bitfield) }, \
- { "avr_bitfield", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_ign_tm_t, avr_bitfield) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ign_tm 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 When was this logged
- * @param fsm_state State of the Controller's FSM
- * @param last_event Last event received
- * @param n_sent_messages Number of sent messages on the Canbus
- * @param n_rcv_message Number of messages received over the Canbus
- * @param cmd_bitfield (LSB)launch_sent, abort_sent, abort_rcv(MSB)
- * @param stm32_bitfield STM32 micro status bitfield
- * @param avr_bitfield AVR micro status bitfield
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ign_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t fsm_state, uint8_t last_event, uint16_t n_sent_messages, uint16_t n_rcv_message, uint8_t cmd_bitfield, uint8_t stm32_bitfield, uint8_t avr_bitfield)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_IGN_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint16_t(buf, 8, n_sent_messages);
- _mav_put_uint16_t(buf, 10, n_rcv_message);
- _mav_put_uint8_t(buf, 12, fsm_state);
- _mav_put_uint8_t(buf, 13, last_event);
- _mav_put_uint8_t(buf, 14, cmd_bitfield);
- _mav_put_uint8_t(buf, 15, stm32_bitfield);
- _mav_put_uint8_t(buf, 16, avr_bitfield);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IGN_TM_LEN);
-#else
- mavlink_ign_tm_t packet;
- packet.timestamp = timestamp;
- packet.n_sent_messages = n_sent_messages;
- packet.n_rcv_message = n_rcv_message;
- packet.fsm_state = fsm_state;
- packet.last_event = last_event;
- packet.cmd_bitfield = cmd_bitfield;
- packet.stm32_bitfield = stm32_bitfield;
- packet.avr_bitfield = avr_bitfield;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IGN_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_IGN_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_IGN_TM_MIN_LEN, MAVLINK_MSG_ID_IGN_TM_LEN, MAVLINK_MSG_ID_IGN_TM_CRC);
-}
-
-/**
- * @brief Pack a ign_tm 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 When was this logged
- * @param fsm_state State of the Controller's FSM
- * @param last_event Last event received
- * @param n_sent_messages Number of sent messages on the Canbus
- * @param n_rcv_message Number of messages received over the Canbus
- * @param cmd_bitfield (LSB)launch_sent, abort_sent, abort_rcv(MSB)
- * @param stm32_bitfield STM32 micro status bitfield
- * @param avr_bitfield AVR micro status bitfield
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ign_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t fsm_state,uint8_t last_event,uint16_t n_sent_messages,uint16_t n_rcv_message,uint8_t cmd_bitfield,uint8_t stm32_bitfield,uint8_t avr_bitfield)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_IGN_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint16_t(buf, 8, n_sent_messages);
- _mav_put_uint16_t(buf, 10, n_rcv_message);
- _mav_put_uint8_t(buf, 12, fsm_state);
- _mav_put_uint8_t(buf, 13, last_event);
- _mav_put_uint8_t(buf, 14, cmd_bitfield);
- _mav_put_uint8_t(buf, 15, stm32_bitfield);
- _mav_put_uint8_t(buf, 16, avr_bitfield);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IGN_TM_LEN);
-#else
- mavlink_ign_tm_t packet;
- packet.timestamp = timestamp;
- packet.n_sent_messages = n_sent_messages;
- packet.n_rcv_message = n_rcv_message;
- packet.fsm_state = fsm_state;
- packet.last_event = last_event;
- packet.cmd_bitfield = cmd_bitfield;
- packet.stm32_bitfield = stm32_bitfield;
- packet.avr_bitfield = avr_bitfield;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IGN_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_IGN_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_IGN_TM_MIN_LEN, MAVLINK_MSG_ID_IGN_TM_LEN, MAVLINK_MSG_ID_IGN_TM_CRC);
-}
-
-/**
- * @brief Encode a ign_tm 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 ign_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ign_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ign_tm_t* ign_tm)
-{
- return mavlink_msg_ign_tm_pack(system_id, component_id, msg, ign_tm->timestamp, ign_tm->fsm_state, ign_tm->last_event, ign_tm->n_sent_messages, ign_tm->n_rcv_message, ign_tm->cmd_bitfield, ign_tm->stm32_bitfield, ign_tm->avr_bitfield);
-}
-
-/**
- * @brief Encode a ign_tm 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 ign_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ign_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ign_tm_t* ign_tm)
-{
- return mavlink_msg_ign_tm_pack_chan(system_id, component_id, chan, msg, ign_tm->timestamp, ign_tm->fsm_state, ign_tm->last_event, ign_tm->n_sent_messages, ign_tm->n_rcv_message, ign_tm->cmd_bitfield, ign_tm->stm32_bitfield, ign_tm->avr_bitfield);
-}
-
-/**
- * @brief Send a ign_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp When was this logged
- * @param fsm_state State of the Controller's FSM
- * @param last_event Last event received
- * @param n_sent_messages Number of sent messages on the Canbus
- * @param n_rcv_message Number of messages received over the Canbus
- * @param cmd_bitfield (LSB)launch_sent, abort_sent, abort_rcv(MSB)
- * @param stm32_bitfield STM32 micro status bitfield
- * @param avr_bitfield AVR micro status bitfield
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ign_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t fsm_state, uint8_t last_event, uint16_t n_sent_messages, uint16_t n_rcv_message, uint8_t cmd_bitfield, uint8_t stm32_bitfield, uint8_t avr_bitfield)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_IGN_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint16_t(buf, 8, n_sent_messages);
- _mav_put_uint16_t(buf, 10, n_rcv_message);
- _mav_put_uint8_t(buf, 12, fsm_state);
- _mav_put_uint8_t(buf, 13, last_event);
- _mav_put_uint8_t(buf, 14, cmd_bitfield);
- _mav_put_uint8_t(buf, 15, stm32_bitfield);
- _mav_put_uint8_t(buf, 16, avr_bitfield);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IGN_TM, buf, MAVLINK_MSG_ID_IGN_TM_MIN_LEN, MAVLINK_MSG_ID_IGN_TM_LEN, MAVLINK_MSG_ID_IGN_TM_CRC);
-#else
- mavlink_ign_tm_t packet;
- packet.timestamp = timestamp;
- packet.n_sent_messages = n_sent_messages;
- packet.n_rcv_message = n_rcv_message;
- packet.fsm_state = fsm_state;
- packet.last_event = last_event;
- packet.cmd_bitfield = cmd_bitfield;
- packet.stm32_bitfield = stm32_bitfield;
- packet.avr_bitfield = avr_bitfield;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IGN_TM, (const char *)&packet, MAVLINK_MSG_ID_IGN_TM_MIN_LEN, MAVLINK_MSG_ID_IGN_TM_LEN, MAVLINK_MSG_ID_IGN_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a ign_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ign_tm_send_struct(mavlink_channel_t chan, const mavlink_ign_tm_t* ign_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ign_tm_send(chan, ign_tm->timestamp, ign_tm->fsm_state, ign_tm->last_event, ign_tm->n_sent_messages, ign_tm->n_rcv_message, ign_tm->cmd_bitfield, ign_tm->stm32_bitfield, ign_tm->avr_bitfield);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IGN_TM, (const char *)ign_tm, MAVLINK_MSG_ID_IGN_TM_MIN_LEN, MAVLINK_MSG_ID_IGN_TM_LEN, MAVLINK_MSG_ID_IGN_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_IGN_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_ign_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t fsm_state, uint8_t last_event, uint16_t n_sent_messages, uint16_t n_rcv_message, uint8_t cmd_bitfield, uint8_t stm32_bitfield, uint8_t avr_bitfield)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint16_t(buf, 8, n_sent_messages);
- _mav_put_uint16_t(buf, 10, n_rcv_message);
- _mav_put_uint8_t(buf, 12, fsm_state);
- _mav_put_uint8_t(buf, 13, last_event);
- _mav_put_uint8_t(buf, 14, cmd_bitfield);
- _mav_put_uint8_t(buf, 15, stm32_bitfield);
- _mav_put_uint8_t(buf, 16, avr_bitfield);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IGN_TM, buf, MAVLINK_MSG_ID_IGN_TM_MIN_LEN, MAVLINK_MSG_ID_IGN_TM_LEN, MAVLINK_MSG_ID_IGN_TM_CRC);
-#else
- mavlink_ign_tm_t *packet = (mavlink_ign_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->n_sent_messages = n_sent_messages;
- packet->n_rcv_message = n_rcv_message;
- packet->fsm_state = fsm_state;
- packet->last_event = last_event;
- packet->cmd_bitfield = cmd_bitfield;
- packet->stm32_bitfield = stm32_bitfield;
- packet->avr_bitfield = avr_bitfield;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IGN_TM, (const char *)packet, MAVLINK_MSG_ID_IGN_TM_MIN_LEN, MAVLINK_MSG_ID_IGN_TM_LEN, MAVLINK_MSG_ID_IGN_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE IGN_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from ign_tm message
- *
- * @return When was this logged
- */
-static inline uint64_t mavlink_msg_ign_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field fsm_state from ign_tm message
- *
- * @return State of the Controller's FSM
- */
-static inline uint8_t mavlink_msg_ign_tm_get_fsm_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 12);
-}
-
-/**
- * @brief Get field last_event from ign_tm message
- *
- * @return Last event received
- */
-static inline uint8_t mavlink_msg_ign_tm_get_last_event(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 13);
-}
-
-/**
- * @brief Get field n_sent_messages from ign_tm message
- *
- * @return Number of sent messages on the Canbus
- */
-static inline uint16_t mavlink_msg_ign_tm_get_n_sent_messages(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 8);
-}
-
-/**
- * @brief Get field n_rcv_message from ign_tm message
- *
- * @return Number of messages received over the Canbus
- */
-static inline uint16_t mavlink_msg_ign_tm_get_n_rcv_message(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 10);
-}
-
-/**
- * @brief Get field cmd_bitfield from ign_tm message
- *
- * @return (LSB)launch_sent, abort_sent, abort_rcv(MSB)
- */
-static inline uint8_t mavlink_msg_ign_tm_get_cmd_bitfield(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 14);
-}
-
-/**
- * @brief Get field stm32_bitfield from ign_tm message
- *
- * @return STM32 micro status bitfield
- */
-static inline uint8_t mavlink_msg_ign_tm_get_stm32_bitfield(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 15);
-}
-
-/**
- * @brief Get field avr_bitfield from ign_tm message
- *
- * @return AVR micro status bitfield
- */
-static inline uint8_t mavlink_msg_ign_tm_get_avr_bitfield(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 16);
-}
-
-/**
- * @brief Decode a ign_tm message into a struct
- *
- * @param msg The message to decode
- * @param ign_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ign_tm_decode(const mavlink_message_t* msg, mavlink_ign_tm_t* ign_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ign_tm->timestamp = mavlink_msg_ign_tm_get_timestamp(msg);
- ign_tm->n_sent_messages = mavlink_msg_ign_tm_get_n_sent_messages(msg);
- ign_tm->n_rcv_message = mavlink_msg_ign_tm_get_n_rcv_message(msg);
- ign_tm->fsm_state = mavlink_msg_ign_tm_get_fsm_state(msg);
- ign_tm->last_event = mavlink_msg_ign_tm_get_last_event(msg);
- ign_tm->cmd_bitfield = mavlink_msg_ign_tm_get_cmd_bitfield(msg);
- ign_tm->stm32_bitfield = mavlink_msg_ign_tm_get_stm32_bitfield(msg);
- ign_tm->avr_bitfield = mavlink_msg_ign_tm_get_avr_bitfield(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_IGN_TM_LEN? msg->len : MAVLINK_MSG_ID_IGN_TM_LEN;
- memset(ign_tm, 0, MAVLINK_MSG_ID_IGN_TM_LEN);
- memcpy(ign_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_logger_tm.h b/mavlink_lib/hermes/mavlink_msg_logger_tm.h
deleted file mode 100644
index e9f438a135778d92e874c53f9e34885e82027bd6..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_logger_tm.h
+++ /dev/null
@@ -1,463 +0,0 @@
-#pragma once
-// MESSAGE LOGGER_TM PACKING
-
-#define MAVLINK_MSG_ID_LOGGER_TM 162
-
-MAVPACKED(
-typedef struct __mavlink_logger_tm_t {
- uint64_t timestamp; /*< Timestamp*/
- int32_t statTooLargeSamples; /*< Number of dropped samples because too large*/
- int32_t statDroppedSamples; /*< Number of dropped samples due to fifo full*/
- int32_t statQueuedSamples; /*< Number of samples written to buffer*/
- int32_t statBufferFilled; /*< Number of buffers filled*/
- int32_t statBufferWritten; /*< Number of buffers written to disk*/
- int32_t statWriteFailed; /*< Number of fwrite() that failed*/
- int32_t statWriteError; /*< Error of the last fwrite() that failed*/
- int32_t statWriteTime; /*< Time to perform an fwrite() of a buffer*/
- int32_t statMaxWriteTime; /*< Max time to perform an fwrite() of a buffer*/
- uint16_t statLogNumber; /*< Currently active log file*/
-}) mavlink_logger_tm_t;
-
-#define MAVLINK_MSG_ID_LOGGER_TM_LEN 46
-#define MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN 46
-#define MAVLINK_MSG_ID_162_LEN 46
-#define MAVLINK_MSG_ID_162_MIN_LEN 46
-
-#define MAVLINK_MSG_ID_LOGGER_TM_CRC 163
-#define MAVLINK_MSG_ID_162_CRC 163
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_LOGGER_TM { \
- 162, \
- "LOGGER_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_logger_tm_t, timestamp) }, \
- { "statLogNumber", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_logger_tm_t, statLogNumber) }, \
- { "statTooLargeSamples", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_logger_tm_t, statTooLargeSamples) }, \
- { "statDroppedSamples", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_logger_tm_t, statDroppedSamples) }, \
- { "statQueuedSamples", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_logger_tm_t, statQueuedSamples) }, \
- { "statBufferFilled", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_logger_tm_t, statBufferFilled) }, \
- { "statBufferWritten", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_logger_tm_t, statBufferWritten) }, \
- { "statWriteFailed", NULL, MAVLINK_TYPE_INT32_T, 0, 28, offsetof(mavlink_logger_tm_t, statWriteFailed) }, \
- { "statWriteError", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_logger_tm_t, statWriteError) }, \
- { "statWriteTime", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_logger_tm_t, statWriteTime) }, \
- { "statMaxWriteTime", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_logger_tm_t, statMaxWriteTime) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_LOGGER_TM { \
- "LOGGER_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_logger_tm_t, timestamp) }, \
- { "statLogNumber", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_logger_tm_t, statLogNumber) }, \
- { "statTooLargeSamples", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_logger_tm_t, statTooLargeSamples) }, \
- { "statDroppedSamples", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_logger_tm_t, statDroppedSamples) }, \
- { "statQueuedSamples", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_logger_tm_t, statQueuedSamples) }, \
- { "statBufferFilled", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_logger_tm_t, statBufferFilled) }, \
- { "statBufferWritten", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_logger_tm_t, statBufferWritten) }, \
- { "statWriteFailed", NULL, MAVLINK_TYPE_INT32_T, 0, 28, offsetof(mavlink_logger_tm_t, statWriteFailed) }, \
- { "statWriteError", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_logger_tm_t, statWriteError) }, \
- { "statWriteTime", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_logger_tm_t, statWriteTime) }, \
- { "statMaxWriteTime", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_logger_tm_t, statMaxWriteTime) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a logger_tm 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 Timestamp
- * @param statLogNumber Currently active log file
- * @param statTooLargeSamples Number of dropped samples because too large
- * @param statDroppedSamples Number of dropped samples due to fifo full
- * @param statQueuedSamples Number of samples written to buffer
- * @param statBufferFilled Number of buffers filled
- * @param statBufferWritten Number of buffers written to disk
- * @param statWriteFailed Number of fwrite() that failed
- * @param statWriteError Error of the last fwrite() that failed
- * @param statWriteTime Time to perform an fwrite() of a buffer
- * @param statMaxWriteTime Max time to perform an fwrite() of a buffer
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_logger_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint16_t statLogNumber, int32_t statTooLargeSamples, int32_t statDroppedSamples, int32_t statQueuedSamples, int32_t statBufferFilled, int32_t statBufferWritten, int32_t statWriteFailed, int32_t statWriteError, int32_t statWriteTime, int32_t statMaxWriteTime)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOGGER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 8, statTooLargeSamples);
- _mav_put_int32_t(buf, 12, statDroppedSamples);
- _mav_put_int32_t(buf, 16, statQueuedSamples);
- _mav_put_int32_t(buf, 20, statBufferFilled);
- _mav_put_int32_t(buf, 24, statBufferWritten);
- _mav_put_int32_t(buf, 28, statWriteFailed);
- _mav_put_int32_t(buf, 32, statWriteError);
- _mav_put_int32_t(buf, 36, statWriteTime);
- _mav_put_int32_t(buf, 40, statMaxWriteTime);
- _mav_put_uint16_t(buf, 44, statLogNumber);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGER_TM_LEN);
-#else
- mavlink_logger_tm_t packet;
- packet.timestamp = timestamp;
- packet.statTooLargeSamples = statTooLargeSamples;
- packet.statDroppedSamples = statDroppedSamples;
- packet.statQueuedSamples = statQueuedSamples;
- packet.statBufferFilled = statBufferFilled;
- packet.statBufferWritten = statBufferWritten;
- packet.statWriteFailed = statWriteFailed;
- packet.statWriteError = statWriteError;
- packet.statWriteTime = statWriteTime;
- packet.statMaxWriteTime = statMaxWriteTime;
- packet.statLogNumber = statLogNumber;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGER_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LOGGER_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-}
-
-/**
- * @brief Pack a logger_tm 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 Timestamp
- * @param statLogNumber Currently active log file
- * @param statTooLargeSamples Number of dropped samples because too large
- * @param statDroppedSamples Number of dropped samples due to fifo full
- * @param statQueuedSamples Number of samples written to buffer
- * @param statBufferFilled Number of buffers filled
- * @param statBufferWritten Number of buffers written to disk
- * @param statWriteFailed Number of fwrite() that failed
- * @param statWriteError Error of the last fwrite() that failed
- * @param statWriteTime Time to perform an fwrite() of a buffer
- * @param statMaxWriteTime Max time to perform an fwrite() of a buffer
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_logger_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint16_t statLogNumber,int32_t statTooLargeSamples,int32_t statDroppedSamples,int32_t statQueuedSamples,int32_t statBufferFilled,int32_t statBufferWritten,int32_t statWriteFailed,int32_t statWriteError,int32_t statWriteTime,int32_t statMaxWriteTime)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOGGER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 8, statTooLargeSamples);
- _mav_put_int32_t(buf, 12, statDroppedSamples);
- _mav_put_int32_t(buf, 16, statQueuedSamples);
- _mav_put_int32_t(buf, 20, statBufferFilled);
- _mav_put_int32_t(buf, 24, statBufferWritten);
- _mav_put_int32_t(buf, 28, statWriteFailed);
- _mav_put_int32_t(buf, 32, statWriteError);
- _mav_put_int32_t(buf, 36, statWriteTime);
- _mav_put_int32_t(buf, 40, statMaxWriteTime);
- _mav_put_uint16_t(buf, 44, statLogNumber);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGER_TM_LEN);
-#else
- mavlink_logger_tm_t packet;
- packet.timestamp = timestamp;
- packet.statTooLargeSamples = statTooLargeSamples;
- packet.statDroppedSamples = statDroppedSamples;
- packet.statQueuedSamples = statQueuedSamples;
- packet.statBufferFilled = statBufferFilled;
- packet.statBufferWritten = statBufferWritten;
- packet.statWriteFailed = statWriteFailed;
- packet.statWriteError = statWriteError;
- packet.statWriteTime = statWriteTime;
- packet.statMaxWriteTime = statMaxWriteTime;
- packet.statLogNumber = statLogNumber;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGER_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LOGGER_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-}
-
-/**
- * @brief Encode a logger_tm 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 logger_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_logger_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_logger_tm_t* logger_tm)
-{
- return mavlink_msg_logger_tm_pack(system_id, component_id, msg, logger_tm->timestamp, logger_tm->statLogNumber, logger_tm->statTooLargeSamples, logger_tm->statDroppedSamples, logger_tm->statQueuedSamples, logger_tm->statBufferFilled, logger_tm->statBufferWritten, logger_tm->statWriteFailed, logger_tm->statWriteError, logger_tm->statWriteTime, logger_tm->statMaxWriteTime);
-}
-
-/**
- * @brief Encode a logger_tm 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 logger_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_logger_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_logger_tm_t* logger_tm)
-{
- return mavlink_msg_logger_tm_pack_chan(system_id, component_id, chan, msg, logger_tm->timestamp, logger_tm->statLogNumber, logger_tm->statTooLargeSamples, logger_tm->statDroppedSamples, logger_tm->statQueuedSamples, logger_tm->statBufferFilled, logger_tm->statBufferWritten, logger_tm->statWriteFailed, logger_tm->statWriteError, logger_tm->statWriteTime, logger_tm->statMaxWriteTime);
-}
-
-/**
- * @brief Send a logger_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp Timestamp
- * @param statLogNumber Currently active log file
- * @param statTooLargeSamples Number of dropped samples because too large
- * @param statDroppedSamples Number of dropped samples due to fifo full
- * @param statQueuedSamples Number of samples written to buffer
- * @param statBufferFilled Number of buffers filled
- * @param statBufferWritten Number of buffers written to disk
- * @param statWriteFailed Number of fwrite() that failed
- * @param statWriteError Error of the last fwrite() that failed
- * @param statWriteTime Time to perform an fwrite() of a buffer
- * @param statMaxWriteTime Max time to perform an fwrite() of a buffer
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_logger_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint16_t statLogNumber, int32_t statTooLargeSamples, int32_t statDroppedSamples, int32_t statQueuedSamples, int32_t statBufferFilled, int32_t statBufferWritten, int32_t statWriteFailed, int32_t statWriteError, int32_t statWriteTime, int32_t statMaxWriteTime)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOGGER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 8, statTooLargeSamples);
- _mav_put_int32_t(buf, 12, statDroppedSamples);
- _mav_put_int32_t(buf, 16, statQueuedSamples);
- _mav_put_int32_t(buf, 20, statBufferFilled);
- _mav_put_int32_t(buf, 24, statBufferWritten);
- _mav_put_int32_t(buf, 28, statWriteFailed);
- _mav_put_int32_t(buf, 32, statWriteError);
- _mav_put_int32_t(buf, 36, statWriteTime);
- _mav_put_int32_t(buf, 40, statMaxWriteTime);
- _mav_put_uint16_t(buf, 44, statLogNumber);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, buf, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#else
- mavlink_logger_tm_t packet;
- packet.timestamp = timestamp;
- packet.statTooLargeSamples = statTooLargeSamples;
- packet.statDroppedSamples = statDroppedSamples;
- packet.statQueuedSamples = statQueuedSamples;
- packet.statBufferFilled = statBufferFilled;
- packet.statBufferWritten = statBufferWritten;
- packet.statWriteFailed = statWriteFailed;
- packet.statWriteError = statWriteError;
- packet.statWriteTime = statWriteTime;
- packet.statMaxWriteTime = statMaxWriteTime;
- packet.statLogNumber = statLogNumber;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, (const char *)&packet, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a logger_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_logger_tm_send_struct(mavlink_channel_t chan, const mavlink_logger_tm_t* logger_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_logger_tm_send(chan, logger_tm->timestamp, logger_tm->statLogNumber, logger_tm->statTooLargeSamples, logger_tm->statDroppedSamples, logger_tm->statQueuedSamples, logger_tm->statBufferFilled, logger_tm->statBufferWritten, logger_tm->statWriteFailed, logger_tm->statWriteError, logger_tm->statWriteTime, logger_tm->statMaxWriteTime);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, (const char *)logger_tm, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_LOGGER_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_logger_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint16_t statLogNumber, int32_t statTooLargeSamples, int32_t statDroppedSamples, int32_t statQueuedSamples, int32_t statBufferFilled, int32_t statBufferWritten, int32_t statWriteFailed, int32_t statWriteError, int32_t statWriteTime, int32_t statMaxWriteTime)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 8, statTooLargeSamples);
- _mav_put_int32_t(buf, 12, statDroppedSamples);
- _mav_put_int32_t(buf, 16, statQueuedSamples);
- _mav_put_int32_t(buf, 20, statBufferFilled);
- _mav_put_int32_t(buf, 24, statBufferWritten);
- _mav_put_int32_t(buf, 28, statWriteFailed);
- _mav_put_int32_t(buf, 32, statWriteError);
- _mav_put_int32_t(buf, 36, statWriteTime);
- _mav_put_int32_t(buf, 40, statMaxWriteTime);
- _mav_put_uint16_t(buf, 44, statLogNumber);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, buf, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#else
- mavlink_logger_tm_t *packet = (mavlink_logger_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->statTooLargeSamples = statTooLargeSamples;
- packet->statDroppedSamples = statDroppedSamples;
- packet->statQueuedSamples = statQueuedSamples;
- packet->statBufferFilled = statBufferFilled;
- packet->statBufferWritten = statBufferWritten;
- packet->statWriteFailed = statWriteFailed;
- packet->statWriteError = statWriteError;
- packet->statWriteTime = statWriteTime;
- packet->statMaxWriteTime = statMaxWriteTime;
- packet->statLogNumber = statLogNumber;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, (const char *)packet, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE LOGGER_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from logger_tm message
- *
- * @return Timestamp
- */
-static inline uint64_t mavlink_msg_logger_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field statLogNumber from logger_tm message
- *
- * @return Currently active log file
- */
-static inline uint16_t mavlink_msg_logger_tm_get_statLogNumber(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 44);
-}
-
-/**
- * @brief Get field statTooLargeSamples from logger_tm message
- *
- * @return Number of dropped samples because too large
- */
-static inline int32_t mavlink_msg_logger_tm_get_statTooLargeSamples(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 8);
-}
-
-/**
- * @brief Get field statDroppedSamples from logger_tm message
- *
- * @return Number of dropped samples due to fifo full
- */
-static inline int32_t mavlink_msg_logger_tm_get_statDroppedSamples(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 12);
-}
-
-/**
- * @brief Get field statQueuedSamples from logger_tm message
- *
- * @return Number of samples written to buffer
- */
-static inline int32_t mavlink_msg_logger_tm_get_statQueuedSamples(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 16);
-}
-
-/**
- * @brief Get field statBufferFilled from logger_tm message
- *
- * @return Number of buffers filled
- */
-static inline int32_t mavlink_msg_logger_tm_get_statBufferFilled(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 20);
-}
-
-/**
- * @brief Get field statBufferWritten from logger_tm message
- *
- * @return Number of buffers written to disk
- */
-static inline int32_t mavlink_msg_logger_tm_get_statBufferWritten(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 24);
-}
-
-/**
- * @brief Get field statWriteFailed from logger_tm message
- *
- * @return Number of fwrite() that failed
- */
-static inline int32_t mavlink_msg_logger_tm_get_statWriteFailed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 28);
-}
-
-/**
- * @brief Get field statWriteError from logger_tm message
- *
- * @return Error of the last fwrite() that failed
- */
-static inline int32_t mavlink_msg_logger_tm_get_statWriteError(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 32);
-}
-
-/**
- * @brief Get field statWriteTime from logger_tm message
- *
- * @return Time to perform an fwrite() of a buffer
- */
-static inline int32_t mavlink_msg_logger_tm_get_statWriteTime(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 36);
-}
-
-/**
- * @brief Get field statMaxWriteTime from logger_tm message
- *
- * @return Max time to perform an fwrite() of a buffer
- */
-static inline int32_t mavlink_msg_logger_tm_get_statMaxWriteTime(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 40);
-}
-
-/**
- * @brief Decode a logger_tm message into a struct
- *
- * @param msg The message to decode
- * @param logger_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_logger_tm_decode(const mavlink_message_t* msg, mavlink_logger_tm_t* logger_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- logger_tm->timestamp = mavlink_msg_logger_tm_get_timestamp(msg);
- logger_tm->statTooLargeSamples = mavlink_msg_logger_tm_get_statTooLargeSamples(msg);
- logger_tm->statDroppedSamples = mavlink_msg_logger_tm_get_statDroppedSamples(msg);
- logger_tm->statQueuedSamples = mavlink_msg_logger_tm_get_statQueuedSamples(msg);
- logger_tm->statBufferFilled = mavlink_msg_logger_tm_get_statBufferFilled(msg);
- logger_tm->statBufferWritten = mavlink_msg_logger_tm_get_statBufferWritten(msg);
- logger_tm->statWriteFailed = mavlink_msg_logger_tm_get_statWriteFailed(msg);
- logger_tm->statWriteError = mavlink_msg_logger_tm_get_statWriteError(msg);
- logger_tm->statWriteTime = mavlink_msg_logger_tm_get_statWriteTime(msg);
- logger_tm->statMaxWriteTime = mavlink_msg_logger_tm_get_statMaxWriteTime(msg);
- logger_tm->statLogNumber = mavlink_msg_logger_tm_get_statLogNumber(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_LOGGER_TM_LEN? msg->len : MAVLINK_MSG_ID_LOGGER_TM_LEN;
- memset(logger_tm, 0, MAVLINK_MSG_ID_LOGGER_TM_LEN);
- memcpy(logger_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_lr_tm.h b/mavlink_lib/hermes/mavlink_msg_lr_tm.h
deleted file mode 100644
index 18b1887cdc13c142e12d10baa6d5e935a95aec10..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_lr_tm.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE LR_TM PACKING
-
-#define MAVLINK_MSG_ID_LR_TM 181
-
-MAVPACKED(
-typedef struct __mavlink_lr_tm_t {
- uint8_t payload[40]; /*< Payload of the packet. Payload contains various bit-packet data*/
-}) mavlink_lr_tm_t;
-
-#define MAVLINK_MSG_ID_LR_TM_LEN 40
-#define MAVLINK_MSG_ID_LR_TM_MIN_LEN 40
-#define MAVLINK_MSG_ID_181_LEN 40
-#define MAVLINK_MSG_ID_181_MIN_LEN 40
-
-#define MAVLINK_MSG_ID_LR_TM_CRC 249
-#define MAVLINK_MSG_ID_181_CRC 249
-
-#define MAVLINK_MSG_LR_TM_FIELD_PAYLOAD_LEN 40
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_LR_TM { \
- 181, \
- "LR_TM", \
- 1, \
- { { "payload", NULL, MAVLINK_TYPE_UINT8_T, 40, 0, offsetof(mavlink_lr_tm_t, payload) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_LR_TM { \
- "LR_TM", \
- 1, \
- { { "payload", NULL, MAVLINK_TYPE_UINT8_T, 40, 0, offsetof(mavlink_lr_tm_t, payload) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a lr_tm 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 payload Payload of the packet. Payload contains various bit-packet data
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_lr_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- const uint8_t *payload)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LR_TM_LEN];
-
- _mav_put_uint8_t_array(buf, 0, payload, 40);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LR_TM_LEN);
-#else
- mavlink_lr_tm_t packet;
-
- mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*40);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LR_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LR_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LR_TM_MIN_LEN, MAVLINK_MSG_ID_LR_TM_LEN, MAVLINK_MSG_ID_LR_TM_CRC);
-}
-
-/**
- * @brief Pack a lr_tm 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 payload Payload of the packet. Payload contains various bit-packet data
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_lr_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- const uint8_t *payload)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LR_TM_LEN];
-
- _mav_put_uint8_t_array(buf, 0, payload, 40);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LR_TM_LEN);
-#else
- mavlink_lr_tm_t packet;
-
- mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*40);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LR_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LR_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LR_TM_MIN_LEN, MAVLINK_MSG_ID_LR_TM_LEN, MAVLINK_MSG_ID_LR_TM_CRC);
-}
-
-/**
- * @brief Encode a lr_tm 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 lr_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_lr_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_lr_tm_t* lr_tm)
-{
- return mavlink_msg_lr_tm_pack(system_id, component_id, msg, lr_tm->payload);
-}
-
-/**
- * @brief Encode a lr_tm 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 lr_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_lr_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_lr_tm_t* lr_tm)
-{
- return mavlink_msg_lr_tm_pack_chan(system_id, component_id, chan, msg, lr_tm->payload);
-}
-
-/**
- * @brief Send a lr_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param payload Payload of the packet. Payload contains various bit-packet data
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_lr_tm_send(mavlink_channel_t chan, const uint8_t *payload)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LR_TM_LEN];
-
- _mav_put_uint8_t_array(buf, 0, payload, 40);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LR_TM, buf, MAVLINK_MSG_ID_LR_TM_MIN_LEN, MAVLINK_MSG_ID_LR_TM_LEN, MAVLINK_MSG_ID_LR_TM_CRC);
-#else
- mavlink_lr_tm_t packet;
-
- mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*40);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LR_TM, (const char *)&packet, MAVLINK_MSG_ID_LR_TM_MIN_LEN, MAVLINK_MSG_ID_LR_TM_LEN, MAVLINK_MSG_ID_LR_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a lr_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_lr_tm_send_struct(mavlink_channel_t chan, const mavlink_lr_tm_t* lr_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_lr_tm_send(chan, lr_tm->payload);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LR_TM, (const char *)lr_tm, MAVLINK_MSG_ID_LR_TM_MIN_LEN, MAVLINK_MSG_ID_LR_TM_LEN, MAVLINK_MSG_ID_LR_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_LR_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_lr_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint8_t *payload)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
-
- _mav_put_uint8_t_array(buf, 0, payload, 40);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LR_TM, buf, MAVLINK_MSG_ID_LR_TM_MIN_LEN, MAVLINK_MSG_ID_LR_TM_LEN, MAVLINK_MSG_ID_LR_TM_CRC);
-#else
- mavlink_lr_tm_t *packet = (mavlink_lr_tm_t *)msgbuf;
-
- mav_array_memcpy(packet->payload, payload, sizeof(uint8_t)*40);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LR_TM, (const char *)packet, MAVLINK_MSG_ID_LR_TM_MIN_LEN, MAVLINK_MSG_ID_LR_TM_LEN, MAVLINK_MSG_ID_LR_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE LR_TM UNPACKING
-
-
-/**
- * @brief Get field payload from lr_tm message
- *
- * @return Payload of the packet. Payload contains various bit-packet data
- */
-static inline uint16_t mavlink_msg_lr_tm_get_payload(const mavlink_message_t* msg, uint8_t *payload)
-{
- return _MAV_RETURN_uint8_t_array(msg, payload, 40, 0);
-}
-
-/**
- * @brief Decode a lr_tm message into a struct
- *
- * @param msg The message to decode
- * @param lr_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_lr_tm_decode(const mavlink_message_t* msg, mavlink_lr_tm_t* lr_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_lr_tm_get_payload(msg, lr_tm->payload);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_LR_TM_LEN? msg->len : MAVLINK_MSG_ID_LR_TM_LEN;
- memset(lr_tm, 0, MAVLINK_MSG_ID_LR_TM_LEN);
- memcpy(lr_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_mpu_tm.h b/mavlink_lib/hermes/mavlink_msg_mpu_tm.h
deleted file mode 100644
index 3f78b64b9cfb820ebee6f4552ee2efea836e8b34..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_mpu_tm.h
+++ /dev/null
@@ -1,463 +0,0 @@
-#pragma once
-// MESSAGE MPU_TM PACKING
-
-#define MAVLINK_MSG_ID_MPU_TM 171
-
-MAVPACKED(
-typedef struct __mavlink_mpu_tm_t {
- uint64_t timestamp; /*< When was this logged*/
- float acc_x; /*< X axis acceleration*/
- float acc_y; /*< Y axis acceleration*/
- float acc_z; /*< Z axis acceleration*/
- float gyro_x; /*< X axis gyro*/
- float gyro_y; /*< Y axis gyro*/
- float gyro_z; /*< Z axis gyro*/
- float compass_x; /*< X axis compass*/
- float compass_y; /*< Y axis compass*/
- float compass_z; /*< Z axis compass*/
- float temp; /*< Temperature*/
-}) mavlink_mpu_tm_t;
-
-#define MAVLINK_MSG_ID_MPU_TM_LEN 48
-#define MAVLINK_MSG_ID_MPU_TM_MIN_LEN 48
-#define MAVLINK_MSG_ID_171_LEN 48
-#define MAVLINK_MSG_ID_171_MIN_LEN 48
-
-#define MAVLINK_MSG_ID_MPU_TM_CRC 57
-#define MAVLINK_MSG_ID_171_CRC 57
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_MPU_TM { \
- 171, \
- "MPU_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_mpu_tm_t, timestamp) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mpu_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mpu_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mpu_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mpu_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mpu_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_mpu_tm_t, gyro_z) }, \
- { "compass_x", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_mpu_tm_t, compass_x) }, \
- { "compass_y", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_mpu_tm_t, compass_y) }, \
- { "compass_z", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_mpu_tm_t, compass_z) }, \
- { "temp", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_mpu_tm_t, temp) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_MPU_TM { \
- "MPU_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_mpu_tm_t, timestamp) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mpu_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mpu_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mpu_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mpu_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mpu_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_mpu_tm_t, gyro_z) }, \
- { "compass_x", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_mpu_tm_t, compass_x) }, \
- { "compass_y", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_mpu_tm_t, compass_y) }, \
- { "compass_z", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_mpu_tm_t, compass_z) }, \
- { "temp", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_mpu_tm_t, temp) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a mpu_tm 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 When was this logged
- * @param acc_x X axis acceleration
- * @param acc_y Y axis acceleration
- * @param acc_z Z axis acceleration
- * @param gyro_x X axis gyro
- * @param gyro_y Y axis gyro
- * @param gyro_z Z axis gyro
- * @param compass_x X axis compass
- * @param compass_y Y axis compass
- * @param compass_z Z axis compass
- * @param temp Temperature
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_mpu_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float compass_x, float compass_y, float compass_z, float temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MPU_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, compass_x);
- _mav_put_float(buf, 36, compass_y);
- _mav_put_float(buf, 40, compass_z);
- _mav_put_float(buf, 44, temp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MPU_TM_LEN);
-#else
- mavlink_mpu_tm_t packet;
- packet.timestamp = timestamp;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.compass_x = compass_x;
- packet.compass_y = compass_y;
- packet.compass_z = compass_z;
- packet.temp = temp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MPU_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_MPU_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MPU_TM_MIN_LEN, MAVLINK_MSG_ID_MPU_TM_LEN, MAVLINK_MSG_ID_MPU_TM_CRC);
-}
-
-/**
- * @brief Pack a mpu_tm 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 When was this logged
- * @param acc_x X axis acceleration
- * @param acc_y Y axis acceleration
- * @param acc_z Z axis acceleration
- * @param gyro_x X axis gyro
- * @param gyro_y Y axis gyro
- * @param gyro_z Z axis gyro
- * @param compass_x X axis compass
- * @param compass_y Y axis compass
- * @param compass_z Z axis compass
- * @param temp Temperature
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_mpu_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float compass_x,float compass_y,float compass_z,float temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MPU_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, compass_x);
- _mav_put_float(buf, 36, compass_y);
- _mav_put_float(buf, 40, compass_z);
- _mav_put_float(buf, 44, temp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MPU_TM_LEN);
-#else
- mavlink_mpu_tm_t packet;
- packet.timestamp = timestamp;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.compass_x = compass_x;
- packet.compass_y = compass_y;
- packet.compass_z = compass_z;
- packet.temp = temp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MPU_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_MPU_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MPU_TM_MIN_LEN, MAVLINK_MSG_ID_MPU_TM_LEN, MAVLINK_MSG_ID_MPU_TM_CRC);
-}
-
-/**
- * @brief Encode a mpu_tm 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 mpu_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_mpu_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mpu_tm_t* mpu_tm)
-{
- return mavlink_msg_mpu_tm_pack(system_id, component_id, msg, mpu_tm->timestamp, mpu_tm->acc_x, mpu_tm->acc_y, mpu_tm->acc_z, mpu_tm->gyro_x, mpu_tm->gyro_y, mpu_tm->gyro_z, mpu_tm->compass_x, mpu_tm->compass_y, mpu_tm->compass_z, mpu_tm->temp);
-}
-
-/**
- * @brief Encode a mpu_tm 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 mpu_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_mpu_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mpu_tm_t* mpu_tm)
-{
- return mavlink_msg_mpu_tm_pack_chan(system_id, component_id, chan, msg, mpu_tm->timestamp, mpu_tm->acc_x, mpu_tm->acc_y, mpu_tm->acc_z, mpu_tm->gyro_x, mpu_tm->gyro_y, mpu_tm->gyro_z, mpu_tm->compass_x, mpu_tm->compass_y, mpu_tm->compass_z, mpu_tm->temp);
-}
-
-/**
- * @brief Send a mpu_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp When was this logged
- * @param acc_x X axis acceleration
- * @param acc_y Y axis acceleration
- * @param acc_z Z axis acceleration
- * @param gyro_x X axis gyro
- * @param gyro_y Y axis gyro
- * @param gyro_z Z axis gyro
- * @param compass_x X axis compass
- * @param compass_y Y axis compass
- * @param compass_z Z axis compass
- * @param temp Temperature
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_mpu_tm_send(mavlink_channel_t chan, uint64_t timestamp, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float compass_x, float compass_y, float compass_z, float temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MPU_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, compass_x);
- _mav_put_float(buf, 36, compass_y);
- _mav_put_float(buf, 40, compass_z);
- _mav_put_float(buf, 44, temp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MPU_TM, buf, MAVLINK_MSG_ID_MPU_TM_MIN_LEN, MAVLINK_MSG_ID_MPU_TM_LEN, MAVLINK_MSG_ID_MPU_TM_CRC);
-#else
- mavlink_mpu_tm_t packet;
- packet.timestamp = timestamp;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.compass_x = compass_x;
- packet.compass_y = compass_y;
- packet.compass_z = compass_z;
- packet.temp = temp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MPU_TM, (const char *)&packet, MAVLINK_MSG_ID_MPU_TM_MIN_LEN, MAVLINK_MSG_ID_MPU_TM_LEN, MAVLINK_MSG_ID_MPU_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a mpu_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_mpu_tm_send_struct(mavlink_channel_t chan, const mavlink_mpu_tm_t* mpu_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_mpu_tm_send(chan, mpu_tm->timestamp, mpu_tm->acc_x, mpu_tm->acc_y, mpu_tm->acc_z, mpu_tm->gyro_x, mpu_tm->gyro_y, mpu_tm->gyro_z, mpu_tm->compass_x, mpu_tm->compass_y, mpu_tm->compass_z, mpu_tm->temp);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MPU_TM, (const char *)mpu_tm, MAVLINK_MSG_ID_MPU_TM_MIN_LEN, MAVLINK_MSG_ID_MPU_TM_LEN, MAVLINK_MSG_ID_MPU_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_MPU_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_mpu_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float compass_x, float compass_y, float compass_z, float temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, compass_x);
- _mav_put_float(buf, 36, compass_y);
- _mav_put_float(buf, 40, compass_z);
- _mav_put_float(buf, 44, temp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MPU_TM, buf, MAVLINK_MSG_ID_MPU_TM_MIN_LEN, MAVLINK_MSG_ID_MPU_TM_LEN, MAVLINK_MSG_ID_MPU_TM_CRC);
-#else
- mavlink_mpu_tm_t *packet = (mavlink_mpu_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->acc_x = acc_x;
- packet->acc_y = acc_y;
- packet->acc_z = acc_z;
- packet->gyro_x = gyro_x;
- packet->gyro_y = gyro_y;
- packet->gyro_z = gyro_z;
- packet->compass_x = compass_x;
- packet->compass_y = compass_y;
- packet->compass_z = compass_z;
- packet->temp = temp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MPU_TM, (const char *)packet, MAVLINK_MSG_ID_MPU_TM_MIN_LEN, MAVLINK_MSG_ID_MPU_TM_LEN, MAVLINK_MSG_ID_MPU_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE MPU_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from mpu_tm message
- *
- * @return When was this logged
- */
-static inline uint64_t mavlink_msg_mpu_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field acc_x from mpu_tm message
- *
- * @return X axis acceleration
- */
-static inline float mavlink_msg_mpu_tm_get_acc_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field acc_y from mpu_tm message
- *
- * @return Y axis acceleration
- */
-static inline float mavlink_msg_mpu_tm_get_acc_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field acc_z from mpu_tm message
- *
- * @return Z axis acceleration
- */
-static inline float mavlink_msg_mpu_tm_get_acc_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field gyro_x from mpu_tm message
- *
- * @return X axis gyro
- */
-static inline float mavlink_msg_mpu_tm_get_gyro_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field gyro_y from mpu_tm message
- *
- * @return Y axis gyro
- */
-static inline float mavlink_msg_mpu_tm_get_gyro_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field gyro_z from mpu_tm message
- *
- * @return Z axis gyro
- */
-static inline float mavlink_msg_mpu_tm_get_gyro_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field compass_x from mpu_tm message
- *
- * @return X axis compass
- */
-static inline float mavlink_msg_mpu_tm_get_compass_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field compass_y from mpu_tm message
- *
- * @return Y axis compass
- */
-static inline float mavlink_msg_mpu_tm_get_compass_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field compass_z from mpu_tm message
- *
- * @return Z axis compass
- */
-static inline float mavlink_msg_mpu_tm_get_compass_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field temp from mpu_tm message
- *
- * @return Temperature
- */
-static inline float mavlink_msg_mpu_tm_get_temp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Decode a mpu_tm message into a struct
- *
- * @param msg The message to decode
- * @param mpu_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_mpu_tm_decode(const mavlink_message_t* msg, mavlink_mpu_tm_t* mpu_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mpu_tm->timestamp = mavlink_msg_mpu_tm_get_timestamp(msg);
- mpu_tm->acc_x = mavlink_msg_mpu_tm_get_acc_x(msg);
- mpu_tm->acc_y = mavlink_msg_mpu_tm_get_acc_y(msg);
- mpu_tm->acc_z = mavlink_msg_mpu_tm_get_acc_z(msg);
- mpu_tm->gyro_x = mavlink_msg_mpu_tm_get_gyro_x(msg);
- mpu_tm->gyro_y = mavlink_msg_mpu_tm_get_gyro_y(msg);
- mpu_tm->gyro_z = mavlink_msg_mpu_tm_get_gyro_z(msg);
- mpu_tm->compass_x = mavlink_msg_mpu_tm_get_compass_x(msg);
- mpu_tm->compass_y = mavlink_msg_mpu_tm_get_compass_y(msg);
- mpu_tm->compass_z = mavlink_msg_mpu_tm_get_compass_z(msg);
- mpu_tm->temp = mavlink_msg_mpu_tm_get_temp(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_MPU_TM_LEN? msg->len : MAVLINK_MSG_ID_MPU_TM_LEN;
- memset(mpu_tm, 0, MAVLINK_MSG_ID_MPU_TM_LEN);
- memcpy(mpu_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_nack_tm.h b/mavlink_lib/hermes/mavlink_msg_nack_tm.h
deleted file mode 100644
index 55451259046d4d2b5458aae948a2070d2a7e05a0..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_nack_tm.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE NACK_TM PACKING
-
-#define MAVLINK_MSG_ID_NACK_TM 131
-
-MAVPACKED(
-typedef struct __mavlink_nack_tm_t {
- uint8_t recv_msgid; /*< Message id of the received message.*/
- uint8_t seq_ack; /*< Sequence number of the received message.*/
-}) mavlink_nack_tm_t;
-
-#define MAVLINK_MSG_ID_NACK_TM_LEN 2
-#define MAVLINK_MSG_ID_NACK_TM_MIN_LEN 2
-#define MAVLINK_MSG_ID_131_LEN 2
-#define MAVLINK_MSG_ID_131_MIN_LEN 2
-
-#define MAVLINK_MSG_ID_NACK_TM_CRC 146
-#define MAVLINK_MSG_ID_131_CRC 146
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_NACK_TM { \
- 131, \
- "NACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_nack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_nack_tm_t, seq_ack) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_NACK_TM { \
- "NACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_nack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_nack_tm_t, seq_ack) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a nack_tm 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 recv_msgid Message id of the received message.
- * @param seq_ack Sequence number of the received message.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_nack_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NACK_TM_LEN);
-#else
- mavlink_nack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NACK_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-}
-
-/**
- * @brief Pack a nack_tm 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 recv_msgid Message id of the received message.
- * @param seq_ack Sequence number of the received message.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_nack_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t recv_msgid,uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NACK_TM_LEN);
-#else
- mavlink_nack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NACK_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-}
-
-/**
- * @brief Encode a nack_tm 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 nack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_nack_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nack_tm_t* nack_tm)
-{
- return mavlink_msg_nack_tm_pack(system_id, component_id, msg, nack_tm->recv_msgid, nack_tm->seq_ack);
-}
-
-/**
- * @brief Encode a nack_tm 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 nack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_nack_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nack_tm_t* nack_tm)
-{
- return mavlink_msg_nack_tm_pack_chan(system_id, component_id, chan, msg, nack_tm->recv_msgid, nack_tm->seq_ack);
-}
-
-/**
- * @brief Send a nack_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param recv_msgid Message id of the received message.
- * @param seq_ack Sequence number of the received message.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_nack_tm_send(mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, buf, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#else
- mavlink_nack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, (const char *)&packet, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a nack_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_nack_tm_send_struct(mavlink_channel_t chan, const mavlink_nack_tm_t* nack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_nack_tm_send(chan, nack_tm->recv_msgid, nack_tm->seq_ack);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, (const char *)nack_tm, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_NACK_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_nack_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, buf, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#else
- mavlink_nack_tm_t *packet = (mavlink_nack_tm_t *)msgbuf;
- packet->recv_msgid = recv_msgid;
- packet->seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, (const char *)packet, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE NACK_TM UNPACKING
-
-
-/**
- * @brief Get field recv_msgid from nack_tm message
- *
- * @return Message id of the received message.
- */
-static inline uint8_t mavlink_msg_nack_tm_get_recv_msgid(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field seq_ack from nack_tm message
- *
- * @return Sequence number of the received message.
- */
-static inline uint8_t mavlink_msg_nack_tm_get_seq_ack(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Decode a nack_tm message into a struct
- *
- * @param msg The message to decode
- * @param nack_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_nack_tm_decode(const mavlink_message_t* msg, mavlink_nack_tm_t* nack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- nack_tm->recv_msgid = mavlink_msg_nack_tm_get_recv_msgid(msg);
- nack_tm->seq_ack = mavlink_msg_nack_tm_get_seq_ack(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_NACK_TM_LEN? msg->len : MAVLINK_MSG_ID_NACK_TM_LEN;
- memset(nack_tm, 0, MAVLINK_MSG_ID_NACK_TM_LEN);
- memcpy(nack_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_noarg_tc.h b/mavlink_lib/hermes/mavlink_msg_noarg_tc.h
deleted file mode 100644
index 7de53c9223ff12524224dede49dcfee4c45f38c1..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_noarg_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE NOARG_TC PACKING
-
-#define MAVLINK_MSG_ID_NOARG_TC 10
-
-MAVPACKED(
-typedef struct __mavlink_noarg_tc_t {
- uint8_t command_id; /*< A member of the MavCommandList enum.*/
-}) mavlink_noarg_tc_t;
-
-#define MAVLINK_MSG_ID_NOARG_TC_LEN 1
-#define MAVLINK_MSG_ID_NOARG_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_10_LEN 1
-#define MAVLINK_MSG_ID_10_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_NOARG_TC_CRC 77
-#define MAVLINK_MSG_ID_10_CRC 77
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_NOARG_TC { \
- 10, \
- "NOARG_TC", \
- 1, \
- { { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_noarg_tc_t, command_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_NOARG_TC { \
- "NOARG_TC", \
- 1, \
- { { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_noarg_tc_t, command_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a noarg_tc 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_id A member of the MavCommandList enum.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_noarg_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NOARG_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NOARG_TC_LEN);
-#else
- mavlink_noarg_tc_t packet;
- packet.command_id = command_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NOARG_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NOARG_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-}
-
-/**
- * @brief Pack a noarg_tc 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_id A member of the MavCommandList enum.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_noarg_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NOARG_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NOARG_TC_LEN);
-#else
- mavlink_noarg_tc_t packet;
- packet.command_id = command_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NOARG_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NOARG_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-}
-
-/**
- * @brief Encode a noarg_tc 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 noarg_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_noarg_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_noarg_tc_t* noarg_tc)
-{
- return mavlink_msg_noarg_tc_pack(system_id, component_id, msg, noarg_tc->command_id);
-}
-
-/**
- * @brief Encode a noarg_tc 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 noarg_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_noarg_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_noarg_tc_t* noarg_tc)
-{
- return mavlink_msg_noarg_tc_pack_chan(system_id, component_id, chan, msg, noarg_tc->command_id);
-}
-
-/**
- * @brief Send a noarg_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param command_id A member of the MavCommandList enum.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_noarg_tc_send(mavlink_channel_t chan, uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NOARG_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOARG_TC, buf, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-#else
- mavlink_noarg_tc_t packet;
- packet.command_id = command_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOARG_TC, (const char *)&packet, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a noarg_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_noarg_tc_send_struct(mavlink_channel_t chan, const mavlink_noarg_tc_t* noarg_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_noarg_tc_send(chan, noarg_tc->command_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOARG_TC, (const char *)noarg_tc, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_NOARG_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_noarg_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, command_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOARG_TC, buf, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-#else
- mavlink_noarg_tc_t *packet = (mavlink_noarg_tc_t *)msgbuf;
- packet->command_id = command_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOARG_TC, (const char *)packet, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE NOARG_TC UNPACKING
-
-
-/**
- * @brief Get field command_id from noarg_tc message
- *
- * @return A member of the MavCommandList enum.
- */
-static inline uint8_t mavlink_msg_noarg_tc_get_command_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a noarg_tc message into a struct
- *
- * @param msg The message to decode
- * @param noarg_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_noarg_tc_decode(const mavlink_message_t* msg, mavlink_noarg_tc_t* noarg_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- noarg_tc->command_id = mavlink_msg_noarg_tc_get_command_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_NOARG_TC_LEN? msg->len : MAVLINK_MSG_ID_NOARG_TC_LEN;
- memset(noarg_tc, 0, MAVLINK_MSG_ID_NOARG_TC_LEN);
- memcpy(noarg_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_ping_tc.h b/mavlink_lib/hermes/mavlink_msg_ping_tc.h
deleted file mode 100644
index cb1575a0f48705e36177dc8186d3ae85bbd41391..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_ping_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE PING_TC PACKING
-
-#define MAVLINK_MSG_ID_PING_TC 1
-
-MAVPACKED(
-typedef struct __mavlink_ping_tc_t {
- uint64_t timestamp; /*< Timestamp to identify when it was sent.*/
-}) mavlink_ping_tc_t;
-
-#define MAVLINK_MSG_ID_PING_TC_LEN 8
-#define MAVLINK_MSG_ID_PING_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_1_LEN 8
-#define MAVLINK_MSG_ID_1_MIN_LEN 8
-
-#define MAVLINK_MSG_ID_PING_TC_CRC 136
-#define MAVLINK_MSG_ID_1_CRC 136
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_PING_TC { \
- 1, \
- "PING_TC", \
- 1, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_tc_t, timestamp) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_PING_TC { \
- "PING_TC", \
- 1, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_tc_t, timestamp) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ping_tc 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 Timestamp to identify when it was sent.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ping_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_TC_LEN);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PING_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-}
-
-/**
- * @brief Pack a ping_tc 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 Timestamp to identify when it was sent.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ping_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_TC_LEN);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PING_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-}
-
-/**
- * @brief Encode a ping_tc 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_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ping_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_tc_t* ping_tc)
-{
- return mavlink_msg_ping_tc_pack(system_id, component_id, msg, ping_tc->timestamp);
-}
-
-/**
- * @brief Encode a ping_tc 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_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ping_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ping_tc_t* ping_tc)
-{
- return mavlink_msg_ping_tc_pack_chan(system_id, component_id, chan, msg, ping_tc->timestamp);
-}
-
-/**
- * @brief Send a ping_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp Timestamp to identify when it was sent.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ping_tc_send(mavlink_channel_t chan, uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, buf, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)&packet, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a ping_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ping_tc_send_struct(mavlink_channel_t chan, const mavlink_ping_tc_t* ping_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ping_tc_send(chan, ping_tc->timestamp);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)ping_tc, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_PING_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, buf, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#else
- mavlink_ping_tc_t *packet = (mavlink_ping_tc_t *)msgbuf;
- packet->timestamp = timestamp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)packet, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE PING_TC UNPACKING
-
-
-/**
- * @brief Get field timestamp from ping_tc message
- *
- * @return Timestamp to identify when it was sent.
- */
-static inline uint64_t mavlink_msg_ping_tc_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Decode a ping_tc message into a struct
- *
- * @param msg The message to decode
- * @param ping_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ping_tc_decode(const mavlink_message_t* msg, mavlink_ping_tc_t* ping_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ping_tc->timestamp = mavlink_msg_ping_tc_get_timestamp(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_PING_TC_LEN? msg->len : MAVLINK_MSG_ID_PING_TC_LEN;
- memset(ping_tc, 0, MAVLINK_MSG_ID_PING_TC_LEN);
- memcpy(ping_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_raw_event_tc.h b/mavlink_lib/hermes/mavlink_msg_raw_event_tc.h
deleted file mode 100644
index 7b95415ba088d3fd4527319f3ee22c84c5754eb9..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_raw_event_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE RAW_EVENT_TC PACKING
-
-#define MAVLINK_MSG_ID_RAW_EVENT_TC 80
-
-MAVPACKED(
-typedef struct __mavlink_raw_event_tc_t {
- uint8_t Event_id; /*< Id of the event to be posted.*/
- uint8_t Topic_id; /*< Id of the topic to which the event should be posted.*/
-}) mavlink_raw_event_tc_t;
-
-#define MAVLINK_MSG_ID_RAW_EVENT_TC_LEN 2
-#define MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN 2
-#define MAVLINK_MSG_ID_80_LEN 2
-#define MAVLINK_MSG_ID_80_MIN_LEN 2
-
-#define MAVLINK_MSG_ID_RAW_EVENT_TC_CRC 134
-#define MAVLINK_MSG_ID_80_CRC 134
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_RAW_EVENT_TC { \
- 80, \
- "RAW_EVENT_TC", \
- 2, \
- { { "Event_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_raw_event_tc_t, Event_id) }, \
- { "Topic_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_raw_event_tc_t, Topic_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_RAW_EVENT_TC { \
- "RAW_EVENT_TC", \
- 2, \
- { { "Event_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_raw_event_tc_t, Event_id) }, \
- { "Topic_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_raw_event_tc_t, Topic_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a raw_event_tc 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 Event_id Id of the event to be posted.
- * @param Topic_id Id of the topic to which the event should be posted.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_raw_event_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t Event_id, uint8_t Topic_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_EVENT_TC_LEN];
- _mav_put_uint8_t(buf, 0, Event_id);
- _mav_put_uint8_t(buf, 1, Topic_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#else
- mavlink_raw_event_tc_t packet;
- packet.Event_id = Event_id;
- packet.Topic_id = Topic_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RAW_EVENT_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-}
-
-/**
- * @brief Pack a raw_event_tc 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 Event_id Id of the event to be posted.
- * @param Topic_id Id of the topic to which the event should be posted.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_raw_event_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t Event_id,uint8_t Topic_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_EVENT_TC_LEN];
- _mav_put_uint8_t(buf, 0, Event_id);
- _mav_put_uint8_t(buf, 1, Topic_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#else
- mavlink_raw_event_tc_t packet;
- packet.Event_id = Event_id;
- packet.Topic_id = Topic_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RAW_EVENT_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-}
-
-/**
- * @brief Encode a raw_event_tc 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_event_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_raw_event_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_event_tc_t* raw_event_tc)
-{
- return mavlink_msg_raw_event_tc_pack(system_id, component_id, msg, raw_event_tc->Event_id, raw_event_tc->Topic_id);
-}
-
-/**
- * @brief Encode a raw_event_tc 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_event_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_raw_event_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_event_tc_t* raw_event_tc)
-{
- return mavlink_msg_raw_event_tc_pack_chan(system_id, component_id, chan, msg, raw_event_tc->Event_id, raw_event_tc->Topic_id);
-}
-
-/**
- * @brief Send a raw_event_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param Event_id Id of the event to be posted.
- * @param Topic_id Id of the topic to which the event should be posted.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_raw_event_tc_send(mavlink_channel_t chan, uint8_t Event_id, uint8_t Topic_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_EVENT_TC_LEN];
- _mav_put_uint8_t(buf, 0, Event_id);
- _mav_put_uint8_t(buf, 1, Topic_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, buf, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#else
- mavlink_raw_event_tc_t packet;
- packet.Event_id = Event_id;
- packet.Topic_id = Topic_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, (const char *)&packet, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a raw_event_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_raw_event_tc_send_struct(mavlink_channel_t chan, const mavlink_raw_event_tc_t* raw_event_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_raw_event_tc_send(chan, raw_event_tc->Event_id, raw_event_tc->Topic_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, (const char *)raw_event_tc, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_RAW_EVENT_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_event_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t Event_id, uint8_t Topic_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, Event_id);
- _mav_put_uint8_t(buf, 1, Topic_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, buf, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#else
- mavlink_raw_event_tc_t *packet = (mavlink_raw_event_tc_t *)msgbuf;
- packet->Event_id = Event_id;
- packet->Topic_id = Topic_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, (const char *)packet, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE RAW_EVENT_TC UNPACKING
-
-
-/**
- * @brief Get field Event_id from raw_event_tc message
- *
- * @return Id of the event to be posted.
- */
-static inline uint8_t mavlink_msg_raw_event_tc_get_Event_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field Topic_id from raw_event_tc message
- *
- * @return Id of the topic to which the event should be posted.
- */
-static inline uint8_t mavlink_msg_raw_event_tc_get_Topic_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Decode a raw_event_tc message into a struct
- *
- * @param msg The message to decode
- * @param raw_event_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_raw_event_tc_decode(const mavlink_message_t* msg, mavlink_raw_event_tc_t* raw_event_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- raw_event_tc->Event_id = mavlink_msg_raw_event_tc_get_Event_id(msg);
- raw_event_tc->Topic_id = mavlink_msg_raw_event_tc_get_Topic_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_RAW_EVENT_TC_LEN? msg->len : MAVLINK_MSG_ID_RAW_EVENT_TC_LEN;
- memset(raw_event_tc, 0, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
- memcpy(raw_event_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_sm_tm.h b/mavlink_lib/hermes/mavlink_msg_sm_tm.h
deleted file mode 100644
index 50e5b0a4284fa62f40ecab6ac94bac36db2a8673..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_sm_tm.h
+++ /dev/null
@@ -1,563 +0,0 @@
-#pragma once
-// MESSAGE SM_TM PACKING
-
-#define MAVLINK_MSG_ID_SM_TM 164
-
-MAVPACKED(
-typedef struct __mavlink_sm_tm_t {
- uint64_t timestamp; /*< When was this logged */
- float task_10hz_min; /*< 10 Hz task min period*/
- float task_10hz_max; /*< 10 Hz task max period*/
- float task_10hz_mean; /*< 10 Hz task mean period*/
- float task_10hz_stddev; /*< 10 Hz task period std deviation*/
- float task_20hz_min; /*< 20 Hz task min period*/
- float task_20hz_max; /*< 20 Hz task max period*/
- float task_20hz_mean; /*< 20 Hz task mean period*/
- float task_20hz_stddev; /*< 20 Hz task period std deviation*/
- float task_250hz_min; /*< 250 Hz task min period*/
- float task_250hz_max; /*< 250 Hz task max period*/
- float task_250hz_mean; /*< 250 Hz task mean period*/
- float task_250hz_stddev; /*< 250 Hz task period std deviation*/
- uint16_t sensor_state; /*< Sensors init + self check result*/
- uint8_t state; /*< Sensor manager state*/
-}) mavlink_sm_tm_t;
-
-#define MAVLINK_MSG_ID_SM_TM_LEN 59
-#define MAVLINK_MSG_ID_SM_TM_MIN_LEN 59
-#define MAVLINK_MSG_ID_164_LEN 59
-#define MAVLINK_MSG_ID_164_MIN_LEN 59
-
-#define MAVLINK_MSG_ID_SM_TM_CRC 154
-#define MAVLINK_MSG_ID_164_CRC 154
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SM_TM { \
- 164, \
- "SM_TM", \
- 15, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_sm_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 58, offsetof(mavlink_sm_tm_t, state) }, \
- { "sensor_state", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_sm_tm_t, sensor_state) }, \
- { "task_10hz_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sm_tm_t, task_10hz_min) }, \
- { "task_10hz_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sm_tm_t, task_10hz_max) }, \
- { "task_10hz_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sm_tm_t, task_10hz_mean) }, \
- { "task_10hz_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sm_tm_t, task_10hz_stddev) }, \
- { "task_20hz_min", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sm_tm_t, task_20hz_min) }, \
- { "task_20hz_max", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sm_tm_t, task_20hz_max) }, \
- { "task_20hz_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sm_tm_t, task_20hz_mean) }, \
- { "task_20hz_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sm_tm_t, task_20hz_stddev) }, \
- { "task_250hz_min", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sm_tm_t, task_250hz_min) }, \
- { "task_250hz_max", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_sm_tm_t, task_250hz_max) }, \
- { "task_250hz_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_sm_tm_t, task_250hz_mean) }, \
- { "task_250hz_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_sm_tm_t, task_250hz_stddev) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SM_TM { \
- "SM_TM", \
- 15, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_sm_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 58, offsetof(mavlink_sm_tm_t, state) }, \
- { "sensor_state", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_sm_tm_t, sensor_state) }, \
- { "task_10hz_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sm_tm_t, task_10hz_min) }, \
- { "task_10hz_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sm_tm_t, task_10hz_max) }, \
- { "task_10hz_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sm_tm_t, task_10hz_mean) }, \
- { "task_10hz_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sm_tm_t, task_10hz_stddev) }, \
- { "task_20hz_min", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sm_tm_t, task_20hz_min) }, \
- { "task_20hz_max", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sm_tm_t, task_20hz_max) }, \
- { "task_20hz_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sm_tm_t, task_20hz_mean) }, \
- { "task_20hz_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sm_tm_t, task_20hz_stddev) }, \
- { "task_250hz_min", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sm_tm_t, task_250hz_min) }, \
- { "task_250hz_max", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_sm_tm_t, task_250hz_max) }, \
- { "task_250hz_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_sm_tm_t, task_250hz_mean) }, \
- { "task_250hz_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_sm_tm_t, task_250hz_stddev) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a sm_tm 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 When was this logged
- * @param state Sensor manager state
- * @param sensor_state Sensors init + self check result
- * @param task_10hz_min 10 Hz task min period
- * @param task_10hz_max 10 Hz task max period
- * @param task_10hz_mean 10 Hz task mean period
- * @param task_10hz_stddev 10 Hz task period std deviation
- * @param task_20hz_min 20 Hz task min period
- * @param task_20hz_max 20 Hz task max period
- * @param task_20hz_mean 20 Hz task mean period
- * @param task_20hz_stddev 20 Hz task period std deviation
- * @param task_250hz_min 250 Hz task min period
- * @param task_250hz_max 250 Hz task max period
- * @param task_250hz_mean 250 Hz task mean period
- * @param task_250hz_stddev 250 Hz task period std deviation
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sm_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t state, uint16_t sensor_state, float task_10hz_min, float task_10hz_max, float task_10hz_mean, float task_10hz_stddev, float task_20hz_min, float task_20hz_max, float task_20hz_mean, float task_20hz_stddev, float task_250hz_min, float task_250hz_max, float task_250hz_mean, float task_250hz_stddev)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SM_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, task_10hz_min);
- _mav_put_float(buf, 12, task_10hz_max);
- _mav_put_float(buf, 16, task_10hz_mean);
- _mav_put_float(buf, 20, task_10hz_stddev);
- _mav_put_float(buf, 24, task_20hz_min);
- _mav_put_float(buf, 28, task_20hz_max);
- _mav_put_float(buf, 32, task_20hz_mean);
- _mav_put_float(buf, 36, task_20hz_stddev);
- _mav_put_float(buf, 40, task_250hz_min);
- _mav_put_float(buf, 44, task_250hz_max);
- _mav_put_float(buf, 48, task_250hz_mean);
- _mav_put_float(buf, 52, task_250hz_stddev);
- _mav_put_uint16_t(buf, 56, sensor_state);
- _mav_put_uint8_t(buf, 58, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SM_TM_LEN);
-#else
- mavlink_sm_tm_t packet;
- packet.timestamp = timestamp;
- packet.task_10hz_min = task_10hz_min;
- packet.task_10hz_max = task_10hz_max;
- packet.task_10hz_mean = task_10hz_mean;
- packet.task_10hz_stddev = task_10hz_stddev;
- packet.task_20hz_min = task_20hz_min;
- packet.task_20hz_max = task_20hz_max;
- packet.task_20hz_mean = task_20hz_mean;
- packet.task_20hz_stddev = task_20hz_stddev;
- packet.task_250hz_min = task_250hz_min;
- packet.task_250hz_max = task_250hz_max;
- packet.task_250hz_mean = task_250hz_mean;
- packet.task_250hz_stddev = task_250hz_stddev;
- packet.sensor_state = sensor_state;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SM_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SM_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SM_TM_MIN_LEN, MAVLINK_MSG_ID_SM_TM_LEN, MAVLINK_MSG_ID_SM_TM_CRC);
-}
-
-/**
- * @brief Pack a sm_tm 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 When was this logged
- * @param state Sensor manager state
- * @param sensor_state Sensors init + self check result
- * @param task_10hz_min 10 Hz task min period
- * @param task_10hz_max 10 Hz task max period
- * @param task_10hz_mean 10 Hz task mean period
- * @param task_10hz_stddev 10 Hz task period std deviation
- * @param task_20hz_min 20 Hz task min period
- * @param task_20hz_max 20 Hz task max period
- * @param task_20hz_mean 20 Hz task mean period
- * @param task_20hz_stddev 20 Hz task period std deviation
- * @param task_250hz_min 250 Hz task min period
- * @param task_250hz_max 250 Hz task max period
- * @param task_250hz_mean 250 Hz task mean period
- * @param task_250hz_stddev 250 Hz task period std deviation
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sm_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t state,uint16_t sensor_state,float task_10hz_min,float task_10hz_max,float task_10hz_mean,float task_10hz_stddev,float task_20hz_min,float task_20hz_max,float task_20hz_mean,float task_20hz_stddev,float task_250hz_min,float task_250hz_max,float task_250hz_mean,float task_250hz_stddev)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SM_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, task_10hz_min);
- _mav_put_float(buf, 12, task_10hz_max);
- _mav_put_float(buf, 16, task_10hz_mean);
- _mav_put_float(buf, 20, task_10hz_stddev);
- _mav_put_float(buf, 24, task_20hz_min);
- _mav_put_float(buf, 28, task_20hz_max);
- _mav_put_float(buf, 32, task_20hz_mean);
- _mav_put_float(buf, 36, task_20hz_stddev);
- _mav_put_float(buf, 40, task_250hz_min);
- _mav_put_float(buf, 44, task_250hz_max);
- _mav_put_float(buf, 48, task_250hz_mean);
- _mav_put_float(buf, 52, task_250hz_stddev);
- _mav_put_uint16_t(buf, 56, sensor_state);
- _mav_put_uint8_t(buf, 58, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SM_TM_LEN);
-#else
- mavlink_sm_tm_t packet;
- packet.timestamp = timestamp;
- packet.task_10hz_min = task_10hz_min;
- packet.task_10hz_max = task_10hz_max;
- packet.task_10hz_mean = task_10hz_mean;
- packet.task_10hz_stddev = task_10hz_stddev;
- packet.task_20hz_min = task_20hz_min;
- packet.task_20hz_max = task_20hz_max;
- packet.task_20hz_mean = task_20hz_mean;
- packet.task_20hz_stddev = task_20hz_stddev;
- packet.task_250hz_min = task_250hz_min;
- packet.task_250hz_max = task_250hz_max;
- packet.task_250hz_mean = task_250hz_mean;
- packet.task_250hz_stddev = task_250hz_stddev;
- packet.sensor_state = sensor_state;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SM_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SM_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SM_TM_MIN_LEN, MAVLINK_MSG_ID_SM_TM_LEN, MAVLINK_MSG_ID_SM_TM_CRC);
-}
-
-/**
- * @brief Encode a sm_tm 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 sm_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sm_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sm_tm_t* sm_tm)
-{
- return mavlink_msg_sm_tm_pack(system_id, component_id, msg, sm_tm->timestamp, sm_tm->state, sm_tm->sensor_state, sm_tm->task_10hz_min, sm_tm->task_10hz_max, sm_tm->task_10hz_mean, sm_tm->task_10hz_stddev, sm_tm->task_20hz_min, sm_tm->task_20hz_max, sm_tm->task_20hz_mean, sm_tm->task_20hz_stddev, sm_tm->task_250hz_min, sm_tm->task_250hz_max, sm_tm->task_250hz_mean, sm_tm->task_250hz_stddev);
-}
-
-/**
- * @brief Encode a sm_tm 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 sm_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sm_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sm_tm_t* sm_tm)
-{
- return mavlink_msg_sm_tm_pack_chan(system_id, component_id, chan, msg, sm_tm->timestamp, sm_tm->state, sm_tm->sensor_state, sm_tm->task_10hz_min, sm_tm->task_10hz_max, sm_tm->task_10hz_mean, sm_tm->task_10hz_stddev, sm_tm->task_20hz_min, sm_tm->task_20hz_max, sm_tm->task_20hz_mean, sm_tm->task_20hz_stddev, sm_tm->task_250hz_min, sm_tm->task_250hz_max, sm_tm->task_250hz_mean, sm_tm->task_250hz_stddev);
-}
-
-/**
- * @brief Send a sm_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp When was this logged
- * @param state Sensor manager state
- * @param sensor_state Sensors init + self check result
- * @param task_10hz_min 10 Hz task min period
- * @param task_10hz_max 10 Hz task max period
- * @param task_10hz_mean 10 Hz task mean period
- * @param task_10hz_stddev 10 Hz task period std deviation
- * @param task_20hz_min 20 Hz task min period
- * @param task_20hz_max 20 Hz task max period
- * @param task_20hz_mean 20 Hz task mean period
- * @param task_20hz_stddev 20 Hz task period std deviation
- * @param task_250hz_min 250 Hz task min period
- * @param task_250hz_max 250 Hz task max period
- * @param task_250hz_mean 250 Hz task mean period
- * @param task_250hz_stddev 250 Hz task period std deviation
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_sm_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state, uint16_t sensor_state, float task_10hz_min, float task_10hz_max, float task_10hz_mean, float task_10hz_stddev, float task_20hz_min, float task_20hz_max, float task_20hz_mean, float task_20hz_stddev, float task_250hz_min, float task_250hz_max, float task_250hz_mean, float task_250hz_stddev)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SM_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, task_10hz_min);
- _mav_put_float(buf, 12, task_10hz_max);
- _mav_put_float(buf, 16, task_10hz_mean);
- _mav_put_float(buf, 20, task_10hz_stddev);
- _mav_put_float(buf, 24, task_20hz_min);
- _mav_put_float(buf, 28, task_20hz_max);
- _mav_put_float(buf, 32, task_20hz_mean);
- _mav_put_float(buf, 36, task_20hz_stddev);
- _mav_put_float(buf, 40, task_250hz_min);
- _mav_put_float(buf, 44, task_250hz_max);
- _mav_put_float(buf, 48, task_250hz_mean);
- _mav_put_float(buf, 52, task_250hz_stddev);
- _mav_put_uint16_t(buf, 56, sensor_state);
- _mav_put_uint8_t(buf, 58, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SM_TM, buf, MAVLINK_MSG_ID_SM_TM_MIN_LEN, MAVLINK_MSG_ID_SM_TM_LEN, MAVLINK_MSG_ID_SM_TM_CRC);
-#else
- mavlink_sm_tm_t packet;
- packet.timestamp = timestamp;
- packet.task_10hz_min = task_10hz_min;
- packet.task_10hz_max = task_10hz_max;
- packet.task_10hz_mean = task_10hz_mean;
- packet.task_10hz_stddev = task_10hz_stddev;
- packet.task_20hz_min = task_20hz_min;
- packet.task_20hz_max = task_20hz_max;
- packet.task_20hz_mean = task_20hz_mean;
- packet.task_20hz_stddev = task_20hz_stddev;
- packet.task_250hz_min = task_250hz_min;
- packet.task_250hz_max = task_250hz_max;
- packet.task_250hz_mean = task_250hz_mean;
- packet.task_250hz_stddev = task_250hz_stddev;
- packet.sensor_state = sensor_state;
- packet.state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SM_TM, (const char *)&packet, MAVLINK_MSG_ID_SM_TM_MIN_LEN, MAVLINK_MSG_ID_SM_TM_LEN, MAVLINK_MSG_ID_SM_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a sm_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_sm_tm_send_struct(mavlink_channel_t chan, const mavlink_sm_tm_t* sm_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_sm_tm_send(chan, sm_tm->timestamp, sm_tm->state, sm_tm->sensor_state, sm_tm->task_10hz_min, sm_tm->task_10hz_max, sm_tm->task_10hz_mean, sm_tm->task_10hz_stddev, sm_tm->task_20hz_min, sm_tm->task_20hz_max, sm_tm->task_20hz_mean, sm_tm->task_20hz_stddev, sm_tm->task_250hz_min, sm_tm->task_250hz_max, sm_tm->task_250hz_mean, sm_tm->task_250hz_stddev);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SM_TM, (const char *)sm_tm, MAVLINK_MSG_ID_SM_TM_MIN_LEN, MAVLINK_MSG_ID_SM_TM_LEN, MAVLINK_MSG_ID_SM_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SM_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_sm_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t state, uint16_t sensor_state, float task_10hz_min, float task_10hz_max, float task_10hz_mean, float task_10hz_stddev, float task_20hz_min, float task_20hz_max, float task_20hz_mean, float task_20hz_stddev, float task_250hz_min, float task_250hz_max, float task_250hz_mean, float task_250hz_stddev)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, task_10hz_min);
- _mav_put_float(buf, 12, task_10hz_max);
- _mav_put_float(buf, 16, task_10hz_mean);
- _mav_put_float(buf, 20, task_10hz_stddev);
- _mav_put_float(buf, 24, task_20hz_min);
- _mav_put_float(buf, 28, task_20hz_max);
- _mav_put_float(buf, 32, task_20hz_mean);
- _mav_put_float(buf, 36, task_20hz_stddev);
- _mav_put_float(buf, 40, task_250hz_min);
- _mav_put_float(buf, 44, task_250hz_max);
- _mav_put_float(buf, 48, task_250hz_mean);
- _mav_put_float(buf, 52, task_250hz_stddev);
- _mav_put_uint16_t(buf, 56, sensor_state);
- _mav_put_uint8_t(buf, 58, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SM_TM, buf, MAVLINK_MSG_ID_SM_TM_MIN_LEN, MAVLINK_MSG_ID_SM_TM_LEN, MAVLINK_MSG_ID_SM_TM_CRC);
-#else
- mavlink_sm_tm_t *packet = (mavlink_sm_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->task_10hz_min = task_10hz_min;
- packet->task_10hz_max = task_10hz_max;
- packet->task_10hz_mean = task_10hz_mean;
- packet->task_10hz_stddev = task_10hz_stddev;
- packet->task_20hz_min = task_20hz_min;
- packet->task_20hz_max = task_20hz_max;
- packet->task_20hz_mean = task_20hz_mean;
- packet->task_20hz_stddev = task_20hz_stddev;
- packet->task_250hz_min = task_250hz_min;
- packet->task_250hz_max = task_250hz_max;
- packet->task_250hz_mean = task_250hz_mean;
- packet->task_250hz_stddev = task_250hz_stddev;
- packet->sensor_state = sensor_state;
- packet->state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SM_TM, (const char *)packet, MAVLINK_MSG_ID_SM_TM_MIN_LEN, MAVLINK_MSG_ID_SM_TM_LEN, MAVLINK_MSG_ID_SM_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SM_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from sm_tm message
- *
- * @return When was this logged
- */
-static inline uint64_t mavlink_msg_sm_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field state from sm_tm message
- *
- * @return Sensor manager state
- */
-static inline uint8_t mavlink_msg_sm_tm_get_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 58);
-}
-
-/**
- * @brief Get field sensor_state from sm_tm message
- *
- * @return Sensors init + self check result
- */
-static inline uint16_t mavlink_msg_sm_tm_get_sensor_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 56);
-}
-
-/**
- * @brief Get field task_10hz_min from sm_tm message
- *
- * @return 10 Hz task min period
- */
-static inline float mavlink_msg_sm_tm_get_task_10hz_min(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field task_10hz_max from sm_tm message
- *
- * @return 10 Hz task max period
- */
-static inline float mavlink_msg_sm_tm_get_task_10hz_max(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field task_10hz_mean from sm_tm message
- *
- * @return 10 Hz task mean period
- */
-static inline float mavlink_msg_sm_tm_get_task_10hz_mean(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field task_10hz_stddev from sm_tm message
- *
- * @return 10 Hz task period std deviation
- */
-static inline float mavlink_msg_sm_tm_get_task_10hz_stddev(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field task_20hz_min from sm_tm message
- *
- * @return 20 Hz task min period
- */
-static inline float mavlink_msg_sm_tm_get_task_20hz_min(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field task_20hz_max from sm_tm message
- *
- * @return 20 Hz task max period
- */
-static inline float mavlink_msg_sm_tm_get_task_20hz_max(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field task_20hz_mean from sm_tm message
- *
- * @return 20 Hz task mean period
- */
-static inline float mavlink_msg_sm_tm_get_task_20hz_mean(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field task_20hz_stddev from sm_tm message
- *
- * @return 20 Hz task period std deviation
- */
-static inline float mavlink_msg_sm_tm_get_task_20hz_stddev(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field task_250hz_min from sm_tm message
- *
- * @return 250 Hz task min period
- */
-static inline float mavlink_msg_sm_tm_get_task_250hz_min(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field task_250hz_max from sm_tm message
- *
- * @return 250 Hz task max period
- */
-static inline float mavlink_msg_sm_tm_get_task_250hz_max(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field task_250hz_mean from sm_tm message
- *
- * @return 250 Hz task mean period
- */
-static inline float mavlink_msg_sm_tm_get_task_250hz_mean(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field task_250hz_stddev from sm_tm message
- *
- * @return 250 Hz task period std deviation
- */
-static inline float mavlink_msg_sm_tm_get_task_250hz_stddev(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Decode a sm_tm message into a struct
- *
- * @param msg The message to decode
- * @param sm_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_sm_tm_decode(const mavlink_message_t* msg, mavlink_sm_tm_t* sm_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- sm_tm->timestamp = mavlink_msg_sm_tm_get_timestamp(msg);
- sm_tm->task_10hz_min = mavlink_msg_sm_tm_get_task_10hz_min(msg);
- sm_tm->task_10hz_max = mavlink_msg_sm_tm_get_task_10hz_max(msg);
- sm_tm->task_10hz_mean = mavlink_msg_sm_tm_get_task_10hz_mean(msg);
- sm_tm->task_10hz_stddev = mavlink_msg_sm_tm_get_task_10hz_stddev(msg);
- sm_tm->task_20hz_min = mavlink_msg_sm_tm_get_task_20hz_min(msg);
- sm_tm->task_20hz_max = mavlink_msg_sm_tm_get_task_20hz_max(msg);
- sm_tm->task_20hz_mean = mavlink_msg_sm_tm_get_task_20hz_mean(msg);
- sm_tm->task_20hz_stddev = mavlink_msg_sm_tm_get_task_20hz_stddev(msg);
- sm_tm->task_250hz_min = mavlink_msg_sm_tm_get_task_250hz_min(msg);
- sm_tm->task_250hz_max = mavlink_msg_sm_tm_get_task_250hz_max(msg);
- sm_tm->task_250hz_mean = mavlink_msg_sm_tm_get_task_250hz_mean(msg);
- sm_tm->task_250hz_stddev = mavlink_msg_sm_tm_get_task_250hz_stddev(msg);
- sm_tm->sensor_state = mavlink_msg_sm_tm_get_sensor_state(msg);
- sm_tm->state = mavlink_msg_sm_tm_get_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SM_TM_LEN? msg->len : MAVLINK_MSG_ID_SM_TM_LEN;
- memset(sm_tm, 0, MAVLINK_MSG_ID_SM_TM_LEN);
- memcpy(sm_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_start_launch_tc.h b/mavlink_lib/hermes/mavlink_msg_start_launch_tc.h
deleted file mode 100644
index 34ab1599e2f08d41912e74034c260f5868631c55..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_start_launch_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE START_LAUNCH_TC PACKING
-
-#define MAVLINK_MSG_ID_START_LAUNCH_TC 20
-
-MAVPACKED(
-typedef struct __mavlink_start_launch_tc_t {
- uint64_t launch_code; /*< 64bit launch code.*/
-}) mavlink_start_launch_tc_t;
-
-#define MAVLINK_MSG_ID_START_LAUNCH_TC_LEN 8
-#define MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_20_LEN 8
-#define MAVLINK_MSG_ID_20_MIN_LEN 8
-
-#define MAVLINK_MSG_ID_START_LAUNCH_TC_CRC 43
-#define MAVLINK_MSG_ID_20_CRC 43
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_START_LAUNCH_TC { \
- 20, \
- "START_LAUNCH_TC", \
- 1, \
- { { "launch_code", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_start_launch_tc_t, launch_code) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_START_LAUNCH_TC { \
- "START_LAUNCH_TC", \
- 1, \
- { { "launch_code", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_start_launch_tc_t, launch_code) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a start_launch_tc 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 launch_code 64bit launch code.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_start_launch_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t launch_code)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_START_LAUNCH_TC_LEN];
- _mav_put_uint64_t(buf, 0, launch_code);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN);
-#else
- mavlink_start_launch_tc_t packet;
- packet.launch_code = launch_code;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_START_LAUNCH_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-}
-
-/**
- * @brief Pack a start_launch_tc 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 launch_code 64bit launch code.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_start_launch_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t launch_code)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_START_LAUNCH_TC_LEN];
- _mav_put_uint64_t(buf, 0, launch_code);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN);
-#else
- mavlink_start_launch_tc_t packet;
- packet.launch_code = launch_code;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_START_LAUNCH_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-}
-
-/**
- * @brief Encode a start_launch_tc 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 start_launch_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_start_launch_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_start_launch_tc_t* start_launch_tc)
-{
- return mavlink_msg_start_launch_tc_pack(system_id, component_id, msg, start_launch_tc->launch_code);
-}
-
-/**
- * @brief Encode a start_launch_tc 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 start_launch_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_start_launch_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_start_launch_tc_t* start_launch_tc)
-{
- return mavlink_msg_start_launch_tc_pack_chan(system_id, component_id, chan, msg, start_launch_tc->launch_code);
-}
-
-/**
- * @brief Send a start_launch_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param launch_code 64bit launch code.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_start_launch_tc_send(mavlink_channel_t chan, uint64_t launch_code)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_START_LAUNCH_TC_LEN];
- _mav_put_uint64_t(buf, 0, launch_code);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_START_LAUNCH_TC, buf, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-#else
- mavlink_start_launch_tc_t packet;
- packet.launch_code = launch_code;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_START_LAUNCH_TC, (const char *)&packet, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a start_launch_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_start_launch_tc_send_struct(mavlink_channel_t chan, const mavlink_start_launch_tc_t* start_launch_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_start_launch_tc_send(chan, start_launch_tc->launch_code);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_START_LAUNCH_TC, (const char *)start_launch_tc, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_START_LAUNCH_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_start_launch_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t launch_code)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, launch_code);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_START_LAUNCH_TC, buf, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-#else
- mavlink_start_launch_tc_t *packet = (mavlink_start_launch_tc_t *)msgbuf;
- packet->launch_code = launch_code;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_START_LAUNCH_TC, (const char *)packet, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE START_LAUNCH_TC UNPACKING
-
-
-/**
- * @brief Get field launch_code from start_launch_tc message
- *
- * @return 64bit launch code.
- */
-static inline uint64_t mavlink_msg_start_launch_tc_get_launch_code(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Decode a start_launch_tc message into a struct
- *
- * @param msg The message to decode
- * @param start_launch_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_start_launch_tc_decode(const mavlink_message_t* msg, mavlink_start_launch_tc_t* start_launch_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- start_launch_tc->launch_code = mavlink_msg_start_launch_tc_get_launch_code(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_START_LAUNCH_TC_LEN? msg->len : MAVLINK_MSG_ID_START_LAUNCH_TC_LEN;
- memset(start_launch_tc, 0, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN);
- memcpy(start_launch_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_sys_tm.h b/mavlink_lib/hermes/mavlink_msg_sys_tm.h
deleted file mode 100644
index f6919010929ea75c093cead2c6833a2f3f368eeb..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_sys_tm.h
+++ /dev/null
@@ -1,463 +0,0 @@
-#pragma once
-// MESSAGE SYS_TM PACKING
-
-#define MAVLINK_MSG_ID_SYS_TM 160
-
-MAVPACKED(
-typedef struct __mavlink_sys_tm_t {
- uint64_t timestamp; /*< Timestamp*/
- uint8_t death_stack; /*< */
- uint8_t logger; /*< */
- uint8_t ev_broker; /*< */
- uint8_t pin_obs; /*< */
- uint8_t fmm; /*< */
- uint8_t sensor_manager; /*< */
- uint8_t ada; /*< */
- uint8_t tmtc; /*< */
- uint8_t ign; /*< */
- uint8_t dpl; /*< */
-}) mavlink_sys_tm_t;
-
-#define MAVLINK_MSG_ID_SYS_TM_LEN 18
-#define MAVLINK_MSG_ID_SYS_TM_MIN_LEN 18
-#define MAVLINK_MSG_ID_160_LEN 18
-#define MAVLINK_MSG_ID_160_MIN_LEN 18
-
-#define MAVLINK_MSG_ID_SYS_TM_CRC 191
-#define MAVLINK_MSG_ID_160_CRC 191
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SYS_TM { \
- 160, \
- "SYS_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_sys_tm_t, timestamp) }, \
- { "death_stack", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_sys_tm_t, death_stack) }, \
- { "logger", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_sys_tm_t, logger) }, \
- { "ev_broker", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_sys_tm_t, ev_broker) }, \
- { "pin_obs", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_sys_tm_t, pin_obs) }, \
- { "fmm", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_sys_tm_t, fmm) }, \
- { "sensor_manager", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_sys_tm_t, sensor_manager) }, \
- { "ada", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_sys_tm_t, ada) }, \
- { "tmtc", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_sys_tm_t, tmtc) }, \
- { "ign", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_sys_tm_t, ign) }, \
- { "dpl", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_sys_tm_t, dpl) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SYS_TM { \
- "SYS_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_sys_tm_t, timestamp) }, \
- { "death_stack", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_sys_tm_t, death_stack) }, \
- { "logger", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_sys_tm_t, logger) }, \
- { "ev_broker", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_sys_tm_t, ev_broker) }, \
- { "pin_obs", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_sys_tm_t, pin_obs) }, \
- { "fmm", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_sys_tm_t, fmm) }, \
- { "sensor_manager", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_sys_tm_t, sensor_manager) }, \
- { "ada", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_sys_tm_t, ada) }, \
- { "tmtc", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_sys_tm_t, tmtc) }, \
- { "ign", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_sys_tm_t, ign) }, \
- { "dpl", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_sys_tm_t, dpl) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a sys_tm 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 Timestamp
- * @param death_stack
- * @param logger
- * @param ev_broker
- * @param pin_obs
- * @param fmm
- * @param sensor_manager
- * @param ada
- * @param tmtc
- * @param ign
- * @param dpl
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sys_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t death_stack, uint8_t logger, uint8_t ev_broker, uint8_t pin_obs, uint8_t fmm, uint8_t sensor_manager, uint8_t ada, uint8_t tmtc, uint8_t ign, uint8_t dpl)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, death_stack);
- _mav_put_uint8_t(buf, 9, logger);
- _mav_put_uint8_t(buf, 10, ev_broker);
- _mav_put_uint8_t(buf, 11, pin_obs);
- _mav_put_uint8_t(buf, 12, fmm);
- _mav_put_uint8_t(buf, 13, sensor_manager);
- _mav_put_uint8_t(buf, 14, ada);
- _mav_put_uint8_t(buf, 15, tmtc);
- _mav_put_uint8_t(buf, 16, ign);
- _mav_put_uint8_t(buf, 17, dpl);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_TM_LEN);
-#else
- mavlink_sys_tm_t packet;
- packet.timestamp = timestamp;
- packet.death_stack = death_stack;
- packet.logger = logger;
- packet.ev_broker = ev_broker;
- packet.pin_obs = pin_obs;
- packet.fmm = fmm;
- packet.sensor_manager = sensor_manager;
- packet.ada = ada;
- packet.tmtc = tmtc;
- packet.ign = ign;
- packet.dpl = dpl;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SYS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-}
-
-/**
- * @brief Pack a sys_tm 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 Timestamp
- * @param death_stack
- * @param logger
- * @param ev_broker
- * @param pin_obs
- * @param fmm
- * @param sensor_manager
- * @param ada
- * @param tmtc
- * @param ign
- * @param dpl
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sys_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t death_stack,uint8_t logger,uint8_t ev_broker,uint8_t pin_obs,uint8_t fmm,uint8_t sensor_manager,uint8_t ada,uint8_t tmtc,uint8_t ign,uint8_t dpl)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, death_stack);
- _mav_put_uint8_t(buf, 9, logger);
- _mav_put_uint8_t(buf, 10, ev_broker);
- _mav_put_uint8_t(buf, 11, pin_obs);
- _mav_put_uint8_t(buf, 12, fmm);
- _mav_put_uint8_t(buf, 13, sensor_manager);
- _mav_put_uint8_t(buf, 14, ada);
- _mav_put_uint8_t(buf, 15, tmtc);
- _mav_put_uint8_t(buf, 16, ign);
- _mav_put_uint8_t(buf, 17, dpl);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_TM_LEN);
-#else
- mavlink_sys_tm_t packet;
- packet.timestamp = timestamp;
- packet.death_stack = death_stack;
- packet.logger = logger;
- packet.ev_broker = ev_broker;
- packet.pin_obs = pin_obs;
- packet.fmm = fmm;
- packet.sensor_manager = sensor_manager;
- packet.ada = ada;
- packet.tmtc = tmtc;
- packet.ign = ign;
- packet.dpl = dpl;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SYS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-}
-
-/**
- * @brief Encode a sys_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sys_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_tm_t* sys_tm)
-{
- return mavlink_msg_sys_tm_pack(system_id, component_id, msg, sys_tm->timestamp, sys_tm->death_stack, sys_tm->logger, sys_tm->ev_broker, sys_tm->pin_obs, sys_tm->fmm, sys_tm->sensor_manager, sys_tm->ada, sys_tm->tmtc, sys_tm->ign, sys_tm->dpl);
-}
-
-/**
- * @brief Encode a sys_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sys_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sys_tm_t* sys_tm)
-{
- return mavlink_msg_sys_tm_pack_chan(system_id, component_id, chan, msg, sys_tm->timestamp, sys_tm->death_stack, sys_tm->logger, sys_tm->ev_broker, sys_tm->pin_obs, sys_tm->fmm, sys_tm->sensor_manager, sys_tm->ada, sys_tm->tmtc, sys_tm->ign, sys_tm->dpl);
-}
-
-/**
- * @brief Send a sys_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp Timestamp
- * @param death_stack
- * @param logger
- * @param ev_broker
- * @param pin_obs
- * @param fmm
- * @param sensor_manager
- * @param ada
- * @param tmtc
- * @param ign
- * @param dpl
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_sys_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t death_stack, uint8_t logger, uint8_t ev_broker, uint8_t pin_obs, uint8_t fmm, uint8_t sensor_manager, uint8_t ada, uint8_t tmtc, uint8_t ign, uint8_t dpl)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, death_stack);
- _mav_put_uint8_t(buf, 9, logger);
- _mav_put_uint8_t(buf, 10, ev_broker);
- _mav_put_uint8_t(buf, 11, pin_obs);
- _mav_put_uint8_t(buf, 12, fmm);
- _mav_put_uint8_t(buf, 13, sensor_manager);
- _mav_put_uint8_t(buf, 14, ada);
- _mav_put_uint8_t(buf, 15, tmtc);
- _mav_put_uint8_t(buf, 16, ign);
- _mav_put_uint8_t(buf, 17, dpl);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, buf, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#else
- mavlink_sys_tm_t packet;
- packet.timestamp = timestamp;
- packet.death_stack = death_stack;
- packet.logger = logger;
- packet.ev_broker = ev_broker;
- packet.pin_obs = pin_obs;
- packet.fmm = fmm;
- packet.sensor_manager = sensor_manager;
- packet.ada = ada;
- packet.tmtc = tmtc;
- packet.ign = ign;
- packet.dpl = dpl;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, (const char *)&packet, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a sys_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_sys_tm_send_struct(mavlink_channel_t chan, const mavlink_sys_tm_t* sys_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_sys_tm_send(chan, sys_tm->timestamp, sys_tm->death_stack, sys_tm->logger, sys_tm->ev_broker, sys_tm->pin_obs, sys_tm->fmm, sys_tm->sensor_manager, sys_tm->ada, sys_tm->tmtc, sys_tm->ign, sys_tm->dpl);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, (const char *)sys_tm, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SYS_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t death_stack, uint8_t logger, uint8_t ev_broker, uint8_t pin_obs, uint8_t fmm, uint8_t sensor_manager, uint8_t ada, uint8_t tmtc, uint8_t ign, uint8_t dpl)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, death_stack);
- _mav_put_uint8_t(buf, 9, logger);
- _mav_put_uint8_t(buf, 10, ev_broker);
- _mav_put_uint8_t(buf, 11, pin_obs);
- _mav_put_uint8_t(buf, 12, fmm);
- _mav_put_uint8_t(buf, 13, sensor_manager);
- _mav_put_uint8_t(buf, 14, ada);
- _mav_put_uint8_t(buf, 15, tmtc);
- _mav_put_uint8_t(buf, 16, ign);
- _mav_put_uint8_t(buf, 17, dpl);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, buf, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#else
- mavlink_sys_tm_t *packet = (mavlink_sys_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->death_stack = death_stack;
- packet->logger = logger;
- packet->ev_broker = ev_broker;
- packet->pin_obs = pin_obs;
- packet->fmm = fmm;
- packet->sensor_manager = sensor_manager;
- packet->ada = ada;
- packet->tmtc = tmtc;
- packet->ign = ign;
- packet->dpl = dpl;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, (const char *)packet, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SYS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from sys_tm message
- *
- * @return Timestamp
- */
-static inline uint64_t mavlink_msg_sys_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field death_stack from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_death_stack(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 8);
-}
-
-/**
- * @brief Get field logger from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_logger(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 9);
-}
-
-/**
- * @brief Get field ev_broker from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_ev_broker(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 10);
-}
-
-/**
- * @brief Get field pin_obs from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_pin_obs(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 11);
-}
-
-/**
- * @brief Get field fmm from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_fmm(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 12);
-}
-
-/**
- * @brief Get field sensor_manager from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_sensor_manager(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 13);
-}
-
-/**
- * @brief Get field ada from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_ada(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 14);
-}
-
-/**
- * @brief Get field tmtc from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_tmtc(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 15);
-}
-
-/**
- * @brief Get field ign from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_ign(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 16);
-}
-
-/**
- * @brief Get field dpl from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_dpl(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 17);
-}
-
-/**
- * @brief Decode a sys_tm message into a struct
- *
- * @param msg The message to decode
- * @param sys_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_sys_tm_decode(const mavlink_message_t* msg, mavlink_sys_tm_t* sys_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- sys_tm->timestamp = mavlink_msg_sys_tm_get_timestamp(msg);
- sys_tm->death_stack = mavlink_msg_sys_tm_get_death_stack(msg);
- sys_tm->logger = mavlink_msg_sys_tm_get_logger(msg);
- sys_tm->ev_broker = mavlink_msg_sys_tm_get_ev_broker(msg);
- sys_tm->pin_obs = mavlink_msg_sys_tm_get_pin_obs(msg);
- sys_tm->fmm = mavlink_msg_sys_tm_get_fmm(msg);
- sys_tm->sensor_manager = mavlink_msg_sys_tm_get_sensor_manager(msg);
- sys_tm->ada = mavlink_msg_sys_tm_get_ada(msg);
- sys_tm->tmtc = mavlink_msg_sys_tm_get_tmtc(msg);
- sys_tm->ign = mavlink_msg_sys_tm_get_ign(msg);
- sys_tm->dpl = mavlink_msg_sys_tm_get_dpl(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SYS_TM_LEN? msg->len : MAVLINK_MSG_ID_SYS_TM_LEN;
- memset(sys_tm, 0, MAVLINK_MSG_ID_SYS_TM_LEN);
- memcpy(sys_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_telemetry_request_tc.h b/mavlink_lib/hermes/mavlink_msg_telemetry_request_tc.h
deleted file mode 100644
index 4d5b9d5f110dcd3f2f60f581f306893be2b19cb5..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_telemetry_request_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE TELEMETRY_REQUEST_TC PACKING
-
-#define MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC 30
-
-MAVPACKED(
-typedef struct __mavlink_telemetry_request_tc_t {
- uint8_t board_id; /*< A member of the MavTMList enum.*/
-}) mavlink_telemetry_request_tc_t;
-
-#define MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN 1
-#define MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_30_LEN 1
-#define MAVLINK_MSG_ID_30_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC 105
-#define MAVLINK_MSG_ID_30_CRC 105
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_TELEMETRY_REQUEST_TC { \
- 30, \
- "TELEMETRY_REQUEST_TC", \
- 1, \
- { { "board_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_telemetry_request_tc_t, board_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_TELEMETRY_REQUEST_TC { \
- "TELEMETRY_REQUEST_TC", \
- 1, \
- { { "board_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_telemetry_request_tc_t, board_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a telemetry_request_tc 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 board_id A member of the MavTMList enum.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_telemetry_request_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t board_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, board_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN);
-#else
- mavlink_telemetry_request_tc_t packet;
- packet.board_id = board_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Pack a telemetry_request_tc 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 board_id A member of the MavTMList enum.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_telemetry_request_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t board_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, board_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN);
-#else
- mavlink_telemetry_request_tc_t packet;
- packet.board_id = board_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Encode a telemetry_request_tc 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 telemetry_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_telemetry_request_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_telemetry_request_tc_t* telemetry_request_tc)
-{
- return mavlink_msg_telemetry_request_tc_pack(system_id, component_id, msg, telemetry_request_tc->board_id);
-}
-
-/**
- * @brief Encode a telemetry_request_tc 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 telemetry_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_telemetry_request_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_telemetry_request_tc_t* telemetry_request_tc)
-{
- return mavlink_msg_telemetry_request_tc_pack_chan(system_id, component_id, chan, msg, telemetry_request_tc->board_id);
-}
-
-/**
- * @brief Send a telemetry_request_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param board_id A member of the MavTMList enum.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_telemetry_request_tc_send(mavlink_channel_t chan, uint8_t board_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, board_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC, buf, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-#else
- mavlink_telemetry_request_tc_t packet;
- packet.board_id = board_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC, (const char *)&packet, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a telemetry_request_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_telemetry_request_tc_send_struct(mavlink_channel_t chan, const mavlink_telemetry_request_tc_t* telemetry_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_telemetry_request_tc_send(chan, telemetry_request_tc->board_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC, (const char *)telemetry_request_tc, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_telemetry_request_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t board_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, board_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC, buf, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-#else
- mavlink_telemetry_request_tc_t *packet = (mavlink_telemetry_request_tc_t *)msgbuf;
- packet->board_id = board_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC, (const char *)packet, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE TELEMETRY_REQUEST_TC UNPACKING
-
-
-/**
- * @brief Get field board_id from telemetry_request_tc message
- *
- * @return A member of the MavTMList enum.
- */
-static inline uint8_t mavlink_msg_telemetry_request_tc_get_board_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a telemetry_request_tc message into a struct
- *
- * @param msg The message to decode
- * @param telemetry_request_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_telemetry_request_tc_decode(const mavlink_message_t* msg, mavlink_telemetry_request_tc_t* telemetry_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- telemetry_request_tc->board_id = mavlink_msg_telemetry_request_tc_get_board_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN? msg->len : MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN;
- memset(telemetry_request_tc, 0, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN);
- memcpy(telemetry_request_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_test_tm.h b/mavlink_lib/hermes/mavlink_msg_test_tm.h
deleted file mode 100644
index 45403517e0976ee3726b9c49e476096470a6e7bc..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_test_tm.h
+++ /dev/null
@@ -1,388 +0,0 @@
-#pragma once
-// MESSAGE TEST_TM PACKING
-
-#define MAVLINK_MSG_ID_TEST_TM 182
-
-MAVPACKED(
-typedef struct __mavlink_test_tm_t {
- uint32_t timestamp; /*< When was this logged (mission clock)*/
- float pressure_hw; /*< Raw pressure from the HoneyWell barometer*/
- float temp_analog; /*< LM75B Analog board temperature*/
- float temp_imu; /*< LM75B IMU board temperature*/
- float battery_volt; /*< Battery voltage*/
- float th_cut_1; /*< Thermal cutter 1 reading*/
- float th_cut_2; /*< Thermal cutter 2 reading*/
- uint8_t gps_nsats; /*< GPS num sats*/
-}) mavlink_test_tm_t;
-
-#define MAVLINK_MSG_ID_TEST_TM_LEN 29
-#define MAVLINK_MSG_ID_TEST_TM_MIN_LEN 29
-#define MAVLINK_MSG_ID_182_LEN 29
-#define MAVLINK_MSG_ID_182_MIN_LEN 29
-
-#define MAVLINK_MSG_ID_TEST_TM_CRC 126
-#define MAVLINK_MSG_ID_182_CRC 126
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_TEST_TM { \
- 182, \
- "TEST_TM", \
- 8, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_test_tm_t, timestamp) }, \
- { "pressure_hw", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_test_tm_t, pressure_hw) }, \
- { "gps_nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_test_tm_t, gps_nsats) }, \
- { "temp_analog", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_test_tm_t, temp_analog) }, \
- { "temp_imu", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_test_tm_t, temp_imu) }, \
- { "battery_volt", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_test_tm_t, battery_volt) }, \
- { "th_cut_1", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_test_tm_t, th_cut_1) }, \
- { "th_cut_2", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_test_tm_t, th_cut_2) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_TEST_TM { \
- "TEST_TM", \
- 8, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_test_tm_t, timestamp) }, \
- { "pressure_hw", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_test_tm_t, pressure_hw) }, \
- { "gps_nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_test_tm_t, gps_nsats) }, \
- { "temp_analog", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_test_tm_t, temp_analog) }, \
- { "temp_imu", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_test_tm_t, temp_imu) }, \
- { "battery_volt", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_test_tm_t, battery_volt) }, \
- { "th_cut_1", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_test_tm_t, th_cut_1) }, \
- { "th_cut_2", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_test_tm_t, th_cut_2) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a test_tm 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 When was this logged (mission clock)
- * @param pressure_hw Raw pressure from the HoneyWell barometer
- * @param gps_nsats GPS num sats
- * @param temp_analog LM75B Analog board temperature
- * @param temp_imu LM75B IMU board temperature
- * @param battery_volt Battery voltage
- * @param th_cut_1 Thermal cutter 1 reading
- * @param th_cut_2 Thermal cutter 2 reading
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_test_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint32_t timestamp, float pressure_hw, uint8_t gps_nsats, float temp_analog, float temp_imu, float battery_volt, float th_cut_1, float th_cut_2)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TEST_TM_LEN];
- _mav_put_uint32_t(buf, 0, timestamp);
- _mav_put_float(buf, 4, pressure_hw);
- _mav_put_float(buf, 8, temp_analog);
- _mav_put_float(buf, 12, temp_imu);
- _mav_put_float(buf, 16, battery_volt);
- _mav_put_float(buf, 20, th_cut_1);
- _mav_put_float(buf, 24, th_cut_2);
- _mav_put_uint8_t(buf, 28, gps_nsats);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TEST_TM_LEN);
-#else
- mavlink_test_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_hw = pressure_hw;
- packet.temp_analog = temp_analog;
- packet.temp_imu = temp_imu;
- packet.battery_volt = battery_volt;
- packet.th_cut_1 = th_cut_1;
- packet.th_cut_2 = th_cut_2;
- packet.gps_nsats = gps_nsats;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TEST_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TEST_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TEST_TM_MIN_LEN, MAVLINK_MSG_ID_TEST_TM_LEN, MAVLINK_MSG_ID_TEST_TM_CRC);
-}
-
-/**
- * @brief Pack a test_tm 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 When was this logged (mission clock)
- * @param pressure_hw Raw pressure from the HoneyWell barometer
- * @param gps_nsats GPS num sats
- * @param temp_analog LM75B Analog board temperature
- * @param temp_imu LM75B IMU board temperature
- * @param battery_volt Battery voltage
- * @param th_cut_1 Thermal cutter 1 reading
- * @param th_cut_2 Thermal cutter 2 reading
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_test_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint32_t timestamp,float pressure_hw,uint8_t gps_nsats,float temp_analog,float temp_imu,float battery_volt,float th_cut_1,float th_cut_2)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TEST_TM_LEN];
- _mav_put_uint32_t(buf, 0, timestamp);
- _mav_put_float(buf, 4, pressure_hw);
- _mav_put_float(buf, 8, temp_analog);
- _mav_put_float(buf, 12, temp_imu);
- _mav_put_float(buf, 16, battery_volt);
- _mav_put_float(buf, 20, th_cut_1);
- _mav_put_float(buf, 24, th_cut_2);
- _mav_put_uint8_t(buf, 28, gps_nsats);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TEST_TM_LEN);
-#else
- mavlink_test_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_hw = pressure_hw;
- packet.temp_analog = temp_analog;
- packet.temp_imu = temp_imu;
- packet.battery_volt = battery_volt;
- packet.th_cut_1 = th_cut_1;
- packet.th_cut_2 = th_cut_2;
- packet.gps_nsats = gps_nsats;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TEST_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TEST_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TEST_TM_MIN_LEN, MAVLINK_MSG_ID_TEST_TM_LEN, MAVLINK_MSG_ID_TEST_TM_CRC);
-}
-
-/**
- * @brief Encode a test_tm 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 test_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_test_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_test_tm_t* test_tm)
-{
- return mavlink_msg_test_tm_pack(system_id, component_id, msg, test_tm->timestamp, test_tm->pressure_hw, test_tm->gps_nsats, test_tm->temp_analog, test_tm->temp_imu, test_tm->battery_volt, test_tm->th_cut_1, test_tm->th_cut_2);
-}
-
-/**
- * @brief Encode a test_tm 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 test_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_test_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_test_tm_t* test_tm)
-{
- return mavlink_msg_test_tm_pack_chan(system_id, component_id, chan, msg, test_tm->timestamp, test_tm->pressure_hw, test_tm->gps_nsats, test_tm->temp_analog, test_tm->temp_imu, test_tm->battery_volt, test_tm->th_cut_1, test_tm->th_cut_2);
-}
-
-/**
- * @brief Send a test_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp When was this logged (mission clock)
- * @param pressure_hw Raw pressure from the HoneyWell barometer
- * @param gps_nsats GPS num sats
- * @param temp_analog LM75B Analog board temperature
- * @param temp_imu LM75B IMU board temperature
- * @param battery_volt Battery voltage
- * @param th_cut_1 Thermal cutter 1 reading
- * @param th_cut_2 Thermal cutter 2 reading
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_test_tm_send(mavlink_channel_t chan, uint32_t timestamp, float pressure_hw, uint8_t gps_nsats, float temp_analog, float temp_imu, float battery_volt, float th_cut_1, float th_cut_2)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TEST_TM_LEN];
- _mav_put_uint32_t(buf, 0, timestamp);
- _mav_put_float(buf, 4, pressure_hw);
- _mav_put_float(buf, 8, temp_analog);
- _mav_put_float(buf, 12, temp_imu);
- _mav_put_float(buf, 16, battery_volt);
- _mav_put_float(buf, 20, th_cut_1);
- _mav_put_float(buf, 24, th_cut_2);
- _mav_put_uint8_t(buf, 28, gps_nsats);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TM, buf, MAVLINK_MSG_ID_TEST_TM_MIN_LEN, MAVLINK_MSG_ID_TEST_TM_LEN, MAVLINK_MSG_ID_TEST_TM_CRC);
-#else
- mavlink_test_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_hw = pressure_hw;
- packet.temp_analog = temp_analog;
- packet.temp_imu = temp_imu;
- packet.battery_volt = battery_volt;
- packet.th_cut_1 = th_cut_1;
- packet.th_cut_2 = th_cut_2;
- packet.gps_nsats = gps_nsats;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TM, (const char *)&packet, MAVLINK_MSG_ID_TEST_TM_MIN_LEN, MAVLINK_MSG_ID_TEST_TM_LEN, MAVLINK_MSG_ID_TEST_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a test_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_test_tm_send_struct(mavlink_channel_t chan, const mavlink_test_tm_t* test_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_test_tm_send(chan, test_tm->timestamp, test_tm->pressure_hw, test_tm->gps_nsats, test_tm->temp_analog, test_tm->temp_imu, test_tm->battery_volt, test_tm->th_cut_1, test_tm->th_cut_2);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TM, (const char *)test_tm, MAVLINK_MSG_ID_TEST_TM_MIN_LEN, MAVLINK_MSG_ID_TEST_TM_LEN, MAVLINK_MSG_ID_TEST_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_TEST_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_test_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t timestamp, float pressure_hw, uint8_t gps_nsats, float temp_analog, float temp_imu, float battery_volt, float th_cut_1, float th_cut_2)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint32_t(buf, 0, timestamp);
- _mav_put_float(buf, 4, pressure_hw);
- _mav_put_float(buf, 8, temp_analog);
- _mav_put_float(buf, 12, temp_imu);
- _mav_put_float(buf, 16, battery_volt);
- _mav_put_float(buf, 20, th_cut_1);
- _mav_put_float(buf, 24, th_cut_2);
- _mav_put_uint8_t(buf, 28, gps_nsats);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TM, buf, MAVLINK_MSG_ID_TEST_TM_MIN_LEN, MAVLINK_MSG_ID_TEST_TM_LEN, MAVLINK_MSG_ID_TEST_TM_CRC);
-#else
- mavlink_test_tm_t *packet = (mavlink_test_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->pressure_hw = pressure_hw;
- packet->temp_analog = temp_analog;
- packet->temp_imu = temp_imu;
- packet->battery_volt = battery_volt;
- packet->th_cut_1 = th_cut_1;
- packet->th_cut_2 = th_cut_2;
- packet->gps_nsats = gps_nsats;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TM, (const char *)packet, MAVLINK_MSG_ID_TEST_TM_MIN_LEN, MAVLINK_MSG_ID_TEST_TM_LEN, MAVLINK_MSG_ID_TEST_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE TEST_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from test_tm message
- *
- * @return When was this logged (mission clock)
- */
-static inline uint32_t mavlink_msg_test_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 0);
-}
-
-/**
- * @brief Get field pressure_hw from test_tm message
- *
- * @return Raw pressure from the HoneyWell barometer
- */
-static inline float mavlink_msg_test_tm_get_pressure_hw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 4);
-}
-
-/**
- * @brief Get field gps_nsats from test_tm message
- *
- * @return GPS num sats
- */
-static inline uint8_t mavlink_msg_test_tm_get_gps_nsats(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 28);
-}
-
-/**
- * @brief Get field temp_analog from test_tm message
- *
- * @return LM75B Analog board temperature
- */
-static inline float mavlink_msg_test_tm_get_temp_analog(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field temp_imu from test_tm message
- *
- * @return LM75B IMU board temperature
- */
-static inline float mavlink_msg_test_tm_get_temp_imu(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field battery_volt from test_tm message
- *
- * @return Battery voltage
- */
-static inline float mavlink_msg_test_tm_get_battery_volt(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field th_cut_1 from test_tm message
- *
- * @return Thermal cutter 1 reading
- */
-static inline float mavlink_msg_test_tm_get_th_cut_1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field th_cut_2 from test_tm message
- *
- * @return Thermal cutter 2 reading
- */
-static inline float mavlink_msg_test_tm_get_th_cut_2(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Decode a test_tm message into a struct
- *
- * @param msg The message to decode
- * @param test_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_test_tm_decode(const mavlink_message_t* msg, mavlink_test_tm_t* test_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- test_tm->timestamp = mavlink_msg_test_tm_get_timestamp(msg);
- test_tm->pressure_hw = mavlink_msg_test_tm_get_pressure_hw(msg);
- test_tm->temp_analog = mavlink_msg_test_tm_get_temp_analog(msg);
- test_tm->temp_imu = mavlink_msg_test_tm_get_temp_imu(msg);
- test_tm->battery_volt = mavlink_msg_test_tm_get_battery_volt(msg);
- test_tm->th_cut_1 = mavlink_msg_test_tm_get_th_cut_1(msg);
- test_tm->th_cut_2 = mavlink_msg_test_tm_get_th_cut_2(msg);
- test_tm->gps_nsats = mavlink_msg_test_tm_get_gps_nsats(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_TEST_TM_LEN? msg->len : MAVLINK_MSG_ID_TEST_TM_LEN;
- memset(test_tm, 0, MAVLINK_MSG_ID_TEST_TM_LEN);
- memcpy(test_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_tmtc_tm.h b/mavlink_lib/hermes/mavlink_msg_tmtc_tm.h
deleted file mode 100644
index 66ea140bdd93c3a4e393370f1da0fc6b78ed58fa..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_tmtc_tm.h
+++ /dev/null
@@ -1,513 +0,0 @@
-#pragma once
-// MESSAGE TMTC_TM PACKING
-
-#define MAVLINK_MSG_ID_TMTC_TM 163
-
-MAVPACKED(
-typedef struct __mavlink_tmtc_tm_t {
- uint64_t timestamp; /*< When was this logged */
- uint32_t parse_state; /*< Parsing state machine*/
- uint16_t n_send_queue; /*< Current len of the occupied portion of the queue*/
- uint16_t max_send_queue; /*< Max occupied len of the queue */
- uint16_t n_send_errors; /*< Number of packet not sent correctly by the TMTC*/
- uint16_t packet_rx_success_count; /*< Received packets*/
- uint16_t packet_rx_drop_count; /*< Number of packet drops */
- uint8_t msg_received; /*< Number of received messages*/
- uint8_t buffer_overrun; /*< Number of buffer overruns*/
- uint8_t parse_error; /*< Number of parse errors*/
- 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 */
-}) mavlink_tmtc_tm_t;
-
-#define MAVLINK_MSG_ID_TMTC_TM_LEN 28
-#define MAVLINK_MSG_ID_TMTC_TM_MIN_LEN 28
-#define MAVLINK_MSG_ID_163_LEN 28
-#define MAVLINK_MSG_ID_163_MIN_LEN 28
-
-#define MAVLINK_MSG_ID_TMTC_TM_CRC 164
-#define MAVLINK_MSG_ID_163_CRC 164
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_TMTC_TM { \
- 163, \
- "TMTC_TM", \
- 13, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_tmtc_tm_t, timestamp) }, \
- { "n_send_queue", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_tmtc_tm_t, n_send_queue) }, \
- { "max_send_queue", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_tmtc_tm_t, max_send_queue) }, \
- { "n_send_errors", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_tmtc_tm_t, n_send_errors) }, \
- { "msg_received", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_tmtc_tm_t, msg_received) }, \
- { "buffer_overrun", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_tmtc_tm_t, buffer_overrun) }, \
- { "parse_error", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_tmtc_tm_t, parse_error) }, \
- { "parse_state", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_tmtc_tm_t, parse_state) }, \
- { "packet_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_tmtc_tm_t, packet_idx) }, \
- { "current_rx_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_tmtc_tm_t, current_rx_seq) }, \
- { "current_tx_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_tmtc_tm_t, current_tx_seq) }, \
- { "packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_tmtc_tm_t, packet_rx_success_count) }, \
- { "packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_tmtc_tm_t, packet_rx_drop_count) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_TMTC_TM { \
- "TMTC_TM", \
- 13, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_tmtc_tm_t, timestamp) }, \
- { "n_send_queue", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_tmtc_tm_t, n_send_queue) }, \
- { "max_send_queue", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_tmtc_tm_t, max_send_queue) }, \
- { "n_send_errors", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_tmtc_tm_t, n_send_errors) }, \
- { "msg_received", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_tmtc_tm_t, msg_received) }, \
- { "buffer_overrun", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_tmtc_tm_t, buffer_overrun) }, \
- { "parse_error", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_tmtc_tm_t, parse_error) }, \
- { "parse_state", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_tmtc_tm_t, parse_state) }, \
- { "packet_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_tmtc_tm_t, packet_idx) }, \
- { "current_rx_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_tmtc_tm_t, current_rx_seq) }, \
- { "current_tx_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_tmtc_tm_t, current_tx_seq) }, \
- { "packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_tmtc_tm_t, packet_rx_success_count) }, \
- { "packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_tmtc_tm_t, packet_rx_drop_count) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a tmtc_tm 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 When was this logged
- * @param n_send_queue Current len of the occupied portion of the queue
- * @param max_send_queue Max occupied len of the queue
- * @param n_send_errors Number of packet not sent correctly by the TMTC
- * @param msg_received Number of received messages
- * @param buffer_overrun Number of buffer overruns
- * @param parse_error Number of parse errors
- * @param parse_state Parsing state machine
- * @param packet_idx Index in current packet
- * @param current_rx_seq Sequence number of last packet received
- * @param current_tx_seq Sequence number of last packet sent
- * @param packet_rx_success_count Received packets
- * @param packet_rx_drop_count Number of packet drops
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_tmtc_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint16_t n_send_queue, uint16_t max_send_queue, uint16_t n_send_errors, uint8_t msg_received, uint8_t buffer_overrun, uint8_t parse_error, uint32_t parse_state, uint8_t packet_idx, uint8_t current_rx_seq, uint8_t current_tx_seq, uint16_t packet_rx_success_count, uint16_t packet_rx_drop_count)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TMTC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint32_t(buf, 8, parse_state);
- _mav_put_uint16_t(buf, 12, n_send_queue);
- _mav_put_uint16_t(buf, 14, max_send_queue);
- _mav_put_uint16_t(buf, 16, n_send_errors);
- _mav_put_uint16_t(buf, 18, packet_rx_success_count);
- _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
- _mav_put_uint8_t(buf, 22, msg_received);
- _mav_put_uint8_t(buf, 23, buffer_overrun);
- _mav_put_uint8_t(buf, 24, parse_error);
- _mav_put_uint8_t(buf, 25, packet_idx);
- _mav_put_uint8_t(buf, 26, current_rx_seq);
- _mav_put_uint8_t(buf, 27, current_tx_seq);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TMTC_TM_LEN);
-#else
- mavlink_tmtc_tm_t packet;
- packet.timestamp = timestamp;
- packet.parse_state = parse_state;
- packet.n_send_queue = n_send_queue;
- packet.max_send_queue = max_send_queue;
- packet.n_send_errors = n_send_errors;
- packet.packet_rx_success_count = packet_rx_success_count;
- packet.packet_rx_drop_count = packet_rx_drop_count;
- packet.msg_received = msg_received;
- packet.buffer_overrun = buffer_overrun;
- packet.parse_error = parse_error;
- packet.packet_idx = packet_idx;
- packet.current_rx_seq = current_rx_seq;
- packet.current_tx_seq = current_tx_seq;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TMTC_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TMTC_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TMTC_TM_MIN_LEN, MAVLINK_MSG_ID_TMTC_TM_LEN, MAVLINK_MSG_ID_TMTC_TM_CRC);
-}
-
-/**
- * @brief Pack a tmtc_tm 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 When was this logged
- * @param n_send_queue Current len of the occupied portion of the queue
- * @param max_send_queue Max occupied len of the queue
- * @param n_send_errors Number of packet not sent correctly by the TMTC
- * @param msg_received Number of received messages
- * @param buffer_overrun Number of buffer overruns
- * @param parse_error Number of parse errors
- * @param parse_state Parsing state machine
- * @param packet_idx Index in current packet
- * @param current_rx_seq Sequence number of last packet received
- * @param current_tx_seq Sequence number of last packet sent
- * @param packet_rx_success_count Received packets
- * @param packet_rx_drop_count Number of packet drops
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_tmtc_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint16_t n_send_queue,uint16_t max_send_queue,uint16_t n_send_errors,uint8_t msg_received,uint8_t buffer_overrun,uint8_t parse_error,uint32_t parse_state,uint8_t packet_idx,uint8_t current_rx_seq,uint8_t current_tx_seq,uint16_t packet_rx_success_count,uint16_t packet_rx_drop_count)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TMTC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint32_t(buf, 8, parse_state);
- _mav_put_uint16_t(buf, 12, n_send_queue);
- _mav_put_uint16_t(buf, 14, max_send_queue);
- _mav_put_uint16_t(buf, 16, n_send_errors);
- _mav_put_uint16_t(buf, 18, packet_rx_success_count);
- _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
- _mav_put_uint8_t(buf, 22, msg_received);
- _mav_put_uint8_t(buf, 23, buffer_overrun);
- _mav_put_uint8_t(buf, 24, parse_error);
- _mav_put_uint8_t(buf, 25, packet_idx);
- _mav_put_uint8_t(buf, 26, current_rx_seq);
- _mav_put_uint8_t(buf, 27, current_tx_seq);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TMTC_TM_LEN);
-#else
- mavlink_tmtc_tm_t packet;
- packet.timestamp = timestamp;
- packet.parse_state = parse_state;
- packet.n_send_queue = n_send_queue;
- packet.max_send_queue = max_send_queue;
- packet.n_send_errors = n_send_errors;
- packet.packet_rx_success_count = packet_rx_success_count;
- packet.packet_rx_drop_count = packet_rx_drop_count;
- packet.msg_received = msg_received;
- packet.buffer_overrun = buffer_overrun;
- packet.parse_error = parse_error;
- packet.packet_idx = packet_idx;
- packet.current_rx_seq = current_rx_seq;
- packet.current_tx_seq = current_tx_seq;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TMTC_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TMTC_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TMTC_TM_MIN_LEN, MAVLINK_MSG_ID_TMTC_TM_LEN, MAVLINK_MSG_ID_TMTC_TM_CRC);
-}
-
-/**
- * @brief Encode a tmtc_tm 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 tmtc_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_tmtc_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_tmtc_tm_t* tmtc_tm)
-{
- return mavlink_msg_tmtc_tm_pack(system_id, component_id, msg, tmtc_tm->timestamp, tmtc_tm->n_send_queue, tmtc_tm->max_send_queue, tmtc_tm->n_send_errors, tmtc_tm->msg_received, tmtc_tm->buffer_overrun, tmtc_tm->parse_error, tmtc_tm->parse_state, tmtc_tm->packet_idx, tmtc_tm->current_rx_seq, tmtc_tm->current_tx_seq, tmtc_tm->packet_rx_success_count, tmtc_tm->packet_rx_drop_count);
-}
-
-/**
- * @brief Encode a tmtc_tm 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 tmtc_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_tmtc_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_tmtc_tm_t* tmtc_tm)
-{
- return mavlink_msg_tmtc_tm_pack_chan(system_id, component_id, chan, msg, tmtc_tm->timestamp, tmtc_tm->n_send_queue, tmtc_tm->max_send_queue, tmtc_tm->n_send_errors, tmtc_tm->msg_received, tmtc_tm->buffer_overrun, tmtc_tm->parse_error, tmtc_tm->parse_state, tmtc_tm->packet_idx, tmtc_tm->current_rx_seq, tmtc_tm->current_tx_seq, tmtc_tm->packet_rx_success_count, tmtc_tm->packet_rx_drop_count);
-}
-
-/**
- * @brief Send a tmtc_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp When was this logged
- * @param n_send_queue Current len of the occupied portion of the queue
- * @param max_send_queue Max occupied len of the queue
- * @param n_send_errors Number of packet not sent correctly by the TMTC
- * @param msg_received Number of received messages
- * @param buffer_overrun Number of buffer overruns
- * @param parse_error Number of parse errors
- * @param parse_state Parsing state machine
- * @param packet_idx Index in current packet
- * @param current_rx_seq Sequence number of last packet received
- * @param current_tx_seq Sequence number of last packet sent
- * @param packet_rx_success_count Received packets
- * @param packet_rx_drop_count Number of packet drops
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_tmtc_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint16_t n_send_queue, uint16_t max_send_queue, uint16_t n_send_errors, uint8_t msg_received, uint8_t buffer_overrun, uint8_t parse_error, uint32_t parse_state, uint8_t packet_idx, uint8_t current_rx_seq, uint8_t current_tx_seq, uint16_t packet_rx_success_count, uint16_t packet_rx_drop_count)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TMTC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint32_t(buf, 8, parse_state);
- _mav_put_uint16_t(buf, 12, n_send_queue);
- _mav_put_uint16_t(buf, 14, max_send_queue);
- _mav_put_uint16_t(buf, 16, n_send_errors);
- _mav_put_uint16_t(buf, 18, packet_rx_success_count);
- _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
- _mav_put_uint8_t(buf, 22, msg_received);
- _mav_put_uint8_t(buf, 23, buffer_overrun);
- _mav_put_uint8_t(buf, 24, parse_error);
- _mav_put_uint8_t(buf, 25, packet_idx);
- _mav_put_uint8_t(buf, 26, current_rx_seq);
- _mav_put_uint8_t(buf, 27, current_tx_seq);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TMTC_TM, buf, MAVLINK_MSG_ID_TMTC_TM_MIN_LEN, MAVLINK_MSG_ID_TMTC_TM_LEN, MAVLINK_MSG_ID_TMTC_TM_CRC);
-#else
- mavlink_tmtc_tm_t packet;
- packet.timestamp = timestamp;
- packet.parse_state = parse_state;
- packet.n_send_queue = n_send_queue;
- packet.max_send_queue = max_send_queue;
- packet.n_send_errors = n_send_errors;
- packet.packet_rx_success_count = packet_rx_success_count;
- packet.packet_rx_drop_count = packet_rx_drop_count;
- packet.msg_received = msg_received;
- packet.buffer_overrun = buffer_overrun;
- packet.parse_error = parse_error;
- packet.packet_idx = packet_idx;
- packet.current_rx_seq = current_rx_seq;
- packet.current_tx_seq = current_tx_seq;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TMTC_TM, (const char *)&packet, MAVLINK_MSG_ID_TMTC_TM_MIN_LEN, MAVLINK_MSG_ID_TMTC_TM_LEN, MAVLINK_MSG_ID_TMTC_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a tmtc_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_tmtc_tm_send_struct(mavlink_channel_t chan, const mavlink_tmtc_tm_t* tmtc_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_tmtc_tm_send(chan, tmtc_tm->timestamp, tmtc_tm->n_send_queue, tmtc_tm->max_send_queue, tmtc_tm->n_send_errors, tmtc_tm->msg_received, tmtc_tm->buffer_overrun, tmtc_tm->parse_error, tmtc_tm->parse_state, tmtc_tm->packet_idx, tmtc_tm->current_rx_seq, tmtc_tm->current_tx_seq, tmtc_tm->packet_rx_success_count, tmtc_tm->packet_rx_drop_count);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TMTC_TM, (const char *)tmtc_tm, MAVLINK_MSG_ID_TMTC_TM_MIN_LEN, MAVLINK_MSG_ID_TMTC_TM_LEN, MAVLINK_MSG_ID_TMTC_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_TMTC_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_tmtc_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint16_t n_send_queue, uint16_t max_send_queue, uint16_t n_send_errors, uint8_t msg_received, uint8_t buffer_overrun, uint8_t parse_error, uint32_t parse_state, uint8_t packet_idx, uint8_t current_rx_seq, uint8_t current_tx_seq, uint16_t packet_rx_success_count, uint16_t packet_rx_drop_count)
-{
-#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, parse_state);
- _mav_put_uint16_t(buf, 12, n_send_queue);
- _mav_put_uint16_t(buf, 14, max_send_queue);
- _mav_put_uint16_t(buf, 16, n_send_errors);
- _mav_put_uint16_t(buf, 18, packet_rx_success_count);
- _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
- _mav_put_uint8_t(buf, 22, msg_received);
- _mav_put_uint8_t(buf, 23, buffer_overrun);
- _mav_put_uint8_t(buf, 24, parse_error);
- _mav_put_uint8_t(buf, 25, packet_idx);
- _mav_put_uint8_t(buf, 26, current_rx_seq);
- _mav_put_uint8_t(buf, 27, current_tx_seq);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TMTC_TM, buf, MAVLINK_MSG_ID_TMTC_TM_MIN_LEN, MAVLINK_MSG_ID_TMTC_TM_LEN, MAVLINK_MSG_ID_TMTC_TM_CRC);
-#else
- mavlink_tmtc_tm_t *packet = (mavlink_tmtc_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->parse_state = parse_state;
- packet->n_send_queue = n_send_queue;
- packet->max_send_queue = max_send_queue;
- packet->n_send_errors = n_send_errors;
- packet->packet_rx_success_count = packet_rx_success_count;
- packet->packet_rx_drop_count = packet_rx_drop_count;
- packet->msg_received = msg_received;
- packet->buffer_overrun = buffer_overrun;
- packet->parse_error = parse_error;
- packet->packet_idx = packet_idx;
- packet->current_rx_seq = current_rx_seq;
- packet->current_tx_seq = current_tx_seq;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TMTC_TM, (const char *)packet, MAVLINK_MSG_ID_TMTC_TM_MIN_LEN, MAVLINK_MSG_ID_TMTC_TM_LEN, MAVLINK_MSG_ID_TMTC_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE TMTC_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from tmtc_tm message
- *
- * @return When was this logged
- */
-static inline uint64_t mavlink_msg_tmtc_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field n_send_queue from tmtc_tm message
- *
- * @return Current len of the occupied portion of the queue
- */
-static inline uint16_t mavlink_msg_tmtc_tm_get_n_send_queue(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 12);
-}
-
-/**
- * @brief Get field max_send_queue from tmtc_tm message
- *
- * @return Max occupied len of the queue
- */
-static inline uint16_t mavlink_msg_tmtc_tm_get_max_send_queue(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 14);
-}
-
-/**
- * @brief Get field n_send_errors from tmtc_tm message
- *
- * @return Number of packet not sent correctly by the TMTC
- */
-static inline uint16_t mavlink_msg_tmtc_tm_get_n_send_errors(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 16);
-}
-
-/**
- * @brief Get field msg_received from tmtc_tm message
- *
- * @return Number of received messages
- */
-static inline uint8_t mavlink_msg_tmtc_tm_get_msg_received(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 22);
-}
-
-/**
- * @brief Get field buffer_overrun from tmtc_tm message
- *
- * @return Number of buffer overruns
- */
-static inline uint8_t mavlink_msg_tmtc_tm_get_buffer_overrun(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 23);
-}
-
-/**
- * @brief Get field parse_error from tmtc_tm message
- *
- * @return Number of parse errors
- */
-static inline uint8_t mavlink_msg_tmtc_tm_get_parse_error(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 24);
-}
-
-/**
- * @brief Get field parse_state from tmtc_tm message
- *
- * @return Parsing state machine
- */
-static inline uint32_t mavlink_msg_tmtc_tm_get_parse_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 8);
-}
-
-/**
- * @brief Get field packet_idx from tmtc_tm message
- *
- * @return Index in current packet
- */
-static inline uint8_t mavlink_msg_tmtc_tm_get_packet_idx(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 25);
-}
-
-/**
- * @brief Get field current_rx_seq from tmtc_tm message
- *
- * @return Sequence number of last packet received
- */
-static inline uint8_t mavlink_msg_tmtc_tm_get_current_rx_seq(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 26);
-}
-
-/**
- * @brief Get field current_tx_seq from tmtc_tm message
- *
- * @return Sequence number of last packet sent
- */
-static inline uint8_t mavlink_msg_tmtc_tm_get_current_tx_seq(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 27);
-}
-
-/**
- * @brief Get field packet_rx_success_count from tmtc_tm message
- *
- * @return Received packets
- */
-static inline uint16_t mavlink_msg_tmtc_tm_get_packet_rx_success_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 18);
-}
-
-/**
- * @brief Get field packet_rx_drop_count from tmtc_tm message
- *
- * @return Number of packet drops
- */
-static inline uint16_t mavlink_msg_tmtc_tm_get_packet_rx_drop_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 20);
-}
-
-/**
- * @brief Decode a tmtc_tm message into a struct
- *
- * @param msg The message to decode
- * @param tmtc_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_tmtc_tm_decode(const mavlink_message_t* msg, mavlink_tmtc_tm_t* tmtc_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- tmtc_tm->timestamp = mavlink_msg_tmtc_tm_get_timestamp(msg);
- tmtc_tm->parse_state = mavlink_msg_tmtc_tm_get_parse_state(msg);
- tmtc_tm->n_send_queue = mavlink_msg_tmtc_tm_get_n_send_queue(msg);
- tmtc_tm->max_send_queue = mavlink_msg_tmtc_tm_get_max_send_queue(msg);
- tmtc_tm->n_send_errors = mavlink_msg_tmtc_tm_get_n_send_errors(msg);
- tmtc_tm->packet_rx_success_count = mavlink_msg_tmtc_tm_get_packet_rx_success_count(msg);
- tmtc_tm->packet_rx_drop_count = mavlink_msg_tmtc_tm_get_packet_rx_drop_count(msg);
- tmtc_tm->msg_received = mavlink_msg_tmtc_tm_get_msg_received(msg);
- tmtc_tm->buffer_overrun = mavlink_msg_tmtc_tm_get_buffer_overrun(msg);
- tmtc_tm->parse_error = mavlink_msg_tmtc_tm_get_parse_error(msg);
- tmtc_tm->packet_idx = mavlink_msg_tmtc_tm_get_packet_idx(msg);
- tmtc_tm->current_rx_seq = mavlink_msg_tmtc_tm_get_current_rx_seq(msg);
- tmtc_tm->current_tx_seq = mavlink_msg_tmtc_tm_get_current_tx_seq(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_TMTC_TM_LEN? msg->len : MAVLINK_MSG_ID_TMTC_TM_LEN;
- memset(tmtc_tm, 0, MAVLINK_MSG_ID_TMTC_TM_LEN);
- memcpy(tmtc_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/mavlink_msg_upload_setting_tc.h b/mavlink_lib/hermes/mavlink_msg_upload_setting_tc.h
deleted file mode 100644
index ea3de324c7113b52bd0854f7f8bf9ac19683f98d..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/mavlink_msg_upload_setting_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE UPLOAD_SETTING_TC PACKING
-
-#define MAVLINK_MSG_ID_UPLOAD_SETTING_TC 21
-
-MAVPACKED(
-typedef struct __mavlink_upload_setting_tc_t {
- float setting; /*< The value of the setting to be uploaded*/
- uint8_t setting_id; /*< A member of the MavSettingList enum.*/
-}) mavlink_upload_setting_tc_t;
-
-#define MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN 5
-#define MAVLINK_MSG_ID_UPLOAD_SETTING_TC_MIN_LEN 5
-#define MAVLINK_MSG_ID_21_LEN 5
-#define MAVLINK_MSG_ID_21_MIN_LEN 5
-
-#define MAVLINK_MSG_ID_UPLOAD_SETTING_TC_CRC 90
-#define MAVLINK_MSG_ID_21_CRC 90
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_UPLOAD_SETTING_TC { \
- 21, \
- "UPLOAD_SETTING_TC", \
- 2, \
- { { "setting_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_upload_setting_tc_t, setting_id) }, \
- { "setting", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_upload_setting_tc_t, setting) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_UPLOAD_SETTING_TC { \
- "UPLOAD_SETTING_TC", \
- 2, \
- { { "setting_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_upload_setting_tc_t, setting_id) }, \
- { "setting", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_upload_setting_tc_t, setting) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a upload_setting_tc 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 setting_id A member of the MavSettingList enum.
- * @param setting The value of the setting to be uploaded
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_upload_setting_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t setting_id, float setting)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN];
- _mav_put_float(buf, 0, setting);
- _mav_put_uint8_t(buf, 4, setting_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN);
-#else
- mavlink_upload_setting_tc_t packet;
- packet.setting = setting;
- packet.setting_id = setting_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_UPLOAD_SETTING_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_MIN_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_CRC);
-}
-
-/**
- * @brief Pack a upload_setting_tc 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 setting_id A member of the MavSettingList enum.
- * @param setting The value of the setting to be uploaded
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_upload_setting_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t setting_id,float setting)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN];
- _mav_put_float(buf, 0, setting);
- _mav_put_uint8_t(buf, 4, setting_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN);
-#else
- mavlink_upload_setting_tc_t packet;
- packet.setting = setting;
- packet.setting_id = setting_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_UPLOAD_SETTING_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_MIN_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_CRC);
-}
-
-/**
- * @brief Encode a upload_setting_tc 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 upload_setting_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_upload_setting_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_upload_setting_tc_t* upload_setting_tc)
-{
- return mavlink_msg_upload_setting_tc_pack(system_id, component_id, msg, upload_setting_tc->setting_id, upload_setting_tc->setting);
-}
-
-/**
- * @brief Encode a upload_setting_tc 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 upload_setting_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_upload_setting_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_upload_setting_tc_t* upload_setting_tc)
-{
- return mavlink_msg_upload_setting_tc_pack_chan(system_id, component_id, chan, msg, upload_setting_tc->setting_id, upload_setting_tc->setting);
-}
-
-/**
- * @brief Send a upload_setting_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param setting_id A member of the MavSettingList enum.
- * @param setting The value of the setting to be uploaded
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_upload_setting_tc_send(mavlink_channel_t chan, uint8_t setting_id, float setting)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN];
- _mav_put_float(buf, 0, setting);
- _mav_put_uint8_t(buf, 4, setting_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UPLOAD_SETTING_TC, buf, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_MIN_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_CRC);
-#else
- mavlink_upload_setting_tc_t packet;
- packet.setting = setting;
- packet.setting_id = setting_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UPLOAD_SETTING_TC, (const char *)&packet, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_MIN_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a upload_setting_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_upload_setting_tc_send_struct(mavlink_channel_t chan, const mavlink_upload_setting_tc_t* upload_setting_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_upload_setting_tc_send(chan, upload_setting_tc->setting_id, upload_setting_tc->setting);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UPLOAD_SETTING_TC, (const char *)upload_setting_tc, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_MIN_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_upload_setting_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t setting_id, float setting)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, setting);
- _mav_put_uint8_t(buf, 4, setting_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UPLOAD_SETTING_TC, buf, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_MIN_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_CRC);
-#else
- mavlink_upload_setting_tc_t *packet = (mavlink_upload_setting_tc_t *)msgbuf;
- packet->setting = setting;
- packet->setting_id = setting_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UPLOAD_SETTING_TC, (const char *)packet, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_MIN_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE UPLOAD_SETTING_TC UNPACKING
-
-
-/**
- * @brief Get field setting_id from upload_setting_tc message
- *
- * @return A member of the MavSettingList enum.
- */
-static inline uint8_t mavlink_msg_upload_setting_tc_get_setting_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 4);
-}
-
-/**
- * @brief Get field setting from upload_setting_tc message
- *
- * @return The value of the setting to be uploaded
- */
-static inline float mavlink_msg_upload_setting_tc_get_setting(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a upload_setting_tc message into a struct
- *
- * @param msg The message to decode
- * @param upload_setting_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_upload_setting_tc_decode(const mavlink_message_t* msg, mavlink_upload_setting_tc_t* upload_setting_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- upload_setting_tc->setting = mavlink_msg_upload_setting_tc_get_setting(msg);
- upload_setting_tc->setting_id = mavlink_msg_upload_setting_tc_get_setting_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN? msg->len : MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN;
- memset(upload_setting_tc, 0, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN);
- memcpy(upload_setting_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/hermes/testsuite.h b/mavlink_lib/hermes/testsuite.h
deleted file mode 100644
index 39b59b192748e81c5718380dfd6a0fc30d533014..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/testsuite.h
+++ /dev/null
@@ -1,1491 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol testsuite generated from hermes.xml
- * @see http://qgroundcontrol.org/mavlink/
- */
-#pragma once
-#ifndef HERMES_TESTSUITE_H
-#define HERMES_TESTSUITE_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#ifndef MAVLINK_TEST_ALL
-#define MAVLINK_TEST_ALL
-
-static void mavlink_test_hermes(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_hermes(system_id, component_id, last_msg);
-}
-#endif
-
-
-
-
-static void mavlink_test_ping_tc(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_PING_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ping_tc_t packet_in = {
- 93372036854775807ULL
- };
- mavlink_ping_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_PING_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PING_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ping_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_pack(system_id, component_id, &msg , packet1.timestamp );
- mavlink_msg_ping_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp );
- mavlink_msg_ping_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ping_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_send(MAVLINK_COMM_1 , packet1.timestamp );
- mavlink_msg_ping_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_noarg_tc(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_NOARG_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_noarg_tc_t packet_in = {
- 5
- };
- mavlink_noarg_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.command_id = packet_in.command_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_NOARG_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NOARG_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_noarg_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_noarg_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_noarg_tc_pack(system_id, component_id, &msg , packet1.command_id );
- mavlink_msg_noarg_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_noarg_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.command_id );
- mavlink_msg_noarg_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_noarg_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_noarg_tc_send(MAVLINK_COMM_1 , packet1.command_id );
- mavlink_msg_noarg_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_start_launch_tc(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_START_LAUNCH_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_start_launch_tc_t packet_in = {
- 93372036854775807ULL
- };
- mavlink_start_launch_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.launch_code = packet_in.launch_code;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_start_launch_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_start_launch_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_start_launch_tc_pack(system_id, component_id, &msg , packet1.launch_code );
- mavlink_msg_start_launch_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_start_launch_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.launch_code );
- mavlink_msg_start_launch_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_start_launch_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_start_launch_tc_send(MAVLINK_COMM_1 , packet1.launch_code );
- mavlink_msg_start_launch_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_upload_setting_tc(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_UPLOAD_SETTING_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_upload_setting_tc_t packet_in = {
- 17.0,17
- };
- mavlink_upload_setting_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.setting = packet_in.setting;
- packet1.setting_id = packet_in.setting_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_UPLOAD_SETTING_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_UPLOAD_SETTING_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_upload_setting_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_upload_setting_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_upload_setting_tc_pack(system_id, component_id, &msg , packet1.setting_id , packet1.setting );
- mavlink_msg_upload_setting_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_upload_setting_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.setting_id , packet1.setting );
- mavlink_msg_upload_setting_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_upload_setting_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_upload_setting_tc_send(MAVLINK_COMM_1 , packet1.setting_id , packet1.setting );
- mavlink_msg_upload_setting_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_telemetry_request_tc(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_TELEMETRY_REQUEST_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_telemetry_request_tc_t packet_in = {
- 5
- };
- mavlink_telemetry_request_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.board_id = packet_in.board_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_telemetry_request_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_telemetry_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_telemetry_request_tc_pack(system_id, component_id, &msg , packet1.board_id );
- mavlink_msg_telemetry_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_telemetry_request_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.board_id );
- mavlink_msg_telemetry_request_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_telemetry_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_telemetry_request_tc_send(MAVLINK_COMM_1 , packet1.board_id );
- mavlink_msg_telemetry_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_raw_event_tc(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_RAW_EVENT_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_raw_event_tc_t packet_in = {
- 5,72
- };
- mavlink_raw_event_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.Event_id = packet_in.Event_id;
- packet1.Topic_id = packet_in.Topic_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_raw_event_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_pack(system_id, component_id, &msg , packet1.Event_id , packet1.Topic_id );
- mavlink_msg_raw_event_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.Event_id , packet1.Topic_id );
- mavlink_msg_raw_event_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_raw_event_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_send(MAVLINK_COMM_1 , packet1.Event_id , packet1.Topic_id );
- mavlink_msg_raw_event_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_ack_tm(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_ACK_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ack_tm_t packet_in = {
- 5,72
- };
- mavlink_ack_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.recv_msgid = packet_in.recv_msgid;
- packet1.seq_ack = packet_in.seq_ack;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_ACK_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ACK_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_pack(system_id, component_id, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_ack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_ack_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_send(MAVLINK_COMM_1 , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_ack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_nack_tm(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_NACK_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_nack_tm_t packet_in = {
- 5,72
- };
- mavlink_nack_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.recv_msgid = packet_in.recv_msgid;
- packet1.seq_ack = packet_in.seq_ack;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_NACK_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NACK_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nack_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_nack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nack_tm_pack(system_id, component_id, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_nack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nack_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_nack_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_nack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nack_tm_send(MAVLINK_COMM_1 , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_nack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_sys_tm(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_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_sys_tm_t packet_in = {
- 93372036854775807ULL,29,96,163,230,41,108,175,242,53,120
- };
- mavlink_sys_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.death_stack = packet_in.death_stack;
- packet1.logger = packet_in.logger;
- packet1.ev_broker = packet_in.ev_broker;
- packet1.pin_obs = packet_in.pin_obs;
- packet1.fmm = packet_in.fmm;
- packet1.sensor_manager = packet_in.sensor_manager;
- packet1.ada = packet_in.ada;
- packet1.tmtc = packet_in.tmtc;
- packet1.ign = packet_in.ign;
- packet1.dpl = packet_in.dpl;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SYS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SYS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sys_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_sys_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sys_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.death_stack , packet1.logger , packet1.ev_broker , packet1.pin_obs , packet1.fmm , packet1.sensor_manager , packet1.ada , packet1.tmtc , packet1.ign , packet1.dpl );
- mavlink_msg_sys_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sys_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.death_stack , packet1.logger , packet1.ev_broker , packet1.pin_obs , packet1.fmm , packet1.sensor_manager , packet1.ada , packet1.tmtc , packet1.ign , packet1.dpl );
- mavlink_msg_sys_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_sys_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sys_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.death_stack , packet1.logger , packet1.ev_broker , packet1.pin_obs , packet1.fmm , packet1.sensor_manager , packet1.ada , packet1.tmtc , packet1.ign , packet1.dpl );
- mavlink_msg_sys_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_fmm_tm(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_FMM_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_fmm_tm_t packet_in = {
- 93372036854775807ULL,93372036854776311ULL,93372036854776815ULL,77,144,211,22,89
- };
- mavlink_fmm_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.pin_launch_last_change = packet_in.pin_launch_last_change;
- packet1.pin_nosecone_last_change = packet_in.pin_nosecone_last_change;
- packet1.state = packet_in.state;
- packet1.pin_launch_num_changes = packet_in.pin_launch_num_changes;
- packet1.pin_launch_state = packet_in.pin_launch_state;
- packet1.pin_nosecone_num_changes = packet_in.pin_nosecone_num_changes;
- packet1.pin_nosecone_state = packet_in.pin_nosecone_state;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_FMM_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FMM_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_fmm_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_fmm_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_fmm_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state , packet1.pin_launch_last_change , packet1.pin_launch_num_changes , packet1.pin_launch_state , packet1.pin_nosecone_last_change , packet1.pin_nosecone_num_changes , packet1.pin_nosecone_state );
- mavlink_msg_fmm_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_fmm_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state , packet1.pin_launch_last_change , packet1.pin_launch_num_changes , packet1.pin_launch_state , packet1.pin_nosecone_last_change , packet1.pin_nosecone_num_changes , packet1.pin_nosecone_state );
- mavlink_msg_fmm_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_fmm_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_fmm_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state , packet1.pin_launch_last_change , packet1.pin_launch_num_changes , packet1.pin_launch_state , packet1.pin_nosecone_last_change , packet1.pin_nosecone_num_changes , packet1.pin_nosecone_state );
- mavlink_msg_fmm_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_logger_tm(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_LOGGER_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_logger_tm_t packet_in = {
- 93372036854775807ULL,963497880,963498088,963498296,963498504,963498712,963498920,963499128,963499336,963499544,19523
- };
- mavlink_logger_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.statTooLargeSamples = packet_in.statTooLargeSamples;
- packet1.statDroppedSamples = packet_in.statDroppedSamples;
- packet1.statQueuedSamples = packet_in.statQueuedSamples;
- packet1.statBufferFilled = packet_in.statBufferFilled;
- packet1.statBufferWritten = packet_in.statBufferWritten;
- packet1.statWriteFailed = packet_in.statWriteFailed;
- packet1.statWriteError = packet_in.statWriteError;
- packet1.statWriteTime = packet_in.statWriteTime;
- packet1.statMaxWriteTime = packet_in.statMaxWriteTime;
- packet1.statLogNumber = packet_in.statLogNumber;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_logger_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_logger_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_logger_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.statLogNumber , packet1.statTooLargeSamples , packet1.statDroppedSamples , packet1.statQueuedSamples , packet1.statBufferFilled , packet1.statBufferWritten , packet1.statWriteFailed , packet1.statWriteError , packet1.statWriteTime , packet1.statMaxWriteTime );
- mavlink_msg_logger_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_logger_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.statLogNumber , packet1.statTooLargeSamples , packet1.statDroppedSamples , packet1.statQueuedSamples , packet1.statBufferFilled , packet1.statBufferWritten , packet1.statWriteFailed , packet1.statWriteError , packet1.statWriteTime , packet1.statMaxWriteTime );
- mavlink_msg_logger_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_logger_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_logger_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.statLogNumber , packet1.statTooLargeSamples , packet1.statDroppedSamples , packet1.statQueuedSamples , packet1.statBufferFilled , packet1.statBufferWritten , packet1.statWriteFailed , packet1.statWriteError , packet1.statWriteTime , packet1.statMaxWriteTime );
- mavlink_msg_logger_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_tmtc_tm(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_TMTC_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_tmtc_tm_t packet_in = {
- 93372036854775807ULL,963497880,17859,17963,18067,18171,18275,199,10,77,144,211,22
- };
- mavlink_tmtc_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.parse_state = packet_in.parse_state;
- packet1.n_send_queue = packet_in.n_send_queue;
- packet1.max_send_queue = packet_in.max_send_queue;
- packet1.n_send_errors = packet_in.n_send_errors;
- packet1.packet_rx_success_count = packet_in.packet_rx_success_count;
- packet1.packet_rx_drop_count = packet_in.packet_rx_drop_count;
- packet1.msg_received = packet_in.msg_received;
- packet1.buffer_overrun = packet_in.buffer_overrun;
- packet1.parse_error = packet_in.parse_error;
- packet1.packet_idx = packet_in.packet_idx;
- packet1.current_rx_seq = packet_in.current_rx_seq;
- packet1.current_tx_seq = packet_in.current_tx_seq;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_TMTC_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TMTC_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_tmtc_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_tmtc_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_tmtc_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.n_send_queue , packet1.max_send_queue , packet1.n_send_errors , packet1.msg_received , packet1.buffer_overrun , packet1.parse_error , packet1.parse_state , packet1.packet_idx , packet1.current_rx_seq , packet1.current_tx_seq , packet1.packet_rx_success_count , packet1.packet_rx_drop_count );
- mavlink_msg_tmtc_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_tmtc_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.n_send_queue , packet1.max_send_queue , packet1.n_send_errors , packet1.msg_received , packet1.buffer_overrun , packet1.parse_error , packet1.parse_state , packet1.packet_idx , packet1.current_rx_seq , packet1.current_tx_seq , packet1.packet_rx_success_count , packet1.packet_rx_drop_count );
- mavlink_msg_tmtc_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_tmtc_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_tmtc_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.n_send_queue , packet1.max_send_queue , packet1.n_send_errors , packet1.msg_received , packet1.buffer_overrun , packet1.parse_error , packet1.parse_state , packet1.packet_idx , packet1.current_rx_seq , packet1.current_tx_seq , packet1.packet_rx_success_count , packet1.packet_rx_drop_count );
- mavlink_msg_tmtc_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_sm_tm(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_SM_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_sm_tm_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,20147,51
- };
- mavlink_sm_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.task_10hz_min = packet_in.task_10hz_min;
- packet1.task_10hz_max = packet_in.task_10hz_max;
- packet1.task_10hz_mean = packet_in.task_10hz_mean;
- packet1.task_10hz_stddev = packet_in.task_10hz_stddev;
- packet1.task_20hz_min = packet_in.task_20hz_min;
- packet1.task_20hz_max = packet_in.task_20hz_max;
- packet1.task_20hz_mean = packet_in.task_20hz_mean;
- packet1.task_20hz_stddev = packet_in.task_20hz_stddev;
- packet1.task_250hz_min = packet_in.task_250hz_min;
- packet1.task_250hz_max = packet_in.task_250hz_max;
- packet1.task_250hz_mean = packet_in.task_250hz_mean;
- packet1.task_250hz_stddev = packet_in.task_250hz_stddev;
- packet1.sensor_state = packet_in.sensor_state;
- 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_SM_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SM_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sm_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_sm_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sm_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state , packet1.sensor_state , packet1.task_10hz_min , packet1.task_10hz_max , packet1.task_10hz_mean , packet1.task_10hz_stddev , packet1.task_20hz_min , packet1.task_20hz_max , packet1.task_20hz_mean , packet1.task_20hz_stddev , packet1.task_250hz_min , packet1.task_250hz_max , packet1.task_250hz_mean , packet1.task_250hz_stddev );
- mavlink_msg_sm_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sm_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state , packet1.sensor_state , packet1.task_10hz_min , packet1.task_10hz_max , packet1.task_10hz_mean , packet1.task_10hz_stddev , packet1.task_20hz_min , packet1.task_20hz_max , packet1.task_20hz_mean , packet1.task_20hz_stddev , packet1.task_250hz_min , packet1.task_250hz_max , packet1.task_250hz_mean , packet1.task_250hz_stddev );
- mavlink_msg_sm_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_sm_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sm_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state , packet1.sensor_state , packet1.task_10hz_min , packet1.task_10hz_max , packet1.task_10hz_mean , packet1.task_10hz_stddev , packet1.task_20hz_min , packet1.task_20hz_max , packet1.task_20hz_mean , packet1.task_20hz_stddev , packet1.task_250hz_min , packet1.task_250hz_max , packet1.task_250hz_mean , packet1.task_250hz_stddev );
- mavlink_msg_sm_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_ign_tm(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_IGN_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ign_tm_t packet_in = {
- 93372036854775807ULL,17651,17755,41,108,175,242,53
- };
- mavlink_ign_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.n_sent_messages = packet_in.n_sent_messages;
- packet1.n_rcv_message = packet_in.n_rcv_message;
- packet1.fsm_state = packet_in.fsm_state;
- packet1.last_event = packet_in.last_event;
- packet1.cmd_bitfield = packet_in.cmd_bitfield;
- packet1.stm32_bitfield = packet_in.stm32_bitfield;
- packet1.avr_bitfield = packet_in.avr_bitfield;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_IGN_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_IGN_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ign_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ign_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ign_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.fsm_state , packet1.last_event , packet1.n_sent_messages , packet1.n_rcv_message , packet1.cmd_bitfield , packet1.stm32_bitfield , packet1.avr_bitfield );
- mavlink_msg_ign_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ign_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.fsm_state , packet1.last_event , packet1.n_sent_messages , packet1.n_rcv_message , packet1.cmd_bitfield , packet1.stm32_bitfield , packet1.avr_bitfield );
- mavlink_msg_ign_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ign_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ign_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.fsm_state , packet1.last_event , packet1.n_sent_messages , packet1.n_rcv_message , packet1.cmd_bitfield , packet1.stm32_bitfield , packet1.avr_bitfield );
- mavlink_msg_ign_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_dpl_tm(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_DPL_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_dpl_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,53,120
- };
- mavlink_dpl_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.cutter_1_test_current = packet_in.cutter_1_test_current;
- packet1.cutter_2_test_current = packet_in.cutter_2_test_current;
- packet1.fsm_state = packet_in.fsm_state;
- packet1.cutter_state = packet_in.cutter_state;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_DPL_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DPL_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_dpl_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_dpl_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_dpl_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.fsm_state , packet1.cutter_1_test_current , packet1.cutter_2_test_current , packet1.cutter_state );
- mavlink_msg_dpl_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_dpl_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.fsm_state , packet1.cutter_1_test_current , packet1.cutter_2_test_current , packet1.cutter_state );
- mavlink_msg_dpl_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_dpl_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_dpl_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.fsm_state , packet1.cutter_1_test_current , packet1.cutter_2_test_current , packet1.cutter_state );
- mavlink_msg_dpl_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_ada_tm(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_ADA_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ada_tm_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,963500168,409.0,437.0,465.0,209
- };
- mavlink_ada_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.target_dpl_altitude = packet_in.target_dpl_altitude;
- packet1.kalman_x0 = packet_in.kalman_x0;
- packet1.kalman_x1 = packet_in.kalman_x1;
- packet1.kalman_x2 = packet_in.kalman_x2;
- packet1.kalman_acc_x0 = packet_in.kalman_acc_x0;
- packet1.kalman_acc_x1 = packet_in.kalman_acc_x1;
- packet1.kalman_acc_x2 = packet_in.kalman_acc_x2;
- packet1.ref_pressure = packet_in.ref_pressure;
- packet1.msl_pressure = packet_in.msl_pressure;
- packet1.ref_pressure_mean = packet_in.ref_pressure_mean;
- packet1.ref_pressure_stddev = packet_in.ref_pressure_stddev;
- packet1.ref_pressure_nsamples = packet_in.ref_pressure_nsamples;
- packet1.ref_altitude = packet_in.ref_altitude;
- packet1.ref_temperature = packet_in.ref_temperature;
- packet1.msl_temperature = packet_in.msl_temperature;
- 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_ADA_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ADA_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ada_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ada_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ada_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state , packet1.target_dpl_altitude , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.kalman_acc_x0 , packet1.kalman_acc_x1 , packet1.kalman_acc_x2 , packet1.ref_pressure , packet1.msl_pressure , packet1.ref_pressure_mean , packet1.ref_pressure_stddev , packet1.ref_pressure_nsamples , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_temperature );
- mavlink_msg_ada_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ada_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state , packet1.target_dpl_altitude , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.kalman_acc_x0 , packet1.kalman_acc_x1 , packet1.kalman_acc_x2 , packet1.ref_pressure , packet1.msl_pressure , packet1.ref_pressure_mean , packet1.ref_pressure_stddev , packet1.ref_pressure_nsamples , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_temperature );
- mavlink_msg_ada_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ada_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ada_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state , packet1.target_dpl_altitude , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.kalman_acc_x0 , packet1.kalman_acc_x1 , packet1.kalman_acc_x2 , packet1.ref_pressure , packet1.msl_pressure , packet1.ref_pressure_mean , packet1.ref_pressure_stddev , packet1.ref_pressure_nsamples , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_temperature );
- mavlink_msg_ada_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_can_tm(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_CAN_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_can_tm_t packet_in = {
- 93372036854775807ULL,93372036854776311ULL,18067,18171,65,132
- };
- mavlink_can_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.last_sent_ts = packet_in.last_sent_ts;
- packet1.last_rcv_ts = packet_in.last_rcv_ts;
- packet1.n_sent = packet_in.n_sent;
- packet1.n_rcv = packet_in.n_rcv;
- packet1.last_sent = packet_in.last_sent;
- packet1.last_rcv = packet_in.last_rcv;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_CAN_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAN_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_can_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_can_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_can_tm_pack(system_id, component_id, &msg , packet1.n_sent , packet1.n_rcv , packet1.last_sent , packet1.last_rcv , packet1.last_sent_ts , packet1.last_rcv_ts );
- mavlink_msg_can_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_can_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.n_sent , packet1.n_rcv , packet1.last_sent , packet1.last_rcv , packet1.last_sent_ts , packet1.last_rcv_ts );
- mavlink_msg_can_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_can_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_can_tm_send(MAVLINK_COMM_1 , packet1.n_sent , packet1.n_rcv , packet1.last_sent , packet1.last_rcv , packet1.last_sent_ts , packet1.last_rcv_ts );
- mavlink_msg_can_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_adc_tm(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_ADC_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_adc_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,113,180
- };
- mavlink_adc_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.hw_baro_volt = packet_in.hw_baro_volt;
- packet1.nxp_baro_volt = packet_in.nxp_baro_volt;
- packet1.hw_baro_pressure = packet_in.hw_baro_pressure;
- packet1.nxp_baro_pressure = packet_in.nxp_baro_pressure;
- packet1.battery_voltage = packet_in.battery_voltage;
- packet1.current_sense_1 = packet_in.current_sense_1;
- packet1.current_sense_2 = packet_in.current_sense_2;
- packet1.hw_baro_flag = packet_in.hw_baro_flag;
- packet1.nxp_baro_flag = packet_in.nxp_baro_flag;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_ADC_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ADC_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adc_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_adc_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adc_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.hw_baro_volt , packet1.nxp_baro_volt , packet1.hw_baro_flag , packet1.nxp_baro_flag , packet1.hw_baro_pressure , packet1.nxp_baro_pressure , packet1.battery_voltage , packet1.current_sense_1 , packet1.current_sense_2 );
- mavlink_msg_adc_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adc_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.hw_baro_volt , packet1.nxp_baro_volt , packet1.hw_baro_flag , packet1.nxp_baro_flag , packet1.hw_baro_pressure , packet1.nxp_baro_pressure , packet1.battery_voltage , packet1.current_sense_1 , packet1.current_sense_2 );
- mavlink_msg_adc_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_adc_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adc_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.hw_baro_volt , packet1.nxp_baro_volt , packet1.hw_baro_flag , packet1.nxp_baro_flag , packet1.hw_baro_pressure , packet1.nxp_baro_pressure , packet1.battery_voltage , packet1.current_sense_1 , packet1.current_sense_2 );
- mavlink_msg_adc_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_adis_tm(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_ADIS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_adis_tm_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
- };
- mavlink_adis_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.acc_x = packet_in.acc_x;
- packet1.acc_y = packet_in.acc_y;
- packet1.acc_z = packet_in.acc_z;
- packet1.gyro_x = packet_in.gyro_x;
- packet1.gyro_y = packet_in.gyro_y;
- packet1.gyro_z = packet_in.gyro_z;
- packet1.compass_x = packet_in.compass_x;
- packet1.compass_y = packet_in.compass_y;
- packet1.compass_z = packet_in.compass_z;
- packet1.temp = packet_in.temp;
- packet1.supply_out = packet_in.supply_out;
- packet1.aux_adc = packet_in.aux_adc;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_ADIS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ADIS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adis_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_adis_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adis_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.compass_x , packet1.compass_y , packet1.compass_z , packet1.temp , packet1.supply_out , packet1.aux_adc );
- mavlink_msg_adis_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adis_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.compass_x , packet1.compass_y , packet1.compass_z , packet1.temp , packet1.supply_out , packet1.aux_adc );
- mavlink_msg_adis_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_adis_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adis_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.compass_x , packet1.compass_y , packet1.compass_z , packet1.temp , packet1.supply_out , packet1.aux_adc );
- mavlink_msg_adis_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_mpu_tm(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_MPU_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_mpu_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0
- };
- mavlink_mpu_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.acc_x = packet_in.acc_x;
- packet1.acc_y = packet_in.acc_y;
- packet1.acc_z = packet_in.acc_z;
- packet1.gyro_x = packet_in.gyro_x;
- packet1.gyro_y = packet_in.gyro_y;
- packet1.gyro_z = packet_in.gyro_z;
- packet1.compass_x = packet_in.compass_x;
- packet1.compass_y = packet_in.compass_y;
- packet1.compass_z = packet_in.compass_z;
- packet1.temp = packet_in.temp;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_MPU_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MPU_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mpu_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_mpu_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mpu_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.compass_x , packet1.compass_y , packet1.compass_z , packet1.temp );
- mavlink_msg_mpu_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mpu_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.compass_x , packet1.compass_y , packet1.compass_z , packet1.temp );
- mavlink_msg_mpu_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_mpu_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mpu_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.compass_x , packet1.compass_y , packet1.compass_z , packet1.temp );
- mavlink_msg_mpu_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_gps_tm(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_GPS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_gps_tm_t packet_in = {
- 93372036854775807ULL,179.0,235.0,291.0,241.0,269.0,297.0,325.0,963499960,161
- };
- mavlink_gps_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.lat = packet_in.lat;
- packet1.lon = packet_in.lon;
- packet1.altitude = packet_in.altitude;
- packet1.vel_north = packet_in.vel_north;
- packet1.vel_east = packet_in.vel_east;
- packet1.vel_down = packet_in.vel_down;
- packet1.vel_mag = packet_in.vel_mag;
- packet1.n_satellites = packet_in.n_satellites;
- packet1.fix = packet_in.fix;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_GPS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gps_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_gps_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gps_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.fix , packet1.lat , packet1.lon , packet1.altitude , packet1.vel_north , packet1.vel_east , packet1.vel_down , packet1.vel_mag , packet1.n_satellites );
- mavlink_msg_gps_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gps_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.fix , packet1.lat , packet1.lon , packet1.altitude , packet1.vel_north , packet1.vel_east , packet1.vel_down , packet1.vel_mag , packet1.n_satellites );
- mavlink_msg_gps_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_gps_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gps_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.fix , packet1.lat , packet1.lon , packet1.altitude , packet1.vel_north , packet1.vel_east , packet1.vel_down , packet1.vel_mag , packet1.n_satellites );
- mavlink_msg_gps_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_hr_tm(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_HR_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_hr_tm_t packet_in = {
- { 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 }
- };
- mavlink_hr_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
-
- mav_array_memcpy(packet1.payload, packet_in.payload, sizeof(uint8_t)*104);
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_HR_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HR_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_hr_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_hr_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_hr_tm_pack(system_id, component_id, &msg , packet1.payload );
- mavlink_msg_hr_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_hr_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.payload );
- mavlink_msg_hr_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_hr_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_hr_tm_send(MAVLINK_COMM_1 , packet1.payload );
- mavlink_msg_hr_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_lr_tm(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_LR_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_lr_tm_t packet_in = {
- { 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 }
- };
- mavlink_lr_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
-
- mav_array_memcpy(packet1.payload, packet_in.payload, 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_LR_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LR_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_lr_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_lr_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_lr_tm_pack(system_id, component_id, &msg , packet1.payload );
- mavlink_msg_lr_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_lr_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.payload );
- mavlink_msg_lr_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_lr_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_lr_tm_send(MAVLINK_COMM_1 , packet1.payload );
- mavlink_msg_lr_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_test_tm(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_TEST_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_test_tm_t packet_in = {
- 963497464,45.0,73.0,101.0,129.0,157.0,185.0,89
- };
- mavlink_test_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.pressure_hw = packet_in.pressure_hw;
- packet1.temp_analog = packet_in.temp_analog;
- packet1.temp_imu = packet_in.temp_imu;
- packet1.battery_volt = packet_in.battery_volt;
- packet1.th_cut_1 = packet_in.th_cut_1;
- packet1.th_cut_2 = packet_in.th_cut_2;
- packet1.gps_nsats = packet_in.gps_nsats;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_TEST_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TEST_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_test_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_test_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_test_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.pressure_hw , packet1.gps_nsats , packet1.temp_analog , packet1.temp_imu , packet1.battery_volt , packet1.th_cut_1 , packet1.th_cut_2 );
- mavlink_msg_test_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_test_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.pressure_hw , packet1.gps_nsats , packet1.temp_analog , packet1.temp_imu , packet1.battery_volt , packet1.th_cut_1 , packet1.th_cut_2 );
- mavlink_msg_test_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_test_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_test_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.pressure_hw , packet1.gps_nsats , packet1.temp_analog , packet1.temp_imu , packet1.battery_volt , packet1.th_cut_1 , packet1.th_cut_2 );
- mavlink_msg_test_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_hermes(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
-{
- mavlink_test_ping_tc(system_id, component_id, last_msg);
- mavlink_test_noarg_tc(system_id, component_id, last_msg);
- mavlink_test_start_launch_tc(system_id, component_id, last_msg);
- mavlink_test_upload_setting_tc(system_id, component_id, last_msg);
- mavlink_test_telemetry_request_tc(system_id, component_id, last_msg);
- mavlink_test_raw_event_tc(system_id, component_id, last_msg);
- mavlink_test_ack_tm(system_id, component_id, last_msg);
- mavlink_test_nack_tm(system_id, component_id, last_msg);
- mavlink_test_sys_tm(system_id, component_id, last_msg);
- mavlink_test_fmm_tm(system_id, component_id, last_msg);
- mavlink_test_logger_tm(system_id, component_id, last_msg);
- mavlink_test_tmtc_tm(system_id, component_id, last_msg);
- mavlink_test_sm_tm(system_id, component_id, last_msg);
- mavlink_test_ign_tm(system_id, component_id, last_msg);
- mavlink_test_dpl_tm(system_id, component_id, last_msg);
- mavlink_test_ada_tm(system_id, component_id, last_msg);
- mavlink_test_can_tm(system_id, component_id, last_msg);
- mavlink_test_adc_tm(system_id, component_id, last_msg);
- mavlink_test_adis_tm(system_id, component_id, last_msg);
- mavlink_test_mpu_tm(system_id, component_id, last_msg);
- mavlink_test_gps_tm(system_id, component_id, last_msg);
- mavlink_test_hr_tm(system_id, component_id, last_msg);
- mavlink_test_lr_tm(system_id, component_id, last_msg);
- mavlink_test_test_tm(system_id, component_id, last_msg);
-}
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // HERMES_TESTSUITE_H
diff --git a/mavlink_lib/hermes/version.h b/mavlink_lib/hermes/version.h
deleted file mode 100644
index 7dd4256b0c076fac4c838f0b775562e8e5432d99..0000000000000000000000000000000000000000
--- a/mavlink_lib/hermes/version.h
+++ /dev/null
@@ -1,14 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol built from hermes.xml
- * @see http://mavlink.org
- */
-#pragma once
-
-#ifndef MAVLINK_VERSION_H
-#define MAVLINK_VERSION_H
-
-#define MAVLINK_BUILD_DATE "Thu Nov 07 2019"
-#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
-#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 104
-
-#endif // MAVLINK_VERSION_H
diff --git a/mavlink_lib/lynx/StatusRepos.h b/mavlink_lib/lynx/StatusRepos.h
deleted file mode 100644
index 5ec7ffe73a85564986a17697adfc1f7f79b80791..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/StatusRepos.h
+++ /dev/null
@@ -1,150 +0,0 @@
-/** @file
- * @brief Skyward Status Repository
- */
-#pragma once
-
-namespace StatusRepo
-{
- /* Enumeration of all possible TMs */
- enum MavTMList: uint8_t
- {
- MAV_ACK_TM_ID,
- MAV_NACK_TM_ID,
- MAV_SYS_TM_ID,
- MAV_FMM_TM_ID,
- MAV_PIN_OBS_TM_ID,
- MAV_LOGGER_TM_ID,
- MAV_TMTC_TM_ID,
- MAV_TASK_STATS_TM_ID,
- MAV_DPL_TM_ID,
- MAV_ADA_TM_ID,
- MAV_ABK_TM_ID,
- MAV_NAS_TM_ID,
- MAV_ADC_TM_ID,
- MAV_MS5803_TM_ID,
- MAV_BMX160_TM_ID,
- MAV_LIS3MDL_TM_ID,
- MAV_GPS_TM_ID,
- MAV_HR_TM_ID,
- MAV_LR_TM_ID,
- MAV_TEST_TM_ID,
- MAV_WINDTUNNEL_TM_ID,
- MAV_SENSORS_TM_ID,
-
- };
-
- /* Struct containing all tms in the form of mavlink structs */
- static struct status_repo_t
- {
- mavlink_ack_tm_t ack_tm;
- mavlink_nack_tm_t nack_tm;
- mavlink_sys_tm_t sys_tm;
- mavlink_fmm_tm_t fmm_tm;
- mavlink_pin_obs_tm_t pin_obs_tm;
- mavlink_logger_tm_t logger_tm;
- mavlink_tmtc_tm_t tmtc_tm;
- mavlink_task_stats_tm_t task_stats_tm;
- mavlink_dpl_tm_t dpl_tm;
- mavlink_ada_tm_t ada_tm;
- mavlink_abk_tm_t abk_tm;
- mavlink_nas_tm_t nas_tm;
- mavlink_adc_tm_t adc_tm;
- mavlink_ms5803_tm_t ms5803_tm;
- mavlink_bmx160_tm_t bmx160_tm;
- mavlink_lis3mdl_tm_t lis3mdl_tm;
- mavlink_gps_tm_t gps_tm;
- mavlink_hr_tm_t hr_tm;
- mavlink_lr_tm_t lr_tm;
- mavlink_test_tm_t test_tm;
- mavlink_windtunnel_tm_t windtunnel_tm;
- mavlink_sensors_tm_t sensors_tm;
-
- } status repo;
-
- /**
- * Retrieve one of the telemetry structs
- * @req_tm required telemetry
- * @return packed mavlink struct of that telemetry
- */
- static mavlink_message_t getTM(uint8_t req_tm, uint8_t sys_id, uint8_t comp_id)
- {
- mavlink_message_t m;
-
- switch (req_tm)
- {
- case MavTMList::MAV_ACK_TM_ID:
- mavlink_msg_ack_tm_encode(sys_id, comp_id, &m, &(repo.ack_tm));
- break;
- case MavTMList::MAV_NACK_TM_ID:
- mavlink_msg_nack_tm_encode(sys_id, comp_id, &m, &(repo.nack_tm));
- break;
- case MavTMList::MAV_SYS_TM_ID:
- mavlink_msg_sys_tm_encode(sys_id, comp_id, &m, &(repo.sys_tm));
- break;
- case MavTMList::MAV_FMM_TM_ID:
- mavlink_msg_fmm_tm_encode(sys_id, comp_id, &m, &(repo.fmm_tm));
- break;
- case MavTMList::MAV_PIN_OBS_TM_ID:
- mavlink_msg_pin_obs_tm_encode(sys_id, comp_id, &m, &(repo.pin_obs_tm));
- break;
- case MavTMList::MAV_LOGGER_TM_ID:
- mavlink_msg_logger_tm_encode(sys_id, comp_id, &m, &(repo.logger_tm));
- break;
- case MavTMList::MAV_TMTC_TM_ID:
- mavlink_msg_tmtc_tm_encode(sys_id, comp_id, &m, &(repo.tmtc_tm));
- break;
- case MavTMList::MAV_TASK_STATS_TM_ID:
- mavlink_msg_task_stats_tm_encode(sys_id, comp_id, &m, &(repo.task_stats_tm));
- break;
- case MavTMList::MAV_DPL_TM_ID:
- mavlink_msg_dpl_tm_encode(sys_id, comp_id, &m, &(repo.dpl_tm));
- break;
- case MavTMList::MAV_ADA_TM_ID:
- mavlink_msg_ada_tm_encode(sys_id, comp_id, &m, &(repo.ada_tm));
- break;
- case MavTMList::MAV_ABK_TM_ID:
- mavlink_msg_abk_tm_encode(sys_id, comp_id, &m, &(repo.abk_tm));
- break;
- case MavTMList::MAV_NAS_TM_ID:
- mavlink_msg_nas_tm_encode(sys_id, comp_id, &m, &(repo.nas_tm));
- break;
- case MavTMList::MAV_ADC_TM_ID:
- mavlink_msg_adc_tm_encode(sys_id, comp_id, &m, &(repo.adc_tm));
- break;
- case MavTMList::MAV_MS5803_TM_ID:
- mavlink_msg_ms5803_tm_encode(sys_id, comp_id, &m, &(repo.ms5803_tm));
- break;
- case MavTMList::MAV_BMX160_TM_ID:
- mavlink_msg_bmx160_tm_encode(sys_id, comp_id, &m, &(repo.bmx160_tm));
- break;
- case MavTMList::MAV_LIS3MDL_TM_ID:
- mavlink_msg_lis3mdl_tm_encode(sys_id, comp_id, &m, &(repo.lis3mdl_tm));
- break;
- case MavTMList::MAV_GPS_TM_ID:
- mavlink_msg_gps_tm_encode(sys_id, comp_id, &m, &(repo.gps_tm));
- break;
- case MavTMList::MAV_HR_TM_ID:
- mavlink_msg_hr_tm_encode(sys_id, comp_id, &m, &(repo.hr_tm));
- break;
- case MavTMList::MAV_LR_TM_ID:
- mavlink_msg_lr_tm_encode(sys_id, comp_id, &m, &(repo.lr_tm));
- break;
- case MavTMList::MAV_TEST_TM_ID:
- mavlink_msg_test_tm_encode(sys_id, comp_id, &m, &(repo.test_tm));
- break;
- case MavTMList::MAV_WINDTUNNEL_TM_ID:
- mavlink_msg_windtunnel_tm_encode(sys_id, comp_id, &m, &(repo.windtunnel_tm));
- break;
- case MavTMList::MAV_SENSORS_TM_ID:
- mavlink_msg_sensors_tm_encode(sys_id, comp_id, &m, &(repo.sensors_tm));
- break;
-
- default:
- // TODO: manage error
- break;
- }
-
- return m;
- }
-
-}
diff --git a/mavlink_lib/lynx/lynx.h b/mavlink_lib/lynx/lynx.h
deleted file mode 100644
index c893cfb69bc121006c997a46cf9ea1a499dd0e5e..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/lynx.h
+++ /dev/null
@@ -1,160 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol generated from lynx.xml
- * @see http://mavlink.org
- */
-#pragma once
-#ifndef MAVLINK_LYNX_H
-#define MAVLINK_LYNX_H
-
-#ifndef MAVLINK_H
- #error Wrong include order: MAVLINK_LYNX.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
-
-#undef MAVLINK_THIS_XML_IDX
-#define MAVLINK_THIS_XML_IDX 0
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-// MESSAGE LENGTHS AND CRCS
-
-#ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {0, 8, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 5, 4, 4, 4, 4, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 21, 9, 38, 46, 28, 152, 14, 56, 34, 125, 0, 28, 16, 48, 24, 54, 0, 0, 0, 0, 166, 120, 25, 48, 105, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
-#endif
-
-#ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {0, 136, 0, 0, 0, 0, 0, 0, 0, 0, 77, 0, 0, 0, 0, 0, 0, 0, 0, 0, 43, 90, 183, 95, 38, 44, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 105, 63, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 230, 237, 66, 163, 164, 170, 161, 76, 130, 14, 0, 135, 56, 225, 129, 156, 0, 0, 0, 0, 67, 11, 177, 176, 230, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
-#endif
-
-#include "../protocol.h"
-
-#define MAVLINK_ENABLED_LYNX
-
-// ENUM DEFINITIONS
-
-
-/** @brief Enum list for all the telemetries that can be requested from ground. */
-#ifndef HAVE_ENUM_MavTMList
-#define HAVE_ENUM_MavTMList
-typedef enum MavTMList
-{
- MAV_SYS_TM_ID=1, /* State of system components | */
- MAV_FMM_TM_ID=2, /* FMM status | */
- MAV_PIN_OBS_TM_ID=3, /* Pin observer data | */
- MAV_LOGGER_TM_ID=4, /* SD Logger stats | */
- MAV_TMTC_TM_ID=5, /* TMTC status (mavlink + queue) | */
- MAV_TASK_STATS_TM_ID=6, /* Task scheduler statistics | */
- MAV_DPL_TM_ID=7, /* Deployment System Status | */
- MAV_ADA_TM_ID=8, /* ADA Status | */
- MAV_ABK_TM_ID=9, /* Aerobrakes data | */
- MAV_NAS_TM_ID=10, /* NavigationSystem data | */
- MAV_ADC_TM_ID=12, /* Analog Digital Converter data | */
- MAV_MS5803_TM_ID=13, /* MS5803 barometer data | */
- MAV_BMX160_TM_ID=14, /* BMX160 IMU data | */
- MAV_LIS3MDL_TM_ID=15, /* LIS3MDL compass data | */
- MAV_GPS_TM_ID=16, /* Piksi GPS data | */
- MAV_HR_TM_ID=18, /* High Rate telemetry | */
- MAV_LR_TM_ID=19, /* Low Rate telemetry | */
- MAV_TEST_TM_ID=20, /* Test telemetry | */
- MAV_WINDTUNNEL_TM_ID=21, /* Wind tunnel telemetry | */
- MAV_SENSORS_TM_ID=22, /* Wind tunnel telemetry | */
- MavTMList_ENUM_END=23, /* | */
-} MavTMList;
-#endif
-
-/** @brief Enum of the commands that don't have any message payload. */
-#ifndef HAVE_ENUM_MavCommandList
-#define HAVE_ENUM_MavCommandList
-typedef enum MavCommandList
-{
- MAV_CMD_ARM=27, /* Command to arm the rocket. | */
- MAV_CMD_DISARM=28, /* Command to disarm the rocket. | */
- MAV_CMD_FORCE_LAUNCH=29, /* Command to disarm the rocket. | */
- MAV_CMD_CALIBRATE_SENSORS=30, /* Command to start sensor calibration. | */
- MAV_CMD_CALIBRATE_ALGOS=31, /* Command to start algorithm calibration. | */
- MAV_CMD_FORCE_INIT=52, /* Command to force the initialization even if there where errors. | */
- MAV_CMD_NOSECONE_OPEN=60, /* Command to open the nosecone. | */
- MAV_CMD_DPL_WIGGLE_SERVO=61, /* Command to wiggle the deployment servo-motor to check if it's working | */
- MAV_CMD_ARB_WIGGLE_SERVO=62, /* Command to wiggle the aerobrake servo-motor to check if it's working | */
- MAV_CMD_DPL_RESET_SERVO=63, /* Command to wiggle the deployment servo-motor to check if it's working | */
- MAV_CMD_ARB_RESET_SERVO=64, /* Command to wiggle the aerobrake servo-motor to check if it's working | */
- MAV_CMD_CUT_DROGUE=65, /* Command to activate the thermal cutters and cut the drogue, activating both thermal cutters sequentially | */
- MAV_CMD_START_LOGGING=70, /* Command to enable sensor logging. | */
- MAV_CMD_CLOSE_LOG=72, /* Command to permanently close the log file. | */
- MAV_CMD_TEST_AEROBRAKES=73, /* Command to test the aerobrakes using a predefined servo sequence | */
- MAV_CMD_DISABLE_AEROBRAKES=74, /* Disables aerobrakes during flight | */
- MAV_CMD_END_MISSION=100, /* Command to communicate the end of the mission and close the file descriptors in the SD card. | */
- MAV_CMD_TEST_MODE=200, /* Command to enter the test mode. | */
- MAV_CMD_BOARD_RESET=201, /* Command to reset the board from test status. | */
- MAV_CMD_SERIAL_TM=202, /* Command to enable mavlink messages over serial instead of radio. | */
- MAV_CMD_RADIO_TM=203, /* Command to disabled mavlink messages over serial (start with radio). | */
- MavCommandList_ENUM_END=204, /* | */
-} MavCommandList;
-#endif
-
-// MAVLINK VERSION
-
-#ifndef MAVLINK_VERSION
-#define MAVLINK_VERSION 2
-#endif
-
-#if (MAVLINK_VERSION == 0)
-#undef MAVLINK_VERSION
-#define MAVLINK_VERSION 2
-#endif
-
-// MESSAGE DEFINITIONS
-#include "./mavlink_msg_ping_tc.h"
-#include "./mavlink_msg_noarg_tc.h"
-#include "./mavlink_msg_start_launch_tc.h"
-#include "./mavlink_msg_upload_setting_tc.h"
-#include "./mavlink_msg_set_aerobrake_angle_tc.h"
-#include "./mavlink_msg_set_reference_altitude.h"
-#include "./mavlink_msg_set_reference_temperature_tc.h"
-#include "./mavlink_msg_set_deployment_altitude_tc.h"
-#include "./mavlink_msg_set_initial_orientation_tc.h"
-#include "./mavlink_msg_set_initial_coordinates_tc.h"
-#include "./mavlink_msg_telemetry_request_tc.h"
-#include "./mavlink_msg_raw_event_tc.h"
-#include "./mavlink_msg_ack_tm.h"
-#include "./mavlink_msg_nack_tm.h"
-#include "./mavlink_msg_sys_tm.h"
-#include "./mavlink_msg_fmm_tm.h"
-#include "./mavlink_msg_pin_obs_tm.h"
-#include "./mavlink_msg_logger_tm.h"
-#include "./mavlink_msg_tmtc_tm.h"
-#include "./mavlink_msg_task_stats_tm.h"
-#include "./mavlink_msg_dpl_tm.h"
-#include "./mavlink_msg_ada_tm.h"
-#include "./mavlink_msg_abk_tm.h"
-#include "./mavlink_msg_nas_tm.h"
-#include "./mavlink_msg_adc_tm.h"
-#include "./mavlink_msg_ms5803_tm.h"
-#include "./mavlink_msg_bmx160_tm.h"
-#include "./mavlink_msg_lis3mdl_tm.h"
-#include "./mavlink_msg_gps_tm.h"
-#include "./mavlink_msg_hr_tm.h"
-#include "./mavlink_msg_lr_tm.h"
-#include "./mavlink_msg_test_tm.h"
-#include "./mavlink_msg_windtunnel_tm.h"
-#include "./mavlink_msg_sensors_tm.h"
-
-// base include
-
-
-#undef MAVLINK_THIS_XML_IDX
-#define MAVLINK_THIS_XML_IDX 0
-
-#if MAVLINK_THIS_XML_IDX == MAVLINK_PRIMARY_XML_IDX
-# define MAVLINK_MESSAGE_INFO {{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_NOARG_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_START_LAUNCH_TC, MAVLINK_MESSAGE_INFO_UPLOAD_SETTING_TC, MAVLINK_MESSAGE_INFO_SET_AEROBRAKE_ANGLE_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE, MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC, MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_INITIAL_ORIENTATION_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_TELEMETRY_REQUEST_TC, MAVLINK_MESSAGE_INFO_SET_INITIAL_COORDINATES_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_RAW_EVENT_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACK_TM, MAVLINK_MESSAGE_INFO_NACK_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_TM, MAVLINK_MESSAGE_INFO_FMM_TM, MAVLINK_MESSAGE_INFO_PIN_OBS_TM, MAVLINK_MESSAGE_INFO_LOGGER_TM, MAVLINK_MESSAGE_INFO_TMTC_TM, MAVLINK_MESSAGE_INFO_TASK_STATS_TM, MAVLINK_MESSAGE_INFO_DPL_TM, MAVLINK_MESSAGE_INFO_ADA_TM, MAVLINK_MESSAGE_INFO_ABK_TM, MAVLINK_MESSAGE_INFO_NAS_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ADC_TM, MAVLINK_MESSAGE_INFO_MS5803_TM, MAVLINK_MESSAGE_INFO_BMX160_TM, MAVLINK_MESSAGE_INFO_LIS3MDL_TM, MAVLINK_MESSAGE_INFO_GPS_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_HR_TM, MAVLINK_MESSAGE_INFO_LR_TM, MAVLINK_MESSAGE_INFO_TEST_TM, MAVLINK_MESSAGE_INFO_WINDTUNNEL_TM, MAVLINK_MESSAGE_INFO_SENSORS_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
-# define MAVLINK_MESSAGE_NAMES {{ "ABK_TM", 168 }, { "ACK_TM", 130 }, { "ADA_TM", 167 }, { "ADC_TM", 171 }, { "BMX160_TM", 173 }, { "DPL_TM", 166 }, { "FMM_TM", 161 }, { "GPS_TM", 175 }, { "HR_TM", 180 }, { "LIS3MDL_TM", 174 }, { "LOGGER_TM", 163 }, { "LR_TM", 181 }, { "MS5803_TM", 172 }, { "NACK_TM", 131 }, { "NAS_TM", 169 }, { "NOARG_TC", 10 }, { "PING_TC", 1 }, { "PIN_OBS_TM", 162 }, { "RAW_EVENT_TC", 80 }, { "SENSORS_TM", 184 }, { "SET_AEROBRAKE_ANGLE_TC", 22 }, { "SET_DEPLOYMENT_ALTITUDE_TC", 25 }, { "SET_INITIAL_COORDINATES_TC", 51 }, { "SET_INITIAL_ORIENTATION_TC", 26 }, { "SET_REFERENCE_ALTITUDE", 23 }, { "SET_REFERENCE_TEMPERATURE_TC", 24 }, { "START_LAUNCH_TC", 20 }, { "SYS_TM", 160 }, { "TASK_STATS_TM", 165 }, { "TELEMETRY_REQUEST_TC", 50 }, { "TEST_TM", 182 }, { "TMTC_TM", 164 }, { "UPLOAD_SETTING_TC", 21 }, { "WINDTUNNEL_TM", 183 }}
-# if MAVLINK_COMMAND_24BIT
-# include "../mavlink_get_info.h"
-# endif
-#endif
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // MAVLINK_LYNX_H
diff --git a/mavlink_lib/lynx/mavlink.h b/mavlink_lib/lynx/mavlink.h
deleted file mode 100644
index e3db0baa1420019f54432f90b066062e87948a8c..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink.h
+++ /dev/null
@@ -1,34 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol built from lynx.xml
- * @see http://mavlink.org
- */
-#pragma once
-#ifndef MAVLINK_H
-#define MAVLINK_H
-
-#define MAVLINK_PRIMARY_XML_IDX 0
-
-#ifndef MAVLINK_STX
-#define MAVLINK_STX 254
-#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 0
-#endif
-
-#include "version.h"
-#include "lynx.h"
-
-#endif // MAVLINK_H
diff --git a/mavlink_lib/lynx/mavlink_msg_abk_tm.h b/mavlink_lib/lynx/mavlink_msg_abk_tm.h
deleted file mode 100644
index bfbf6da930947e763e856eca23d75fcf9f2d9521..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_abk_tm.h
+++ /dev/null
@@ -1,413 +0,0 @@
-#pragma once
-// MESSAGE ABK_TM PACKING
-
-#define MAVLINK_MSG_ID_ABK_TM 168
-
-MAVPACKED(
-typedef struct __mavlink_abk_tm_t {
- uint64_t timestamp; /*< [ms] When was this logged*/
- float servo_position; /*< [deg] Aerobrakes opening angle*/
- float estimated_cd; /*< Drag estimated by the control algorithm*/
- float pid_error; /*< Error of the PID controller at each step*/
- float z; /*< [m] Input altitude*/
- float vz; /*< [m/s] Input vertical speed*/
- float v_mod; /*< [m/s] Input speed magnitude*/
- uint8_t state; /*< Aerobrakes FSM state*/
- uint8_t trajectory; /*< Chosen trajectory to be followed*/
-}) mavlink_abk_tm_t;
-
-#define MAVLINK_MSG_ID_ABK_TM_LEN 34
-#define MAVLINK_MSG_ID_ABK_TM_MIN_LEN 34
-#define MAVLINK_MSG_ID_168_LEN 34
-#define MAVLINK_MSG_ID_168_MIN_LEN 34
-
-#define MAVLINK_MSG_ID_ABK_TM_CRC 130
-#define MAVLINK_MSG_ID_168_CRC 130
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ABK_TM { \
- 168, \
- "ABK_TM", \
- 9, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_abk_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_abk_tm_t, state) }, \
- { "servo_position", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_abk_tm_t, servo_position) }, \
- { "estimated_cd", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_abk_tm_t, estimated_cd) }, \
- { "pid_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_abk_tm_t, pid_error) }, \
- { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_abk_tm_t, z) }, \
- { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_abk_tm_t, vz) }, \
- { "v_mod", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_abk_tm_t, v_mod) }, \
- { "trajectory", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_abk_tm_t, trajectory) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ABK_TM { \
- "ABK_TM", \
- 9, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_abk_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_abk_tm_t, state) }, \
- { "servo_position", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_abk_tm_t, servo_position) }, \
- { "estimated_cd", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_abk_tm_t, estimated_cd) }, \
- { "pid_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_abk_tm_t, pid_error) }, \
- { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_abk_tm_t, z) }, \
- { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_abk_tm_t, vz) }, \
- { "v_mod", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_abk_tm_t, v_mod) }, \
- { "trajectory", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_abk_tm_t, trajectory) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a abk_tm 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] When was this logged
- * @param state Aerobrakes FSM state
- * @param servo_position [deg] Aerobrakes opening angle
- * @param estimated_cd Drag estimated by the control algorithm
- * @param pid_error Error of the PID controller at each step
- * @param z [m] Input altitude
- * @param vz [m/s] Input vertical speed
- * @param v_mod [m/s] Input speed magnitude
- * @param trajectory Chosen trajectory to be followed
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_abk_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t state, float servo_position, float estimated_cd, float pid_error, float z, float vz, float v_mod, uint8_t trajectory)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ABK_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, servo_position);
- _mav_put_float(buf, 12, estimated_cd);
- _mav_put_float(buf, 16, pid_error);
- _mav_put_float(buf, 20, z);
- _mav_put_float(buf, 24, vz);
- _mav_put_float(buf, 28, v_mod);
- _mav_put_uint8_t(buf, 32, state);
- _mav_put_uint8_t(buf, 33, trajectory);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ABK_TM_LEN);
-#else
- mavlink_abk_tm_t packet;
- packet.timestamp = timestamp;
- packet.servo_position = servo_position;
- packet.estimated_cd = estimated_cd;
- packet.pid_error = pid_error;
- packet.z = z;
- packet.vz = vz;
- packet.v_mod = v_mod;
- packet.state = state;
- packet.trajectory = trajectory;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ABK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ABK_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ABK_TM_MIN_LEN, MAVLINK_MSG_ID_ABK_TM_LEN, MAVLINK_MSG_ID_ABK_TM_CRC);
-}
-
-/**
- * @brief Pack a abk_tm 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] When was this logged
- * @param state Aerobrakes FSM state
- * @param servo_position [deg] Aerobrakes opening angle
- * @param estimated_cd Drag estimated by the control algorithm
- * @param pid_error Error of the PID controller at each step
- * @param z [m] Input altitude
- * @param vz [m/s] Input vertical speed
- * @param v_mod [m/s] Input speed magnitude
- * @param trajectory Chosen trajectory to be followed
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_abk_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t state,float servo_position,float estimated_cd,float pid_error,float z,float vz,float v_mod,uint8_t trajectory)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ABK_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, servo_position);
- _mav_put_float(buf, 12, estimated_cd);
- _mav_put_float(buf, 16, pid_error);
- _mav_put_float(buf, 20, z);
- _mav_put_float(buf, 24, vz);
- _mav_put_float(buf, 28, v_mod);
- _mav_put_uint8_t(buf, 32, state);
- _mav_put_uint8_t(buf, 33, trajectory);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ABK_TM_LEN);
-#else
- mavlink_abk_tm_t packet;
- packet.timestamp = timestamp;
- packet.servo_position = servo_position;
- packet.estimated_cd = estimated_cd;
- packet.pid_error = pid_error;
- packet.z = z;
- packet.vz = vz;
- packet.v_mod = v_mod;
- packet.state = state;
- packet.trajectory = trajectory;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ABK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ABK_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ABK_TM_MIN_LEN, MAVLINK_MSG_ID_ABK_TM_LEN, MAVLINK_MSG_ID_ABK_TM_CRC);
-}
-
-/**
- * @brief Encode a abk_tm 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 abk_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_abk_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_abk_tm_t* abk_tm)
-{
- return mavlink_msg_abk_tm_pack(system_id, component_id, msg, abk_tm->timestamp, abk_tm->state, abk_tm->servo_position, abk_tm->estimated_cd, abk_tm->pid_error, abk_tm->z, abk_tm->vz, abk_tm->v_mod, abk_tm->trajectory);
-}
-
-/**
- * @brief Encode a abk_tm 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 abk_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_abk_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_abk_tm_t* abk_tm)
-{
- return mavlink_msg_abk_tm_pack_chan(system_id, component_id, chan, msg, abk_tm->timestamp, abk_tm->state, abk_tm->servo_position, abk_tm->estimated_cd, abk_tm->pid_error, abk_tm->z, abk_tm->vz, abk_tm->v_mod, abk_tm->trajectory);
-}
-
-/**
- * @brief Send a abk_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [ms] When was this logged
- * @param state Aerobrakes FSM state
- * @param servo_position [deg] Aerobrakes opening angle
- * @param estimated_cd Drag estimated by the control algorithm
- * @param pid_error Error of the PID controller at each step
- * @param z [m] Input altitude
- * @param vz [m/s] Input vertical speed
- * @param v_mod [m/s] Input speed magnitude
- * @param trajectory Chosen trajectory to be followed
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_abk_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float servo_position, float estimated_cd, float pid_error, float z, float vz, float v_mod, uint8_t trajectory)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ABK_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, servo_position);
- _mav_put_float(buf, 12, estimated_cd);
- _mav_put_float(buf, 16, pid_error);
- _mav_put_float(buf, 20, z);
- _mav_put_float(buf, 24, vz);
- _mav_put_float(buf, 28, v_mod);
- _mav_put_uint8_t(buf, 32, state);
- _mav_put_uint8_t(buf, 33, trajectory);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ABK_TM, buf, MAVLINK_MSG_ID_ABK_TM_MIN_LEN, MAVLINK_MSG_ID_ABK_TM_LEN, MAVLINK_MSG_ID_ABK_TM_CRC);
-#else
- mavlink_abk_tm_t packet;
- packet.timestamp = timestamp;
- packet.servo_position = servo_position;
- packet.estimated_cd = estimated_cd;
- packet.pid_error = pid_error;
- packet.z = z;
- packet.vz = vz;
- packet.v_mod = v_mod;
- packet.state = state;
- packet.trajectory = trajectory;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ABK_TM, (const char *)&packet, MAVLINK_MSG_ID_ABK_TM_MIN_LEN, MAVLINK_MSG_ID_ABK_TM_LEN, MAVLINK_MSG_ID_ABK_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a abk_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_abk_tm_send_struct(mavlink_channel_t chan, const mavlink_abk_tm_t* abk_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_abk_tm_send(chan, abk_tm->timestamp, abk_tm->state, abk_tm->servo_position, abk_tm->estimated_cd, abk_tm->pid_error, abk_tm->z, abk_tm->vz, abk_tm->v_mod, abk_tm->trajectory);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ABK_TM, (const char *)abk_tm, MAVLINK_MSG_ID_ABK_TM_MIN_LEN, MAVLINK_MSG_ID_ABK_TM_LEN, MAVLINK_MSG_ID_ABK_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ABK_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_abk_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float servo_position, float estimated_cd, float pid_error, float z, float vz, float v_mod, uint8_t trajectory)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, servo_position);
- _mav_put_float(buf, 12, estimated_cd);
- _mav_put_float(buf, 16, pid_error);
- _mav_put_float(buf, 20, z);
- _mav_put_float(buf, 24, vz);
- _mav_put_float(buf, 28, v_mod);
- _mav_put_uint8_t(buf, 32, state);
- _mav_put_uint8_t(buf, 33, trajectory);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ABK_TM, buf, MAVLINK_MSG_ID_ABK_TM_MIN_LEN, MAVLINK_MSG_ID_ABK_TM_LEN, MAVLINK_MSG_ID_ABK_TM_CRC);
-#else
- mavlink_abk_tm_t *packet = (mavlink_abk_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->servo_position = servo_position;
- packet->estimated_cd = estimated_cd;
- packet->pid_error = pid_error;
- packet->z = z;
- packet->vz = vz;
- packet->v_mod = v_mod;
- packet->state = state;
- packet->trajectory = trajectory;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ABK_TM, (const char *)packet, MAVLINK_MSG_ID_ABK_TM_MIN_LEN, MAVLINK_MSG_ID_ABK_TM_LEN, MAVLINK_MSG_ID_ABK_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ABK_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from abk_tm message
- *
- * @return [ms] When was this logged
- */
-static inline uint64_t mavlink_msg_abk_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field state from abk_tm message
- *
- * @return Aerobrakes FSM state
- */
-static inline uint8_t mavlink_msg_abk_tm_get_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 32);
-}
-
-/**
- * @brief Get field servo_position from abk_tm message
- *
- * @return [deg] Aerobrakes opening angle
- */
-static inline float mavlink_msg_abk_tm_get_servo_position(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field estimated_cd from abk_tm message
- *
- * @return Drag estimated by the control algorithm
- */
-static inline float mavlink_msg_abk_tm_get_estimated_cd(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field pid_error from abk_tm message
- *
- * @return Error of the PID controller at each step
- */
-static inline float mavlink_msg_abk_tm_get_pid_error(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field z from abk_tm message
- *
- * @return [m] Input altitude
- */
-static inline float mavlink_msg_abk_tm_get_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field vz from abk_tm message
- *
- * @return [m/s] Input vertical speed
- */
-static inline float mavlink_msg_abk_tm_get_vz(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field v_mod from abk_tm message
- *
- * @return [m/s] Input speed magnitude
- */
-static inline float mavlink_msg_abk_tm_get_v_mod(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field trajectory from abk_tm message
- *
- * @return Chosen trajectory to be followed
- */
-static inline uint8_t mavlink_msg_abk_tm_get_trajectory(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 33);
-}
-
-/**
- * @brief Decode a abk_tm message into a struct
- *
- * @param msg The message to decode
- * @param abk_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_abk_tm_decode(const mavlink_message_t* msg, mavlink_abk_tm_t* abk_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- abk_tm->timestamp = mavlink_msg_abk_tm_get_timestamp(msg);
- abk_tm->servo_position = mavlink_msg_abk_tm_get_servo_position(msg);
- abk_tm->estimated_cd = mavlink_msg_abk_tm_get_estimated_cd(msg);
- abk_tm->pid_error = mavlink_msg_abk_tm_get_pid_error(msg);
- abk_tm->z = mavlink_msg_abk_tm_get_z(msg);
- abk_tm->vz = mavlink_msg_abk_tm_get_vz(msg);
- abk_tm->v_mod = mavlink_msg_abk_tm_get_v_mod(msg);
- abk_tm->state = mavlink_msg_abk_tm_get_state(msg);
- abk_tm->trajectory = mavlink_msg_abk_tm_get_trajectory(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ABK_TM_LEN? msg->len : MAVLINK_MSG_ID_ABK_TM_LEN;
- memset(abk_tm, 0, MAVLINK_MSG_ID_ABK_TM_LEN);
- memcpy(abk_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_ack_tm.h b/mavlink_lib/lynx/mavlink_msg_ack_tm.h
deleted file mode 100644
index cde26ee2c5160270c275dc1ab1c228d0890bc741..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_ack_tm.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE ACK_TM PACKING
-
-#define MAVLINK_MSG_ID_ACK_TM 130
-
-MAVPACKED(
-typedef struct __mavlink_ack_tm_t {
- uint8_t recv_msgid; /*< Message id of the received message.*/
- uint8_t seq_ack; /*< Sequence number of the received message.*/
-}) mavlink_ack_tm_t;
-
-#define MAVLINK_MSG_ID_ACK_TM_LEN 2
-#define MAVLINK_MSG_ID_ACK_TM_MIN_LEN 2
-#define MAVLINK_MSG_ID_130_LEN 2
-#define MAVLINK_MSG_ID_130_MIN_LEN 2
-
-#define MAVLINK_MSG_ID_ACK_TM_CRC 50
-#define MAVLINK_MSG_ID_130_CRC 50
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ACK_TM { \
- 130, \
- "ACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_ack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_ack_tm_t, seq_ack) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ACK_TM { \
- "ACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_ack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_ack_tm_t, seq_ack) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ack_tm 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 recv_msgid Message id of the received message.
- * @param seq_ack Sequence number of the received message.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ack_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACK_TM_LEN);
-#else
- mavlink_ack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ACK_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-}
-
-/**
- * @brief Pack a ack_tm 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 recv_msgid Message id of the received message.
- * @param seq_ack Sequence number of the received message.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ack_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t recv_msgid,uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACK_TM_LEN);
-#else
- mavlink_ack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ACK_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-}
-
-/**
- * @brief Encode a ack_tm 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 ack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ack_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ack_tm_t* ack_tm)
-{
- return mavlink_msg_ack_tm_pack(system_id, component_id, msg, ack_tm->recv_msgid, ack_tm->seq_ack);
-}
-
-/**
- * @brief Encode a ack_tm 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 ack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ack_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ack_tm_t* ack_tm)
-{
- return mavlink_msg_ack_tm_pack_chan(system_id, component_id, chan, msg, ack_tm->recv_msgid, ack_tm->seq_ack);
-}
-
-/**
- * @brief Send a ack_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param recv_msgid Message id of the received message.
- * @param seq_ack Sequence number of the received message.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ack_tm_send(mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, buf, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#else
- mavlink_ack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, (const char *)&packet, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a ack_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ack_tm_send_struct(mavlink_channel_t chan, const mavlink_ack_tm_t* ack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ack_tm_send(chan, ack_tm->recv_msgid, ack_tm->seq_ack);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, (const char *)ack_tm, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ACK_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_ack_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, buf, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#else
- mavlink_ack_tm_t *packet = (mavlink_ack_tm_t *)msgbuf;
- packet->recv_msgid = recv_msgid;
- packet->seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, (const char *)packet, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ACK_TM UNPACKING
-
-
-/**
- * @brief Get field recv_msgid from ack_tm message
- *
- * @return Message id of the received message.
- */
-static inline uint8_t mavlink_msg_ack_tm_get_recv_msgid(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field seq_ack from ack_tm message
- *
- * @return Sequence number of the received message.
- */
-static inline uint8_t mavlink_msg_ack_tm_get_seq_ack(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Decode a ack_tm message into a struct
- *
- * @param msg The message to decode
- * @param ack_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ack_tm_decode(const mavlink_message_t* msg, mavlink_ack_tm_t* ack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ack_tm->recv_msgid = mavlink_msg_ack_tm_get_recv_msgid(msg);
- ack_tm->seq_ack = mavlink_msg_ack_tm_get_seq_ack(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ACK_TM_LEN? msg->len : MAVLINK_MSG_ID_ACK_TM_LEN;
- memset(ack_tm, 0, MAVLINK_MSG_ID_ACK_TM_LEN);
- memcpy(ack_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_ada_tm.h b/mavlink_lib/lynx/mavlink_msg_ada_tm.h
deleted file mode 100644
index 5867489a7daec6cd49437b9295ac9779d6de9c20..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_ada_tm.h
+++ /dev/null
@@ -1,588 +0,0 @@
-#pragma once
-// MESSAGE ADA_TM PACKING
-
-#define MAVLINK_MSG_ID_ADA_TM 167
-
-MAVPACKED(
-typedef struct __mavlink_ada_tm_t {
- uint64_t timestamp; /*< [ms] When was this logged*/
- float target_dpl_altitude; /*< Target deployment altitude*/
- float kalman_x0; /*< Kalman state variable 0 (pressure)*/
- float kalman_x1; /*< Kalman state variable 1 (pressure velocity)*/
- float kalman_x2; /*< Kalman state variable 2 (pressure acceleration)*/
- float vert_speed; /*< [m/s] Vertical speed computed by the ADA*/
- float msl_altitude; /*< [m] Altitude w.r.t. mean sea level*/
- float ref_pressure; /*< [Pa] Calibration pressure*/
- float ref_altitude; /*< [m] Calibration altitude*/
- float ref_temperature; /*< [degC] Calibration temperature*/
- float msl_pressure; /*< [Pa] Expected pressure at mean sea level*/
- float msl_temperature; /*< [degC] Expected temperature at mean sea level*/
- uint8_t state; /*< ADA current state*/
- uint8_t apogee_reached; /*< True if apogee has been reached*/
- uint8_t aerobrakes_disabled; /*< True if aerobrakes have been disabled*/
- uint8_t dpl_altitude_reached; /*< True if aerobrakes have been disabled*/
-}) mavlink_ada_tm_t;
-
-#define MAVLINK_MSG_ID_ADA_TM_LEN 56
-#define MAVLINK_MSG_ID_ADA_TM_MIN_LEN 56
-#define MAVLINK_MSG_ID_167_LEN 56
-#define MAVLINK_MSG_ID_167_MIN_LEN 56
-
-#define MAVLINK_MSG_ID_ADA_TM_CRC 76
-#define MAVLINK_MSG_ID_167_CRC 76
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ADA_TM { \
- 167, \
- "ADA_TM", \
- 16, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ada_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_ada_tm_t, state) }, \
- { "apogee_reached", NULL, MAVLINK_TYPE_UINT8_T, 0, 53, offsetof(mavlink_ada_tm_t, apogee_reached) }, \
- { "aerobrakes_disabled", NULL, MAVLINK_TYPE_UINT8_T, 0, 54, offsetof(mavlink_ada_tm_t, aerobrakes_disabled) }, \
- { "dpl_altitude_reached", NULL, MAVLINK_TYPE_UINT8_T, 0, 55, offsetof(mavlink_ada_tm_t, dpl_altitude_reached) }, \
- { "target_dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ada_tm_t, target_dpl_altitude) }, \
- { "kalman_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ada_tm_t, kalman_x0) }, \
- { "kalman_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ada_tm_t, kalman_x1) }, \
- { "kalman_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ada_tm_t, kalman_x2) }, \
- { "vert_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ada_tm_t, vert_speed) }, \
- { "msl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_ada_tm_t, msl_altitude) }, \
- { "ref_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_ada_tm_t, ref_pressure) }, \
- { "ref_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_ada_tm_t, ref_altitude) }, \
- { "ref_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_ada_tm_t, ref_temperature) }, \
- { "msl_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_ada_tm_t, msl_pressure) }, \
- { "msl_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_ada_tm_t, msl_temperature) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ADA_TM { \
- "ADA_TM", \
- 16, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ada_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_ada_tm_t, state) }, \
- { "apogee_reached", NULL, MAVLINK_TYPE_UINT8_T, 0, 53, offsetof(mavlink_ada_tm_t, apogee_reached) }, \
- { "aerobrakes_disabled", NULL, MAVLINK_TYPE_UINT8_T, 0, 54, offsetof(mavlink_ada_tm_t, aerobrakes_disabled) }, \
- { "dpl_altitude_reached", NULL, MAVLINK_TYPE_UINT8_T, 0, 55, offsetof(mavlink_ada_tm_t, dpl_altitude_reached) }, \
- { "target_dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ada_tm_t, target_dpl_altitude) }, \
- { "kalman_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ada_tm_t, kalman_x0) }, \
- { "kalman_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ada_tm_t, kalman_x1) }, \
- { "kalman_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ada_tm_t, kalman_x2) }, \
- { "vert_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ada_tm_t, vert_speed) }, \
- { "msl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_ada_tm_t, msl_altitude) }, \
- { "ref_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_ada_tm_t, ref_pressure) }, \
- { "ref_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_ada_tm_t, ref_altitude) }, \
- { "ref_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_ada_tm_t, ref_temperature) }, \
- { "msl_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_ada_tm_t, msl_pressure) }, \
- { "msl_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_ada_tm_t, msl_temperature) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ada_tm 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] When was this logged
- * @param state ADA current state
- * @param apogee_reached True if apogee has been reached
- * @param aerobrakes_disabled True if aerobrakes have been disabled
- * @param dpl_altitude_reached True if aerobrakes have been disabled
- * @param target_dpl_altitude Target deployment altitude
- * @param kalman_x0 Kalman state variable 0 (pressure)
- * @param kalman_x1 Kalman state variable 1 (pressure velocity)
- * @param kalman_x2 Kalman state variable 2 (pressure acceleration)
- * @param vert_speed [m/s] Vertical speed computed by the ADA
- * @param msl_altitude [m] Altitude w.r.t. mean sea level
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_altitude [m] Calibration altitude
- * @param ref_temperature [degC] Calibration temperature
- * @param msl_pressure [Pa] Expected pressure at mean sea level
- * @param msl_temperature [degC] Expected temperature at mean sea level
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ada_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t state, uint8_t apogee_reached, uint8_t aerobrakes_disabled, uint8_t dpl_altitude_reached, float target_dpl_altitude, float kalman_x0, float kalman_x1, float kalman_x2, float vert_speed, float msl_altitude, float ref_pressure, float ref_altitude, float ref_temperature, float msl_pressure, float msl_temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, target_dpl_altitude);
- _mav_put_float(buf, 12, kalman_x0);
- _mav_put_float(buf, 16, kalman_x1);
- _mav_put_float(buf, 20, kalman_x2);
- _mav_put_float(buf, 24, vert_speed);
- _mav_put_float(buf, 28, msl_altitude);
- _mav_put_float(buf, 32, ref_pressure);
- _mav_put_float(buf, 36, ref_altitude);
- _mav_put_float(buf, 40, ref_temperature);
- _mav_put_float(buf, 44, msl_pressure);
- _mav_put_float(buf, 48, msl_temperature);
- _mav_put_uint8_t(buf, 52, state);
- _mav_put_uint8_t(buf, 53, apogee_reached);
- _mav_put_uint8_t(buf, 54, aerobrakes_disabled);
- _mav_put_uint8_t(buf, 55, dpl_altitude_reached);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADA_TM_LEN);
-#else
- mavlink_ada_tm_t packet;
- packet.timestamp = timestamp;
- packet.target_dpl_altitude = target_dpl_altitude;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.vert_speed = vert_speed;
- packet.msl_altitude = msl_altitude;
- packet.ref_pressure = ref_pressure;
- packet.ref_altitude = ref_altitude;
- packet.ref_temperature = ref_temperature;
- packet.msl_pressure = msl_pressure;
- packet.msl_temperature = msl_temperature;
- packet.state = state;
- packet.apogee_reached = apogee_reached;
- packet.aerobrakes_disabled = aerobrakes_disabled;
- packet.dpl_altitude_reached = dpl_altitude_reached;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADA_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADA_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-}
-
-/**
- * @brief Pack a ada_tm 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] When was this logged
- * @param state ADA current state
- * @param apogee_reached True if apogee has been reached
- * @param aerobrakes_disabled True if aerobrakes have been disabled
- * @param dpl_altitude_reached True if aerobrakes have been disabled
- * @param target_dpl_altitude Target deployment altitude
- * @param kalman_x0 Kalman state variable 0 (pressure)
- * @param kalman_x1 Kalman state variable 1 (pressure velocity)
- * @param kalman_x2 Kalman state variable 2 (pressure acceleration)
- * @param vert_speed [m/s] Vertical speed computed by the ADA
- * @param msl_altitude [m] Altitude w.r.t. mean sea level
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_altitude [m] Calibration altitude
- * @param ref_temperature [degC] Calibration temperature
- * @param msl_pressure [Pa] Expected pressure at mean sea level
- * @param msl_temperature [degC] Expected temperature at mean sea level
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ada_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t state,uint8_t apogee_reached,uint8_t aerobrakes_disabled,uint8_t dpl_altitude_reached,float target_dpl_altitude,float kalman_x0,float kalman_x1,float kalman_x2,float vert_speed,float msl_altitude,float ref_pressure,float ref_altitude,float ref_temperature,float msl_pressure,float msl_temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, target_dpl_altitude);
- _mav_put_float(buf, 12, kalman_x0);
- _mav_put_float(buf, 16, kalman_x1);
- _mav_put_float(buf, 20, kalman_x2);
- _mav_put_float(buf, 24, vert_speed);
- _mav_put_float(buf, 28, msl_altitude);
- _mav_put_float(buf, 32, ref_pressure);
- _mav_put_float(buf, 36, ref_altitude);
- _mav_put_float(buf, 40, ref_temperature);
- _mav_put_float(buf, 44, msl_pressure);
- _mav_put_float(buf, 48, msl_temperature);
- _mav_put_uint8_t(buf, 52, state);
- _mav_put_uint8_t(buf, 53, apogee_reached);
- _mav_put_uint8_t(buf, 54, aerobrakes_disabled);
- _mav_put_uint8_t(buf, 55, dpl_altitude_reached);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADA_TM_LEN);
-#else
- mavlink_ada_tm_t packet;
- packet.timestamp = timestamp;
- packet.target_dpl_altitude = target_dpl_altitude;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.vert_speed = vert_speed;
- packet.msl_altitude = msl_altitude;
- packet.ref_pressure = ref_pressure;
- packet.ref_altitude = ref_altitude;
- packet.ref_temperature = ref_temperature;
- packet.msl_pressure = msl_pressure;
- packet.msl_temperature = msl_temperature;
- packet.state = state;
- packet.apogee_reached = apogee_reached;
- packet.aerobrakes_disabled = aerobrakes_disabled;
- packet.dpl_altitude_reached = dpl_altitude_reached;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADA_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADA_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-}
-
-/**
- * @brief Encode a ada_tm 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 ada_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ada_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ada_tm_t* ada_tm)
-{
- return mavlink_msg_ada_tm_pack(system_id, component_id, msg, ada_tm->timestamp, ada_tm->state, ada_tm->apogee_reached, ada_tm->aerobrakes_disabled, ada_tm->dpl_altitude_reached, ada_tm->target_dpl_altitude, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->vert_speed, ada_tm->msl_altitude, ada_tm->ref_pressure, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_pressure, ada_tm->msl_temperature);
-}
-
-/**
- * @brief Encode a ada_tm 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 ada_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ada_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ada_tm_t* ada_tm)
-{
- return mavlink_msg_ada_tm_pack_chan(system_id, component_id, chan, msg, ada_tm->timestamp, ada_tm->state, ada_tm->apogee_reached, ada_tm->aerobrakes_disabled, ada_tm->dpl_altitude_reached, ada_tm->target_dpl_altitude, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->vert_speed, ada_tm->msl_altitude, ada_tm->ref_pressure, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_pressure, ada_tm->msl_temperature);
-}
-
-/**
- * @brief Send a ada_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [ms] When was this logged
- * @param state ADA current state
- * @param apogee_reached True if apogee has been reached
- * @param aerobrakes_disabled True if aerobrakes have been disabled
- * @param dpl_altitude_reached True if aerobrakes have been disabled
- * @param target_dpl_altitude Target deployment altitude
- * @param kalman_x0 Kalman state variable 0 (pressure)
- * @param kalman_x1 Kalman state variable 1 (pressure velocity)
- * @param kalman_x2 Kalman state variable 2 (pressure acceleration)
- * @param vert_speed [m/s] Vertical speed computed by the ADA
- * @param msl_altitude [m] Altitude w.r.t. mean sea level
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_altitude [m] Calibration altitude
- * @param ref_temperature [degC] Calibration temperature
- * @param msl_pressure [Pa] Expected pressure at mean sea level
- * @param msl_temperature [degC] Expected temperature at mean sea level
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ada_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state, uint8_t apogee_reached, uint8_t aerobrakes_disabled, uint8_t dpl_altitude_reached, float target_dpl_altitude, float kalman_x0, float kalman_x1, float kalman_x2, float vert_speed, float msl_altitude, float ref_pressure, float ref_altitude, float ref_temperature, float msl_pressure, float msl_temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, target_dpl_altitude);
- _mav_put_float(buf, 12, kalman_x0);
- _mav_put_float(buf, 16, kalman_x1);
- _mav_put_float(buf, 20, kalman_x2);
- _mav_put_float(buf, 24, vert_speed);
- _mav_put_float(buf, 28, msl_altitude);
- _mav_put_float(buf, 32, ref_pressure);
- _mav_put_float(buf, 36, ref_altitude);
- _mav_put_float(buf, 40, ref_temperature);
- _mav_put_float(buf, 44, msl_pressure);
- _mav_put_float(buf, 48, msl_temperature);
- _mav_put_uint8_t(buf, 52, state);
- _mav_put_uint8_t(buf, 53, apogee_reached);
- _mav_put_uint8_t(buf, 54, aerobrakes_disabled);
- _mav_put_uint8_t(buf, 55, dpl_altitude_reached);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, buf, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#else
- mavlink_ada_tm_t packet;
- packet.timestamp = timestamp;
- packet.target_dpl_altitude = target_dpl_altitude;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.vert_speed = vert_speed;
- packet.msl_altitude = msl_altitude;
- packet.ref_pressure = ref_pressure;
- packet.ref_altitude = ref_altitude;
- packet.ref_temperature = ref_temperature;
- packet.msl_pressure = msl_pressure;
- packet.msl_temperature = msl_temperature;
- packet.state = state;
- packet.apogee_reached = apogee_reached;
- packet.aerobrakes_disabled = aerobrakes_disabled;
- packet.dpl_altitude_reached = dpl_altitude_reached;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, (const char *)&packet, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a ada_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ada_tm_send_struct(mavlink_channel_t chan, const mavlink_ada_tm_t* ada_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ada_tm_send(chan, ada_tm->timestamp, ada_tm->state, ada_tm->apogee_reached, ada_tm->aerobrakes_disabled, ada_tm->dpl_altitude_reached, ada_tm->target_dpl_altitude, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->vert_speed, ada_tm->msl_altitude, ada_tm->ref_pressure, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_pressure, ada_tm->msl_temperature);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, (const char *)ada_tm, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ADA_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_ada_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t state, uint8_t apogee_reached, uint8_t aerobrakes_disabled, uint8_t dpl_altitude_reached, float target_dpl_altitude, float kalman_x0, float kalman_x1, float kalman_x2, float vert_speed, float msl_altitude, float ref_pressure, float ref_altitude, float ref_temperature, float msl_pressure, float msl_temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, target_dpl_altitude);
- _mav_put_float(buf, 12, kalman_x0);
- _mav_put_float(buf, 16, kalman_x1);
- _mav_put_float(buf, 20, kalman_x2);
- _mav_put_float(buf, 24, vert_speed);
- _mav_put_float(buf, 28, msl_altitude);
- _mav_put_float(buf, 32, ref_pressure);
- _mav_put_float(buf, 36, ref_altitude);
- _mav_put_float(buf, 40, ref_temperature);
- _mav_put_float(buf, 44, msl_pressure);
- _mav_put_float(buf, 48, msl_temperature);
- _mav_put_uint8_t(buf, 52, state);
- _mav_put_uint8_t(buf, 53, apogee_reached);
- _mav_put_uint8_t(buf, 54, aerobrakes_disabled);
- _mav_put_uint8_t(buf, 55, dpl_altitude_reached);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, buf, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#else
- mavlink_ada_tm_t *packet = (mavlink_ada_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->target_dpl_altitude = target_dpl_altitude;
- packet->kalman_x0 = kalman_x0;
- packet->kalman_x1 = kalman_x1;
- packet->kalman_x2 = kalman_x2;
- packet->vert_speed = vert_speed;
- packet->msl_altitude = msl_altitude;
- packet->ref_pressure = ref_pressure;
- packet->ref_altitude = ref_altitude;
- packet->ref_temperature = ref_temperature;
- packet->msl_pressure = msl_pressure;
- packet->msl_temperature = msl_temperature;
- packet->state = state;
- packet->apogee_reached = apogee_reached;
- packet->aerobrakes_disabled = aerobrakes_disabled;
- packet->dpl_altitude_reached = dpl_altitude_reached;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, (const char *)packet, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ADA_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from ada_tm message
- *
- * @return [ms] When was this logged
- */
-static inline uint64_t mavlink_msg_ada_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field state from ada_tm message
- *
- * @return ADA current state
- */
-static inline uint8_t mavlink_msg_ada_tm_get_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 52);
-}
-
-/**
- * @brief Get field apogee_reached from ada_tm message
- *
- * @return True if apogee has been reached
- */
-static inline uint8_t mavlink_msg_ada_tm_get_apogee_reached(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 53);
-}
-
-/**
- * @brief Get field aerobrakes_disabled from ada_tm message
- *
- * @return True if aerobrakes have been disabled
- */
-static inline uint8_t mavlink_msg_ada_tm_get_aerobrakes_disabled(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 54);
-}
-
-/**
- * @brief Get field dpl_altitude_reached from ada_tm message
- *
- * @return True if aerobrakes have been disabled
- */
-static inline uint8_t mavlink_msg_ada_tm_get_dpl_altitude_reached(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 55);
-}
-
-/**
- * @brief Get field target_dpl_altitude from ada_tm message
- *
- * @return Target deployment altitude
- */
-static inline float mavlink_msg_ada_tm_get_target_dpl_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field kalman_x0 from ada_tm message
- *
- * @return Kalman state variable 0 (pressure)
- */
-static inline float mavlink_msg_ada_tm_get_kalman_x0(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field kalman_x1 from ada_tm message
- *
- * @return Kalman state variable 1 (pressure velocity)
- */
-static inline float mavlink_msg_ada_tm_get_kalman_x1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field kalman_x2 from ada_tm message
- *
- * @return Kalman state variable 2 (pressure acceleration)
- */
-static inline float mavlink_msg_ada_tm_get_kalman_x2(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field vert_speed from ada_tm message
- *
- * @return [m/s] Vertical speed computed by the ADA
- */
-static inline float mavlink_msg_ada_tm_get_vert_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field msl_altitude from ada_tm message
- *
- * @return [m] Altitude w.r.t. mean sea level
- */
-static inline float mavlink_msg_ada_tm_get_msl_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field ref_pressure from ada_tm message
- *
- * @return [Pa] Calibration pressure
- */
-static inline float mavlink_msg_ada_tm_get_ref_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field ref_altitude from ada_tm message
- *
- * @return [m] Calibration altitude
- */
-static inline float mavlink_msg_ada_tm_get_ref_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field ref_temperature from ada_tm message
- *
- * @return [degC] Calibration temperature
- */
-static inline float mavlink_msg_ada_tm_get_ref_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field msl_pressure from ada_tm message
- *
- * @return [Pa] Expected pressure at mean sea level
- */
-static inline float mavlink_msg_ada_tm_get_msl_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field msl_temperature from ada_tm message
- *
- * @return [degC] Expected temperature at mean sea level
- */
-static inline float mavlink_msg_ada_tm_get_msl_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Decode a ada_tm message into a struct
- *
- * @param msg The message to decode
- * @param ada_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ada_tm_decode(const mavlink_message_t* msg, mavlink_ada_tm_t* ada_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ada_tm->timestamp = mavlink_msg_ada_tm_get_timestamp(msg);
- ada_tm->target_dpl_altitude = mavlink_msg_ada_tm_get_target_dpl_altitude(msg);
- ada_tm->kalman_x0 = mavlink_msg_ada_tm_get_kalman_x0(msg);
- ada_tm->kalman_x1 = mavlink_msg_ada_tm_get_kalman_x1(msg);
- ada_tm->kalman_x2 = mavlink_msg_ada_tm_get_kalman_x2(msg);
- ada_tm->vert_speed = mavlink_msg_ada_tm_get_vert_speed(msg);
- ada_tm->msl_altitude = mavlink_msg_ada_tm_get_msl_altitude(msg);
- ada_tm->ref_pressure = mavlink_msg_ada_tm_get_ref_pressure(msg);
- ada_tm->ref_altitude = mavlink_msg_ada_tm_get_ref_altitude(msg);
- ada_tm->ref_temperature = mavlink_msg_ada_tm_get_ref_temperature(msg);
- ada_tm->msl_pressure = mavlink_msg_ada_tm_get_msl_pressure(msg);
- ada_tm->msl_temperature = mavlink_msg_ada_tm_get_msl_temperature(msg);
- ada_tm->state = mavlink_msg_ada_tm_get_state(msg);
- ada_tm->apogee_reached = mavlink_msg_ada_tm_get_apogee_reached(msg);
- ada_tm->aerobrakes_disabled = mavlink_msg_ada_tm_get_aerobrakes_disabled(msg);
- ada_tm->dpl_altitude_reached = mavlink_msg_ada_tm_get_dpl_altitude_reached(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ADA_TM_LEN? msg->len : MAVLINK_MSG_ID_ADA_TM_LEN;
- memset(ada_tm, 0, MAVLINK_MSG_ID_ADA_TM_LEN);
- memcpy(ada_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_adc_tm.h b/mavlink_lib/lynx/mavlink_msg_adc_tm.h
deleted file mode 100644
index e50a4728900b86532ef355776ef23250da7b84ad..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_adc_tm.h
+++ /dev/null
@@ -1,338 +0,0 @@
-#pragma once
-// MESSAGE ADC_TM PACKING
-
-#define MAVLINK_MSG_ID_ADC_TM 171
-
-MAVPACKED(
-typedef struct __mavlink_adc_tm_t {
- uint64_t timestamp; /*< [ms] When was this logged*/
- float pitot_pressure; /*< [Pa] Pitot tube dynamic pressure*/
- float dpl_pressure; /*< [Pa] Deployment vane internal pressure*/
- float static_pressure; /*< [Pa] Static ports pressure*/
- float bat_voltage; /*< [V] LiPo battery voltage*/
- float bat_voltage_5v; /*< [V] 5V power supply*/
-}) mavlink_adc_tm_t;
-
-#define MAVLINK_MSG_ID_ADC_TM_LEN 28
-#define MAVLINK_MSG_ID_ADC_TM_MIN_LEN 28
-#define MAVLINK_MSG_ID_171_LEN 28
-#define MAVLINK_MSG_ID_171_MIN_LEN 28
-
-#define MAVLINK_MSG_ID_ADC_TM_CRC 135
-#define MAVLINK_MSG_ID_171_CRC 135
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ADC_TM { \
- 171, \
- "ADC_TM", \
- 6, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_adc_tm_t, timestamp) }, \
- { "pitot_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_adc_tm_t, pitot_pressure) }, \
- { "dpl_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_adc_tm_t, dpl_pressure) }, \
- { "static_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_adc_tm_t, static_pressure) }, \
- { "bat_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_adc_tm_t, bat_voltage) }, \
- { "bat_voltage_5v", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_adc_tm_t, bat_voltage_5v) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ADC_TM { \
- "ADC_TM", \
- 6, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_adc_tm_t, timestamp) }, \
- { "pitot_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_adc_tm_t, pitot_pressure) }, \
- { "dpl_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_adc_tm_t, dpl_pressure) }, \
- { "static_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_adc_tm_t, static_pressure) }, \
- { "bat_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_adc_tm_t, bat_voltage) }, \
- { "bat_voltage_5v", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_adc_tm_t, bat_voltage_5v) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a adc_tm 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] When was this logged
- * @param pitot_pressure [Pa] Pitot tube dynamic pressure
- * @param dpl_pressure [Pa] Deployment vane internal pressure
- * @param static_pressure [Pa] Static ports pressure
- * @param bat_voltage [V] LiPo battery voltage
- * @param bat_voltage_5v [V] 5V power supply
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_adc_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, float pitot_pressure, float dpl_pressure, float static_pressure, float bat_voltage, float bat_voltage_5v)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pitot_pressure);
- _mav_put_float(buf, 12, dpl_pressure);
- _mav_put_float(buf, 16, static_pressure);
- _mav_put_float(buf, 20, bat_voltage);
- _mav_put_float(buf, 24, bat_voltage_5v);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADC_TM_LEN);
-#else
- mavlink_adc_tm_t packet;
- packet.timestamp = timestamp;
- packet.pitot_pressure = pitot_pressure;
- packet.dpl_pressure = dpl_pressure;
- packet.static_pressure = static_pressure;
- packet.bat_voltage = bat_voltage;
- packet.bat_voltage_5v = bat_voltage_5v;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADC_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADC_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-}
-
-/**
- * @brief Pack a adc_tm 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] When was this logged
- * @param pitot_pressure [Pa] Pitot tube dynamic pressure
- * @param dpl_pressure [Pa] Deployment vane internal pressure
- * @param static_pressure [Pa] Static ports pressure
- * @param bat_voltage [V] LiPo battery voltage
- * @param bat_voltage_5v [V] 5V power supply
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_adc_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,float pitot_pressure,float dpl_pressure,float static_pressure,float bat_voltage,float bat_voltage_5v)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pitot_pressure);
- _mav_put_float(buf, 12, dpl_pressure);
- _mav_put_float(buf, 16, static_pressure);
- _mav_put_float(buf, 20, bat_voltage);
- _mav_put_float(buf, 24, bat_voltage_5v);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADC_TM_LEN);
-#else
- mavlink_adc_tm_t packet;
- packet.timestamp = timestamp;
- packet.pitot_pressure = pitot_pressure;
- packet.dpl_pressure = dpl_pressure;
- packet.static_pressure = static_pressure;
- packet.bat_voltage = bat_voltage;
- packet.bat_voltage_5v = bat_voltage_5v;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADC_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADC_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-}
-
-/**
- * @brief Encode a adc_tm 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 adc_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_adc_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_adc_tm_t* adc_tm)
-{
- return mavlink_msg_adc_tm_pack(system_id, component_id, msg, adc_tm->timestamp, adc_tm->pitot_pressure, adc_tm->dpl_pressure, adc_tm->static_pressure, adc_tm->bat_voltage, adc_tm->bat_voltage_5v);
-}
-
-/**
- * @brief Encode a adc_tm 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 adc_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_adc_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_adc_tm_t* adc_tm)
-{
- return mavlink_msg_adc_tm_pack_chan(system_id, component_id, chan, msg, adc_tm->timestamp, adc_tm->pitot_pressure, adc_tm->dpl_pressure, adc_tm->static_pressure, adc_tm->bat_voltage, adc_tm->bat_voltage_5v);
-}
-
-/**
- * @brief Send a adc_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [ms] When was this logged
- * @param pitot_pressure [Pa] Pitot tube dynamic pressure
- * @param dpl_pressure [Pa] Deployment vane internal pressure
- * @param static_pressure [Pa] Static ports pressure
- * @param bat_voltage [V] LiPo battery voltage
- * @param bat_voltage_5v [V] 5V power supply
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_adc_tm_send(mavlink_channel_t chan, uint64_t timestamp, float pitot_pressure, float dpl_pressure, float static_pressure, float bat_voltage, float bat_voltage_5v)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pitot_pressure);
- _mav_put_float(buf, 12, dpl_pressure);
- _mav_put_float(buf, 16, static_pressure);
- _mav_put_float(buf, 20, bat_voltage);
- _mav_put_float(buf, 24, bat_voltage_5v);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, buf, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#else
- mavlink_adc_tm_t packet;
- packet.timestamp = timestamp;
- packet.pitot_pressure = pitot_pressure;
- packet.dpl_pressure = dpl_pressure;
- packet.static_pressure = static_pressure;
- packet.bat_voltage = bat_voltage;
- packet.bat_voltage_5v = bat_voltage_5v;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)&packet, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a adc_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_adc_tm_send_struct(mavlink_channel_t chan, const mavlink_adc_tm_t* adc_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_adc_tm_send(chan, adc_tm->timestamp, adc_tm->pitot_pressure, adc_tm->dpl_pressure, adc_tm->static_pressure, adc_tm->bat_voltage, adc_tm->bat_voltage_5v);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)adc_tm, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ADC_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_adc_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float pitot_pressure, float dpl_pressure, float static_pressure, float bat_voltage, float bat_voltage_5v)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pitot_pressure);
- _mav_put_float(buf, 12, dpl_pressure);
- _mav_put_float(buf, 16, static_pressure);
- _mav_put_float(buf, 20, bat_voltage);
- _mav_put_float(buf, 24, bat_voltage_5v);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, buf, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#else
- mavlink_adc_tm_t *packet = (mavlink_adc_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->pitot_pressure = pitot_pressure;
- packet->dpl_pressure = dpl_pressure;
- packet->static_pressure = static_pressure;
- packet->bat_voltage = bat_voltage;
- packet->bat_voltage_5v = bat_voltage_5v;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)packet, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ADC_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from adc_tm message
- *
- * @return [ms] When was this logged
- */
-static inline uint64_t mavlink_msg_adc_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field pitot_pressure from adc_tm message
- *
- * @return [Pa] Pitot tube dynamic pressure
- */
-static inline float mavlink_msg_adc_tm_get_pitot_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field dpl_pressure from adc_tm message
- *
- * @return [Pa] Deployment vane internal pressure
- */
-static inline float mavlink_msg_adc_tm_get_dpl_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field static_pressure from adc_tm message
- *
- * @return [Pa] Static ports pressure
- */
-static inline float mavlink_msg_adc_tm_get_static_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field bat_voltage from adc_tm message
- *
- * @return [V] LiPo battery voltage
- */
-static inline float mavlink_msg_adc_tm_get_bat_voltage(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field bat_voltage_5v from adc_tm message
- *
- * @return [V] 5V power supply
- */
-static inline float mavlink_msg_adc_tm_get_bat_voltage_5v(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Decode a adc_tm message into a struct
- *
- * @param msg The message to decode
- * @param adc_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_adc_tm_decode(const mavlink_message_t* msg, mavlink_adc_tm_t* adc_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- adc_tm->timestamp = mavlink_msg_adc_tm_get_timestamp(msg);
- adc_tm->pitot_pressure = mavlink_msg_adc_tm_get_pitot_pressure(msg);
- adc_tm->dpl_pressure = mavlink_msg_adc_tm_get_dpl_pressure(msg);
- adc_tm->static_pressure = mavlink_msg_adc_tm_get_static_pressure(msg);
- adc_tm->bat_voltage = mavlink_msg_adc_tm_get_bat_voltage(msg);
- adc_tm->bat_voltage_5v = mavlink_msg_adc_tm_get_bat_voltage_5v(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ADC_TM_LEN? msg->len : MAVLINK_MSG_ID_ADC_TM_LEN;
- memset(adc_tm, 0, MAVLINK_MSG_ID_ADC_TM_LEN);
- memcpy(adc_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_bmx160_tm.h b/mavlink_lib/lynx/mavlink_msg_bmx160_tm.h
deleted file mode 100644
index 489f4de7a6dd0c6eb08e98b53f5e0ce0dccfe59b..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_bmx160_tm.h
+++ /dev/null
@@ -1,463 +0,0 @@
-#pragma once
-// MESSAGE BMX160_TM PACKING
-
-#define MAVLINK_MSG_ID_BMX160_TM 173
-
-MAVPACKED(
-typedef struct __mavlink_bmx160_tm_t {
- uint64_t timestamp; /*< [ms] When was this logged*/
- float acc_x; /*< [m/s2] X axis acceleration*/
- float acc_y; /*< [m/s2] Y axis acceleration*/
- float acc_z; /*< [m/s2] Z axis acceleration*/
- float gyro_x; /*< [rad/s] X axis gyro*/
- float gyro_y; /*< [rad/s] Y axis gyro*/
- float gyro_z; /*< [rad/s] Z axis gyro*/
- float mag_x; /*< [uT] X axis compass*/
- float mag_y; /*< [uT] Y axis compass*/
- float mag_z; /*< [uT] Z axis compass*/
- float temp; /*< [deg] Temperature*/
-}) mavlink_bmx160_tm_t;
-
-#define MAVLINK_MSG_ID_BMX160_TM_LEN 48
-#define MAVLINK_MSG_ID_BMX160_TM_MIN_LEN 48
-#define MAVLINK_MSG_ID_173_LEN 48
-#define MAVLINK_MSG_ID_173_MIN_LEN 48
-
-#define MAVLINK_MSG_ID_BMX160_TM_CRC 225
-#define MAVLINK_MSG_ID_173_CRC 225
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_BMX160_TM { \
- 173, \
- "BMX160_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_bmx160_tm_t, timestamp) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_bmx160_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_bmx160_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_bmx160_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_bmx160_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_bmx160_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_bmx160_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_bmx160_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_bmx160_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_bmx160_tm_t, mag_z) }, \
- { "temp", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_bmx160_tm_t, temp) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_BMX160_TM { \
- "BMX160_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_bmx160_tm_t, timestamp) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_bmx160_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_bmx160_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_bmx160_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_bmx160_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_bmx160_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_bmx160_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_bmx160_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_bmx160_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_bmx160_tm_t, mag_z) }, \
- { "temp", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_bmx160_tm_t, temp) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a bmx160_tm 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] When was this logged
- * @param acc_x [m/s2] X axis acceleration
- * @param acc_y [m/s2] Y axis acceleration
- * @param acc_z [m/s2] Z axis acceleration
- * @param gyro_x [rad/s] X axis gyro
- * @param gyro_y [rad/s] Y axis gyro
- * @param gyro_z [rad/s] Z axis gyro
- * @param mag_x [uT] X axis compass
- * @param mag_y [uT] Y axis compass
- * @param mag_z [uT] Z axis compass
- * @param temp [deg] Temperature
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_bmx160_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, float temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_BMX160_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, mag_x);
- _mav_put_float(buf, 36, mag_y);
- _mav_put_float(buf, 40, mag_z);
- _mav_put_float(buf, 44, temp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BMX160_TM_LEN);
-#else
- mavlink_bmx160_tm_t packet;
- packet.timestamp = timestamp;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.temp = temp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BMX160_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_BMX160_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BMX160_TM_MIN_LEN, MAVLINK_MSG_ID_BMX160_TM_LEN, MAVLINK_MSG_ID_BMX160_TM_CRC);
-}
-
-/**
- * @brief Pack a bmx160_tm 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] When was this logged
- * @param acc_x [m/s2] X axis acceleration
- * @param acc_y [m/s2] Y axis acceleration
- * @param acc_z [m/s2] Z axis acceleration
- * @param gyro_x [rad/s] X axis gyro
- * @param gyro_y [rad/s] Y axis gyro
- * @param gyro_z [rad/s] Z axis gyro
- * @param mag_x [uT] X axis compass
- * @param mag_y [uT] Y axis compass
- * @param mag_z [uT] Z axis compass
- * @param temp [deg] Temperature
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_bmx160_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,float temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_BMX160_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, mag_x);
- _mav_put_float(buf, 36, mag_y);
- _mav_put_float(buf, 40, mag_z);
- _mav_put_float(buf, 44, temp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BMX160_TM_LEN);
-#else
- mavlink_bmx160_tm_t packet;
- packet.timestamp = timestamp;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.temp = temp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BMX160_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_BMX160_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BMX160_TM_MIN_LEN, MAVLINK_MSG_ID_BMX160_TM_LEN, MAVLINK_MSG_ID_BMX160_TM_CRC);
-}
-
-/**
- * @brief Encode a bmx160_tm 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 bmx160_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_bmx160_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_bmx160_tm_t* bmx160_tm)
-{
- return mavlink_msg_bmx160_tm_pack(system_id, component_id, msg, bmx160_tm->timestamp, bmx160_tm->acc_x, bmx160_tm->acc_y, bmx160_tm->acc_z, bmx160_tm->gyro_x, bmx160_tm->gyro_y, bmx160_tm->gyro_z, bmx160_tm->mag_x, bmx160_tm->mag_y, bmx160_tm->mag_z, bmx160_tm->temp);
-}
-
-/**
- * @brief Encode a bmx160_tm 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 bmx160_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_bmx160_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_bmx160_tm_t* bmx160_tm)
-{
- return mavlink_msg_bmx160_tm_pack_chan(system_id, component_id, chan, msg, bmx160_tm->timestamp, bmx160_tm->acc_x, bmx160_tm->acc_y, bmx160_tm->acc_z, bmx160_tm->gyro_x, bmx160_tm->gyro_y, bmx160_tm->gyro_z, bmx160_tm->mag_x, bmx160_tm->mag_y, bmx160_tm->mag_z, bmx160_tm->temp);
-}
-
-/**
- * @brief Send a bmx160_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [ms] When was this logged
- * @param acc_x [m/s2] X axis acceleration
- * @param acc_y [m/s2] Y axis acceleration
- * @param acc_z [m/s2] Z axis acceleration
- * @param gyro_x [rad/s] X axis gyro
- * @param gyro_y [rad/s] Y axis gyro
- * @param gyro_z [rad/s] Z axis gyro
- * @param mag_x [uT] X axis compass
- * @param mag_y [uT] Y axis compass
- * @param mag_z [uT] Z axis compass
- * @param temp [deg] Temperature
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_bmx160_tm_send(mavlink_channel_t chan, uint64_t timestamp, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, float temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_BMX160_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, mag_x);
- _mav_put_float(buf, 36, mag_y);
- _mav_put_float(buf, 40, mag_z);
- _mav_put_float(buf, 44, temp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BMX160_TM, buf, MAVLINK_MSG_ID_BMX160_TM_MIN_LEN, MAVLINK_MSG_ID_BMX160_TM_LEN, MAVLINK_MSG_ID_BMX160_TM_CRC);
-#else
- mavlink_bmx160_tm_t packet;
- packet.timestamp = timestamp;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.temp = temp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BMX160_TM, (const char *)&packet, MAVLINK_MSG_ID_BMX160_TM_MIN_LEN, MAVLINK_MSG_ID_BMX160_TM_LEN, MAVLINK_MSG_ID_BMX160_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a bmx160_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_bmx160_tm_send_struct(mavlink_channel_t chan, const mavlink_bmx160_tm_t* bmx160_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_bmx160_tm_send(chan, bmx160_tm->timestamp, bmx160_tm->acc_x, bmx160_tm->acc_y, bmx160_tm->acc_z, bmx160_tm->gyro_x, bmx160_tm->gyro_y, bmx160_tm->gyro_z, bmx160_tm->mag_x, bmx160_tm->mag_y, bmx160_tm->mag_z, bmx160_tm->temp);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BMX160_TM, (const char *)bmx160_tm, MAVLINK_MSG_ID_BMX160_TM_MIN_LEN, MAVLINK_MSG_ID_BMX160_TM_LEN, MAVLINK_MSG_ID_BMX160_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_BMX160_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_bmx160_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, float temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, mag_x);
- _mav_put_float(buf, 36, mag_y);
- _mav_put_float(buf, 40, mag_z);
- _mav_put_float(buf, 44, temp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BMX160_TM, buf, MAVLINK_MSG_ID_BMX160_TM_MIN_LEN, MAVLINK_MSG_ID_BMX160_TM_LEN, MAVLINK_MSG_ID_BMX160_TM_CRC);
-#else
- mavlink_bmx160_tm_t *packet = (mavlink_bmx160_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->acc_x = acc_x;
- packet->acc_y = acc_y;
- packet->acc_z = acc_z;
- packet->gyro_x = gyro_x;
- packet->gyro_y = gyro_y;
- packet->gyro_z = gyro_z;
- packet->mag_x = mag_x;
- packet->mag_y = mag_y;
- packet->mag_z = mag_z;
- packet->temp = temp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BMX160_TM, (const char *)packet, MAVLINK_MSG_ID_BMX160_TM_MIN_LEN, MAVLINK_MSG_ID_BMX160_TM_LEN, MAVLINK_MSG_ID_BMX160_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE BMX160_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from bmx160_tm message
- *
- * @return [ms] When was this logged
- */
-static inline uint64_t mavlink_msg_bmx160_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field acc_x from bmx160_tm message
- *
- * @return [m/s2] X axis acceleration
- */
-static inline float mavlink_msg_bmx160_tm_get_acc_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field acc_y from bmx160_tm message
- *
- * @return [m/s2] Y axis acceleration
- */
-static inline float mavlink_msg_bmx160_tm_get_acc_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field acc_z from bmx160_tm message
- *
- * @return [m/s2] Z axis acceleration
- */
-static inline float mavlink_msg_bmx160_tm_get_acc_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field gyro_x from bmx160_tm message
- *
- * @return [rad/s] X axis gyro
- */
-static inline float mavlink_msg_bmx160_tm_get_gyro_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field gyro_y from bmx160_tm message
- *
- * @return [rad/s] Y axis gyro
- */
-static inline float mavlink_msg_bmx160_tm_get_gyro_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field gyro_z from bmx160_tm message
- *
- * @return [rad/s] Z axis gyro
- */
-static inline float mavlink_msg_bmx160_tm_get_gyro_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field mag_x from bmx160_tm message
- *
- * @return [uT] X axis compass
- */
-static inline float mavlink_msg_bmx160_tm_get_mag_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field mag_y from bmx160_tm message
- *
- * @return [uT] Y axis compass
- */
-static inline float mavlink_msg_bmx160_tm_get_mag_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field mag_z from bmx160_tm message
- *
- * @return [uT] Z axis compass
- */
-static inline float mavlink_msg_bmx160_tm_get_mag_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field temp from bmx160_tm message
- *
- * @return [deg] Temperature
- */
-static inline float mavlink_msg_bmx160_tm_get_temp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Decode a bmx160_tm message into a struct
- *
- * @param msg The message to decode
- * @param bmx160_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_bmx160_tm_decode(const mavlink_message_t* msg, mavlink_bmx160_tm_t* bmx160_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- bmx160_tm->timestamp = mavlink_msg_bmx160_tm_get_timestamp(msg);
- bmx160_tm->acc_x = mavlink_msg_bmx160_tm_get_acc_x(msg);
- bmx160_tm->acc_y = mavlink_msg_bmx160_tm_get_acc_y(msg);
- bmx160_tm->acc_z = mavlink_msg_bmx160_tm_get_acc_z(msg);
- bmx160_tm->gyro_x = mavlink_msg_bmx160_tm_get_gyro_x(msg);
- bmx160_tm->gyro_y = mavlink_msg_bmx160_tm_get_gyro_y(msg);
- bmx160_tm->gyro_z = mavlink_msg_bmx160_tm_get_gyro_z(msg);
- bmx160_tm->mag_x = mavlink_msg_bmx160_tm_get_mag_x(msg);
- bmx160_tm->mag_y = mavlink_msg_bmx160_tm_get_mag_y(msg);
- bmx160_tm->mag_z = mavlink_msg_bmx160_tm_get_mag_z(msg);
- bmx160_tm->temp = mavlink_msg_bmx160_tm_get_temp(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_BMX160_TM_LEN? msg->len : MAVLINK_MSG_ID_BMX160_TM_LEN;
- memset(bmx160_tm, 0, MAVLINK_MSG_ID_BMX160_TM_LEN);
- memcpy(bmx160_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_dpl_tm.h b/mavlink_lib/lynx/mavlink_msg_dpl_tm.h
deleted file mode 100644
index be515350962bdf073fdd5530ed2d8d7f83991240..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_dpl_tm.h
+++ /dev/null
@@ -1,288 +0,0 @@
-#pragma once
-// MESSAGE DPL_TM PACKING
-
-#define MAVLINK_MSG_ID_DPL_TM 166
-
-MAVPACKED(
-typedef struct __mavlink_dpl_tm_t {
- uint64_t timestamp; /*< [ms] When was this logged*/
- float servo_position; /*< [deg] DPL servo position (angle)*/
- uint8_t fsm_state; /*< Current state of the dpl controller*/
- uint8_t cutters_enabled; /*< Cutters state (enabled/disabled)*/
-}) mavlink_dpl_tm_t;
-
-#define MAVLINK_MSG_ID_DPL_TM_LEN 14
-#define MAVLINK_MSG_ID_DPL_TM_MIN_LEN 14
-#define MAVLINK_MSG_ID_166_LEN 14
-#define MAVLINK_MSG_ID_166_MIN_LEN 14
-
-#define MAVLINK_MSG_ID_DPL_TM_CRC 161
-#define MAVLINK_MSG_ID_166_CRC 161
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_DPL_TM { \
- 166, \
- "DPL_TM", \
- 4, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_dpl_tm_t, timestamp) }, \
- { "fsm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_dpl_tm_t, fsm_state) }, \
- { "cutters_enabled", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_dpl_tm_t, cutters_enabled) }, \
- { "servo_position", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_dpl_tm_t, servo_position) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_DPL_TM { \
- "DPL_TM", \
- 4, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_dpl_tm_t, timestamp) }, \
- { "fsm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_dpl_tm_t, fsm_state) }, \
- { "cutters_enabled", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_dpl_tm_t, cutters_enabled) }, \
- { "servo_position", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_dpl_tm_t, servo_position) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a dpl_tm 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] When was this logged
- * @param fsm_state Current state of the dpl controller
- * @param cutters_enabled Cutters state (enabled/disabled)
- * @param servo_position [deg] DPL servo position (angle)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_dpl_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t fsm_state, uint8_t cutters_enabled, float servo_position)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_DPL_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, servo_position);
- _mav_put_uint8_t(buf, 12, fsm_state);
- _mav_put_uint8_t(buf, 13, cutters_enabled);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DPL_TM_LEN);
-#else
- mavlink_dpl_tm_t packet;
- packet.timestamp = timestamp;
- packet.servo_position = servo_position;
- packet.fsm_state = fsm_state;
- packet.cutters_enabled = cutters_enabled;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DPL_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_DPL_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DPL_TM_MIN_LEN, MAVLINK_MSG_ID_DPL_TM_LEN, MAVLINK_MSG_ID_DPL_TM_CRC);
-}
-
-/**
- * @brief Pack a dpl_tm 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] When was this logged
- * @param fsm_state Current state of the dpl controller
- * @param cutters_enabled Cutters state (enabled/disabled)
- * @param servo_position [deg] DPL servo position (angle)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_dpl_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t fsm_state,uint8_t cutters_enabled,float servo_position)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_DPL_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, servo_position);
- _mav_put_uint8_t(buf, 12, fsm_state);
- _mav_put_uint8_t(buf, 13, cutters_enabled);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DPL_TM_LEN);
-#else
- mavlink_dpl_tm_t packet;
- packet.timestamp = timestamp;
- packet.servo_position = servo_position;
- packet.fsm_state = fsm_state;
- packet.cutters_enabled = cutters_enabled;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DPL_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_DPL_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DPL_TM_MIN_LEN, MAVLINK_MSG_ID_DPL_TM_LEN, MAVLINK_MSG_ID_DPL_TM_CRC);
-}
-
-/**
- * @brief Encode a dpl_tm 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 dpl_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_dpl_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_dpl_tm_t* dpl_tm)
-{
- return mavlink_msg_dpl_tm_pack(system_id, component_id, msg, dpl_tm->timestamp, dpl_tm->fsm_state, dpl_tm->cutters_enabled, dpl_tm->servo_position);
-}
-
-/**
- * @brief Encode a dpl_tm 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 dpl_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_dpl_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_dpl_tm_t* dpl_tm)
-{
- return mavlink_msg_dpl_tm_pack_chan(system_id, component_id, chan, msg, dpl_tm->timestamp, dpl_tm->fsm_state, dpl_tm->cutters_enabled, dpl_tm->servo_position);
-}
-
-/**
- * @brief Send a dpl_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [ms] When was this logged
- * @param fsm_state Current state of the dpl controller
- * @param cutters_enabled Cutters state (enabled/disabled)
- * @param servo_position [deg] DPL servo position (angle)
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_dpl_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t fsm_state, uint8_t cutters_enabled, float servo_position)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_DPL_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, servo_position);
- _mav_put_uint8_t(buf, 12, fsm_state);
- _mav_put_uint8_t(buf, 13, cutters_enabled);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DPL_TM, buf, MAVLINK_MSG_ID_DPL_TM_MIN_LEN, MAVLINK_MSG_ID_DPL_TM_LEN, MAVLINK_MSG_ID_DPL_TM_CRC);
-#else
- mavlink_dpl_tm_t packet;
- packet.timestamp = timestamp;
- packet.servo_position = servo_position;
- packet.fsm_state = fsm_state;
- packet.cutters_enabled = cutters_enabled;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DPL_TM, (const char *)&packet, MAVLINK_MSG_ID_DPL_TM_MIN_LEN, MAVLINK_MSG_ID_DPL_TM_LEN, MAVLINK_MSG_ID_DPL_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a dpl_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_dpl_tm_send_struct(mavlink_channel_t chan, const mavlink_dpl_tm_t* dpl_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_dpl_tm_send(chan, dpl_tm->timestamp, dpl_tm->fsm_state, dpl_tm->cutters_enabled, dpl_tm->servo_position);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DPL_TM, (const char *)dpl_tm, MAVLINK_MSG_ID_DPL_TM_MIN_LEN, MAVLINK_MSG_ID_DPL_TM_LEN, MAVLINK_MSG_ID_DPL_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_DPL_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_dpl_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t fsm_state, uint8_t cutters_enabled, float servo_position)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, servo_position);
- _mav_put_uint8_t(buf, 12, fsm_state);
- _mav_put_uint8_t(buf, 13, cutters_enabled);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DPL_TM, buf, MAVLINK_MSG_ID_DPL_TM_MIN_LEN, MAVLINK_MSG_ID_DPL_TM_LEN, MAVLINK_MSG_ID_DPL_TM_CRC);
-#else
- mavlink_dpl_tm_t *packet = (mavlink_dpl_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->servo_position = servo_position;
- packet->fsm_state = fsm_state;
- packet->cutters_enabled = cutters_enabled;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DPL_TM, (const char *)packet, MAVLINK_MSG_ID_DPL_TM_MIN_LEN, MAVLINK_MSG_ID_DPL_TM_LEN, MAVLINK_MSG_ID_DPL_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE DPL_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from dpl_tm message
- *
- * @return [ms] When was this logged
- */
-static inline uint64_t mavlink_msg_dpl_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field fsm_state from dpl_tm message
- *
- * @return Current state of the dpl controller
- */
-static inline uint8_t mavlink_msg_dpl_tm_get_fsm_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 12);
-}
-
-/**
- * @brief Get field cutters_enabled from dpl_tm message
- *
- * @return Cutters state (enabled/disabled)
- */
-static inline uint8_t mavlink_msg_dpl_tm_get_cutters_enabled(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 13);
-}
-
-/**
- * @brief Get field servo_position from dpl_tm message
- *
- * @return [deg] DPL servo position (angle)
- */
-static inline float mavlink_msg_dpl_tm_get_servo_position(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Decode a dpl_tm message into a struct
- *
- * @param msg The message to decode
- * @param dpl_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_dpl_tm_decode(const mavlink_message_t* msg, mavlink_dpl_tm_t* dpl_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- dpl_tm->timestamp = mavlink_msg_dpl_tm_get_timestamp(msg);
- dpl_tm->servo_position = mavlink_msg_dpl_tm_get_servo_position(msg);
- dpl_tm->fsm_state = mavlink_msg_dpl_tm_get_fsm_state(msg);
- dpl_tm->cutters_enabled = mavlink_msg_dpl_tm_get_cutters_enabled(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_DPL_TM_LEN? msg->len : MAVLINK_MSG_ID_DPL_TM_LEN;
- memset(dpl_tm, 0, MAVLINK_MSG_ID_DPL_TM_LEN);
- memcpy(dpl_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_fmm_tm.h b/mavlink_lib/lynx/mavlink_msg_fmm_tm.h
deleted file mode 100644
index 5d10be1c135cfbbbee86b445f43c92e2f179e578..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_fmm_tm.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE FMM_TM PACKING
-
-#define MAVLINK_MSG_ID_FMM_TM 161
-
-MAVPACKED(
-typedef struct __mavlink_fmm_tm_t {
- uint64_t timestamp; /*< [ms] Timestamp*/
- uint8_t state; /*< FMM State*/
-}) mavlink_fmm_tm_t;
-
-#define MAVLINK_MSG_ID_FMM_TM_LEN 9
-#define MAVLINK_MSG_ID_FMM_TM_MIN_LEN 9
-#define MAVLINK_MSG_ID_161_LEN 9
-#define MAVLINK_MSG_ID_161_MIN_LEN 9
-
-#define MAVLINK_MSG_ID_FMM_TM_CRC 237
-#define MAVLINK_MSG_ID_161_CRC 237
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_FMM_TM { \
- 161, \
- "FMM_TM", \
- 2, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_fmm_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fmm_tm_t, state) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_FMM_TM { \
- "FMM_TM", \
- 2, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_fmm_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fmm_tm_t, state) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a fmm_tm 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
- * @param state FMM State
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_fmm_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_FMM_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FMM_TM_LEN);
-#else
- mavlink_fmm_tm_t packet;
- packet.timestamp = timestamp;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FMM_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_FMM_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FMM_TM_MIN_LEN, MAVLINK_MSG_ID_FMM_TM_LEN, MAVLINK_MSG_ID_FMM_TM_CRC);
-}
-
-/**
- * @brief Pack a fmm_tm 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
- * @param state FMM State
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_fmm_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_FMM_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FMM_TM_LEN);
-#else
- mavlink_fmm_tm_t packet;
- packet.timestamp = timestamp;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FMM_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_FMM_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FMM_TM_MIN_LEN, MAVLINK_MSG_ID_FMM_TM_LEN, MAVLINK_MSG_ID_FMM_TM_CRC);
-}
-
-/**
- * @brief Encode a fmm_tm 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 fmm_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_fmm_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fmm_tm_t* fmm_tm)
-{
- return mavlink_msg_fmm_tm_pack(system_id, component_id, msg, fmm_tm->timestamp, fmm_tm->state);
-}
-
-/**
- * @brief Encode a fmm_tm 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 fmm_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_fmm_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fmm_tm_t* fmm_tm)
-{
- return mavlink_msg_fmm_tm_pack_chan(system_id, component_id, chan, msg, fmm_tm->timestamp, fmm_tm->state);
-}
-
-/**
- * @brief Send a fmm_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [ms] Timestamp
- * @param state FMM State
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_fmm_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_FMM_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FMM_TM, buf, MAVLINK_MSG_ID_FMM_TM_MIN_LEN, MAVLINK_MSG_ID_FMM_TM_LEN, MAVLINK_MSG_ID_FMM_TM_CRC);
-#else
- mavlink_fmm_tm_t packet;
- packet.timestamp = timestamp;
- packet.state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FMM_TM, (const char *)&packet, MAVLINK_MSG_ID_FMM_TM_MIN_LEN, MAVLINK_MSG_ID_FMM_TM_LEN, MAVLINK_MSG_ID_FMM_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a fmm_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_fmm_tm_send_struct(mavlink_channel_t chan, const mavlink_fmm_tm_t* fmm_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_fmm_tm_send(chan, fmm_tm->timestamp, fmm_tm->state);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FMM_TM, (const char *)fmm_tm, MAVLINK_MSG_ID_FMM_TM_MIN_LEN, MAVLINK_MSG_ID_FMM_TM_LEN, MAVLINK_MSG_ID_FMM_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_FMM_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_fmm_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FMM_TM, buf, MAVLINK_MSG_ID_FMM_TM_MIN_LEN, MAVLINK_MSG_ID_FMM_TM_LEN, MAVLINK_MSG_ID_FMM_TM_CRC);
-#else
- mavlink_fmm_tm_t *packet = (mavlink_fmm_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FMM_TM, (const char *)packet, MAVLINK_MSG_ID_FMM_TM_MIN_LEN, MAVLINK_MSG_ID_FMM_TM_LEN, MAVLINK_MSG_ID_FMM_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE FMM_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from fmm_tm message
- *
- * @return [ms] Timestamp
- */
-static inline uint64_t mavlink_msg_fmm_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field state from fmm_tm message
- *
- * @return FMM State
- */
-static inline uint8_t mavlink_msg_fmm_tm_get_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 8);
-}
-
-/**
- * @brief Decode a fmm_tm message into a struct
- *
- * @param msg The message to decode
- * @param fmm_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_fmm_tm_decode(const mavlink_message_t* msg, mavlink_fmm_tm_t* fmm_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- fmm_tm->timestamp = mavlink_msg_fmm_tm_get_timestamp(msg);
- fmm_tm->state = mavlink_msg_fmm_tm_get_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_FMM_TM_LEN? msg->len : MAVLINK_MSG_ID_FMM_TM_LEN;
- memset(fmm_tm, 0, MAVLINK_MSG_ID_FMM_TM_LEN);
- memcpy(fmm_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_gps_tm.h b/mavlink_lib/lynx/mavlink_msg_gps_tm.h
deleted file mode 100644
index 27fa1ce6bed54a7044d7126f26173dd22e0db995..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_gps_tm.h
+++ /dev/null
@@ -1,463 +0,0 @@
-#pragma once
-// MESSAGE GPS_TM PACKING
-
-#define MAVLINK_MSG_ID_GPS_TM 175
-
-MAVPACKED(
-typedef struct __mavlink_gps_tm_t {
- uint64_t timestamp; /*< [ms] When was this logged*/
- double latitude; /*< [deg] Latitude*/
- double longitude; /*< [deg] Longitude*/
- double height; /*< [m] Altitude*/
- float vel_north; /*< [m/s] Velocity in NED frame (north)*/
- float vel_east; /*< [m/s] Velocity in NED frame (east)*/
- float vel_down; /*< [m/s] Velocity in NED frame (down)*/
- float speed; /*< [m/s] Speed*/
- float track; /*< [deg] Track*/
- uint8_t fix; /*< Wether the GPS has a FIX*/
- uint8_t n_satellites; /*< Number of connected satellites*/
-}) mavlink_gps_tm_t;
-
-#define MAVLINK_MSG_ID_GPS_TM_LEN 54
-#define MAVLINK_MSG_ID_GPS_TM_MIN_LEN 54
-#define MAVLINK_MSG_ID_175_LEN 54
-#define MAVLINK_MSG_ID_175_MIN_LEN 54
-
-#define MAVLINK_MSG_ID_GPS_TM_CRC 156
-#define MAVLINK_MSG_ID_175_CRC 156
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_GPS_TM { \
- 175, \
- "GPS_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_tm_t, timestamp) }, \
- { "fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_gps_tm_t, fix) }, \
- { "latitude", NULL, MAVLINK_TYPE_DOUBLE, 0, 8, offsetof(mavlink_gps_tm_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_DOUBLE, 0, 16, offsetof(mavlink_gps_tm_t, longitude) }, \
- { "height", NULL, MAVLINK_TYPE_DOUBLE, 0, 24, offsetof(mavlink_gps_tm_t, height) }, \
- { "vel_north", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_tm_t, vel_north) }, \
- { "vel_east", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gps_tm_t, vel_east) }, \
- { "vel_down", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gps_tm_t, vel_down) }, \
- { "speed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_tm_t, speed) }, \
- { "track", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_tm_t, track) }, \
- { "n_satellites", NULL, MAVLINK_TYPE_UINT8_T, 0, 53, offsetof(mavlink_gps_tm_t, n_satellites) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_GPS_TM { \
- "GPS_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_tm_t, timestamp) }, \
- { "fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_gps_tm_t, fix) }, \
- { "latitude", NULL, MAVLINK_TYPE_DOUBLE, 0, 8, offsetof(mavlink_gps_tm_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_DOUBLE, 0, 16, offsetof(mavlink_gps_tm_t, longitude) }, \
- { "height", NULL, MAVLINK_TYPE_DOUBLE, 0, 24, offsetof(mavlink_gps_tm_t, height) }, \
- { "vel_north", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_tm_t, vel_north) }, \
- { "vel_east", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gps_tm_t, vel_east) }, \
- { "vel_down", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gps_tm_t, vel_down) }, \
- { "speed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_tm_t, speed) }, \
- { "track", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_tm_t, track) }, \
- { "n_satellites", NULL, MAVLINK_TYPE_UINT8_T, 0, 53, offsetof(mavlink_gps_tm_t, n_satellites) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a gps_tm 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] When was this logged
- * @param fix Wether the GPS has a FIX
- * @param latitude [deg] Latitude
- * @param longitude [deg] Longitude
- * @param height [m] Altitude
- * @param vel_north [m/s] Velocity in NED frame (north)
- * @param vel_east [m/s] Velocity in NED frame (east)
- * @param vel_down [m/s] Velocity in NED frame (down)
- * @param speed [m/s] Speed
- * @param track [deg] Track
- * @param n_satellites Number of connected satellites
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_gps_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t fix, double latitude, double longitude, double height, float vel_north, float vel_east, float vel_down, float speed, float track, uint8_t n_satellites)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GPS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, latitude);
- _mav_put_double(buf, 16, longitude);
- _mav_put_double(buf, 24, height);
- _mav_put_float(buf, 32, vel_north);
- _mav_put_float(buf, 36, vel_east);
- _mav_put_float(buf, 40, vel_down);
- _mav_put_float(buf, 44, speed);
- _mav_put_float(buf, 48, track);
- _mav_put_uint8_t(buf, 52, fix);
- _mav_put_uint8_t(buf, 53, n_satellites);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_TM_LEN);
-#else
- mavlink_gps_tm_t packet;
- packet.timestamp = timestamp;
- packet.latitude = latitude;
- packet.longitude = longitude;
- packet.height = height;
- packet.vel_north = vel_north;
- packet.vel_east = vel_east;
- packet.vel_down = vel_down;
- packet.speed = speed;
- packet.track = track;
- packet.fix = fix;
- packet.n_satellites = n_satellites;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_GPS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-}
-
-/**
- * @brief Pack a gps_tm 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] When was this logged
- * @param fix Wether the GPS has a FIX
- * @param latitude [deg] Latitude
- * @param longitude [deg] Longitude
- * @param height [m] Altitude
- * @param vel_north [m/s] Velocity in NED frame (north)
- * @param vel_east [m/s] Velocity in NED frame (east)
- * @param vel_down [m/s] Velocity in NED frame (down)
- * @param speed [m/s] Speed
- * @param track [deg] Track
- * @param n_satellites Number of connected satellites
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_gps_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t fix,double latitude,double longitude,double height,float vel_north,float vel_east,float vel_down,float speed,float track,uint8_t n_satellites)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GPS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, latitude);
- _mav_put_double(buf, 16, longitude);
- _mav_put_double(buf, 24, height);
- _mav_put_float(buf, 32, vel_north);
- _mav_put_float(buf, 36, vel_east);
- _mav_put_float(buf, 40, vel_down);
- _mav_put_float(buf, 44, speed);
- _mav_put_float(buf, 48, track);
- _mav_put_uint8_t(buf, 52, fix);
- _mav_put_uint8_t(buf, 53, n_satellites);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_TM_LEN);
-#else
- mavlink_gps_tm_t packet;
- packet.timestamp = timestamp;
- packet.latitude = latitude;
- packet.longitude = longitude;
- packet.height = height;
- packet.vel_north = vel_north;
- packet.vel_east = vel_east;
- packet.vel_down = vel_down;
- packet.speed = speed;
- packet.track = track;
- packet.fix = fix;
- packet.n_satellites = n_satellites;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_GPS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-}
-
-/**
- * @brief Encode a gps_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_gps_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_tm_t* gps_tm)
-{
- return mavlink_msg_gps_tm_pack(system_id, component_id, msg, gps_tm->timestamp, gps_tm->fix, gps_tm->latitude, gps_tm->longitude, gps_tm->height, gps_tm->vel_north, gps_tm->vel_east, gps_tm->vel_down, gps_tm->speed, gps_tm->track, gps_tm->n_satellites);
-}
-
-/**
- * @brief Encode a gps_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_gps_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_tm_t* gps_tm)
-{
- return mavlink_msg_gps_tm_pack_chan(system_id, component_id, chan, msg, gps_tm->timestamp, gps_tm->fix, gps_tm->latitude, gps_tm->longitude, gps_tm->height, gps_tm->vel_north, gps_tm->vel_east, gps_tm->vel_down, gps_tm->speed, gps_tm->track, gps_tm->n_satellites);
-}
-
-/**
- * @brief Send a gps_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [ms] When was this logged
- * @param fix Wether the GPS has a FIX
- * @param latitude [deg] Latitude
- * @param longitude [deg] Longitude
- * @param height [m] Altitude
- * @param vel_north [m/s] Velocity in NED frame (north)
- * @param vel_east [m/s] Velocity in NED frame (east)
- * @param vel_down [m/s] Velocity in NED frame (down)
- * @param speed [m/s] Speed
- * @param track [deg] Track
- * @param n_satellites Number of connected satellites
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_gps_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t fix, double latitude, double longitude, double height, float vel_north, float vel_east, float vel_down, float speed, float track, uint8_t n_satellites)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GPS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, latitude);
- _mav_put_double(buf, 16, longitude);
- _mav_put_double(buf, 24, height);
- _mav_put_float(buf, 32, vel_north);
- _mav_put_float(buf, 36, vel_east);
- _mav_put_float(buf, 40, vel_down);
- _mav_put_float(buf, 44, speed);
- _mav_put_float(buf, 48, track);
- _mav_put_uint8_t(buf, 52, fix);
- _mav_put_uint8_t(buf, 53, n_satellites);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, buf, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#else
- mavlink_gps_tm_t packet;
- packet.timestamp = timestamp;
- packet.latitude = latitude;
- packet.longitude = longitude;
- packet.height = height;
- packet.vel_north = vel_north;
- packet.vel_east = vel_east;
- packet.vel_down = vel_down;
- packet.speed = speed;
- packet.track = track;
- packet.fix = fix;
- packet.n_satellites = n_satellites;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, (const char *)&packet, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a gps_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_gps_tm_send_struct(mavlink_channel_t chan, const mavlink_gps_tm_t* gps_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_gps_tm_send(chan, gps_tm->timestamp, gps_tm->fix, gps_tm->latitude, gps_tm->longitude, gps_tm->height, gps_tm->vel_north, gps_tm->vel_east, gps_tm->vel_down, gps_tm->speed, gps_tm->track, gps_tm->n_satellites);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, (const char *)gps_tm, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_GPS_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t fix, double latitude, double longitude, double height, float vel_north, float vel_east, float vel_down, float speed, float track, uint8_t n_satellites)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, latitude);
- _mav_put_double(buf, 16, longitude);
- _mav_put_double(buf, 24, height);
- _mav_put_float(buf, 32, vel_north);
- _mav_put_float(buf, 36, vel_east);
- _mav_put_float(buf, 40, vel_down);
- _mav_put_float(buf, 44, speed);
- _mav_put_float(buf, 48, track);
- _mav_put_uint8_t(buf, 52, fix);
- _mav_put_uint8_t(buf, 53, n_satellites);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, buf, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#else
- mavlink_gps_tm_t *packet = (mavlink_gps_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->latitude = latitude;
- packet->longitude = longitude;
- packet->height = height;
- packet->vel_north = vel_north;
- packet->vel_east = vel_east;
- packet->vel_down = vel_down;
- packet->speed = speed;
- packet->track = track;
- packet->fix = fix;
- packet->n_satellites = n_satellites;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, (const char *)packet, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE GPS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from gps_tm message
- *
- * @return [ms] When was this logged
- */
-static inline uint64_t mavlink_msg_gps_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field fix from gps_tm message
- *
- * @return Wether the GPS has a FIX
- */
-static inline uint8_t mavlink_msg_gps_tm_get_fix(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 52);
-}
-
-/**
- * @brief Get field latitude from gps_tm message
- *
- * @return [deg] Latitude
- */
-static inline double mavlink_msg_gps_tm_get_latitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_double(msg, 8);
-}
-
-/**
- * @brief Get field longitude from gps_tm message
- *
- * @return [deg] Longitude
- */
-static inline double mavlink_msg_gps_tm_get_longitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_double(msg, 16);
-}
-
-/**
- * @brief Get field height from gps_tm message
- *
- * @return [m] Altitude
- */
-static inline double mavlink_msg_gps_tm_get_height(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_double(msg, 24);
-}
-
-/**
- * @brief Get field vel_north from gps_tm message
- *
- * @return [m/s] Velocity in NED frame (north)
- */
-static inline float mavlink_msg_gps_tm_get_vel_north(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field vel_east from gps_tm message
- *
- * @return [m/s] Velocity in NED frame (east)
- */
-static inline float mavlink_msg_gps_tm_get_vel_east(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field vel_down from gps_tm message
- *
- * @return [m/s] Velocity in NED frame (down)
- */
-static inline float mavlink_msg_gps_tm_get_vel_down(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field speed from gps_tm message
- *
- * @return [m/s] Speed
- */
-static inline float mavlink_msg_gps_tm_get_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field track from gps_tm message
- *
- * @return [deg] Track
- */
-static inline float mavlink_msg_gps_tm_get_track(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field n_satellites from gps_tm message
- *
- * @return Number of connected satellites
- */
-static inline uint8_t mavlink_msg_gps_tm_get_n_satellites(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 53);
-}
-
-/**
- * @brief Decode a gps_tm message into a struct
- *
- * @param msg The message to decode
- * @param gps_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_gps_tm_decode(const mavlink_message_t* msg, mavlink_gps_tm_t* gps_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- gps_tm->timestamp = mavlink_msg_gps_tm_get_timestamp(msg);
- gps_tm->latitude = mavlink_msg_gps_tm_get_latitude(msg);
- gps_tm->longitude = mavlink_msg_gps_tm_get_longitude(msg);
- gps_tm->height = mavlink_msg_gps_tm_get_height(msg);
- gps_tm->vel_north = mavlink_msg_gps_tm_get_vel_north(msg);
- gps_tm->vel_east = mavlink_msg_gps_tm_get_vel_east(msg);
- gps_tm->vel_down = mavlink_msg_gps_tm_get_vel_down(msg);
- gps_tm->speed = mavlink_msg_gps_tm_get_speed(msg);
- gps_tm->track = mavlink_msg_gps_tm_get_track(msg);
- gps_tm->fix = mavlink_msg_gps_tm_get_fix(msg);
- gps_tm->n_satellites = mavlink_msg_gps_tm_get_n_satellites(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_TM_LEN? msg->len : MAVLINK_MSG_ID_GPS_TM_LEN;
- memset(gps_tm, 0, MAVLINK_MSG_ID_GPS_TM_LEN);
- memcpy(gps_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_hr_tm.h b/mavlink_lib/lynx/mavlink_msg_hr_tm.h
deleted file mode 100644
index aaca4ce6d3df403e2b51d2ef2eb7418d854e785f..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_hr_tm.h
+++ /dev/null
@@ -1,1388 +0,0 @@
-#pragma once
-// MESSAGE HR_TM PACKING
-
-#define MAVLINK_MSG_ID_HR_TM 180
-
-MAVPACKED(
-typedef struct __mavlink_hr_tm_t {
- uint64_t timestamp; /*< [ms] Timestamp in milliseconds*/
- float pressure_ada; /*< [Pa] Atmospheric pressure estimated by ADA*/
- float pressure_digi; /*< [Pa] Pressure from digital sensor*/
- float pressure_static; /*< [Pa] Pressure from static port*/
- float pressure_dpl; /*< [Pa] Pressure from deployment vane sensor*/
- float airspeed_pitot; /*< [m/s] Pitot airspeed*/
- float msl_altitude; /*< [m] Altitude above mean sea level*/
- float ada_vert_speed; /*< [m/s] Vertical speed estimated by ADA*/
- float ada_vert_accel; /*< [m/s^2] Vertical acceleration estimated by ADA*/
- float acc_x; /*< [m/s^2] Acceleration on X axis (body)*/
- float acc_y; /*< [m/s^2] Acceleration on Y axis (body)*/
- float acc_z; /*< [m/s^2] Acceleration on Z axis (body)*/
- float gyro_x; /*< [rad/s] Angular speed on X axis (body)*/
- float gyro_y; /*< [rad/s] Angular speed on Y axis (body)*/
- float gyro_z; /*< [rad/s] Angular speed on Z axis (body)*/
- float mag_x; /*< [uT] Magnetic field on X axis (body)*/
- float mag_y; /*< [uT] Magnetic field on Y axis (body)*/
- float mag_z; /*< [uT] Magnetic field on Z axis (body)*/
- float gps_lat; /*< [deg] Latitude*/
- float gps_lon; /*< [deg] Longitude*/
- float gps_alt; /*< [m] GPS Altitude*/
- float vbat; /*< [V] Battery voltage*/
- float vsupply_5v; /*< [V] Power supply 5V*/
- float temperature; /*< [degC] Temperature*/
- float ab_angle; /*< [deg] Aerobrakes angle*/
- float ab_estimated_cd; /*< Estimated drag coefficient*/
- float nas_x; /*< [deg] Navigation system estimated X position (longitude)*/
- float nas_y; /*< [deg] Navigation system estimated Y position (latitude)*/
- float nas_z; /*< [m] Navigation system estimated Z position*/
- float nas_vx; /*< [m/s] Navigation system estimated north velocity*/
- float nas_vy; /*< [m/s] Navigation system estimated east velocity*/
- float nas_vz; /*< [m/s] Navigation system estimated down velocity*/
- float nas_roll; /*< [deg] Navigation system estimated attitude (roll)*/
- float nas_pitch; /*< [deg] Navigation system estimated attitude (pitch)*/
- float nas_yaw; /*< [deg] Navigation system estimated attitude (yaw)*/
- float nas_bias0; /*< Navigation system bias*/
- float nas_bias1; /*< Navigation system bias*/
- float nas_bias2; /*< Navigation system bias*/
- uint8_t ada_state; /*< ADA Controller State*/
- uint8_t fmm_state; /*< Flight Mode Manager State*/
- uint8_t dpl_state; /*< Deployment Controller State*/
- uint8_t ab_state; /*< Aerobrake FSM state*/
- uint8_t nas_state; /*< Navigation System FSM State*/
- uint8_t gps_fix; /*< GPS fix (1 = fix, 0 = no fix)*/
- uint8_t pin_launch; /*< Launch pin status (1 = connected, 0 = disconnected)*/
- uint8_t pin_nosecone; /*< Nosecone pin status (1 = connected, 0 = disconnected)*/
- uint8_t servo_sensor; /*< Servo sensor status (1 = actuated, 0 = idle)*/
- int8_t logger_error; /*< Logger error (0 = no error, -1 otherwise)*/
-}) mavlink_hr_tm_t;
-
-#define MAVLINK_MSG_ID_HR_TM_LEN 166
-#define MAVLINK_MSG_ID_HR_TM_MIN_LEN 166
-#define MAVLINK_MSG_ID_180_LEN 166
-#define MAVLINK_MSG_ID_180_MIN_LEN 166
-
-#define MAVLINK_MSG_ID_HR_TM_CRC 67
-#define MAVLINK_MSG_ID_180_CRC 67
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_HR_TM { \
- 180, \
- "HR_TM", \
- 48, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hr_tm_t, timestamp) }, \
- { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_hr_tm_t, ada_state) }, \
- { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_hr_tm_t, fmm_state) }, \
- { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_hr_tm_t, dpl_state) }, \
- { "ab_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_hr_tm_t, ab_state) }, \
- { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_hr_tm_t, nas_state) }, \
- { "pressure_ada", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hr_tm_t, pressure_ada) }, \
- { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hr_tm_t, pressure_digi) }, \
- { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hr_tm_t, pressure_static) }, \
- { "pressure_dpl", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hr_tm_t, pressure_dpl) }, \
- { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hr_tm_t, airspeed_pitot) }, \
- { "msl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hr_tm_t, msl_altitude) }, \
- { "ada_vert_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hr_tm_t, ada_vert_speed) }, \
- { "ada_vert_accel", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hr_tm_t, ada_vert_accel) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_hr_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_hr_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_hr_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_hr_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_hr_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_hr_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_hr_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_hr_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_hr_tm_t, mag_z) }, \
- { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_hr_tm_t, gps_fix) }, \
- { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_hr_tm_t, gps_lat) }, \
- { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_hr_tm_t, gps_lon) }, \
- { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_hr_tm_t, gps_alt) }, \
- { "vbat", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_hr_tm_t, vbat) }, \
- { "vsupply_5v", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_hr_tm_t, vsupply_5v) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_hr_tm_t, temperature) }, \
- { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 162, offsetof(mavlink_hr_tm_t, pin_launch) }, \
- { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 163, offsetof(mavlink_hr_tm_t, pin_nosecone) }, \
- { "servo_sensor", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_hr_tm_t, servo_sensor) }, \
- { "ab_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_hr_tm_t, ab_angle) }, \
- { "ab_estimated_cd", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_hr_tm_t, ab_estimated_cd) }, \
- { "nas_x", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_hr_tm_t, nas_x) }, \
- { "nas_y", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_hr_tm_t, nas_y) }, \
- { "nas_z", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_hr_tm_t, nas_z) }, \
- { "nas_vx", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_hr_tm_t, nas_vx) }, \
- { "nas_vy", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_hr_tm_t, nas_vy) }, \
- { "nas_vz", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_hr_tm_t, nas_vz) }, \
- { "nas_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_hr_tm_t, nas_roll) }, \
- { "nas_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_hr_tm_t, nas_pitch) }, \
- { "nas_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_hr_tm_t, nas_yaw) }, \
- { "nas_bias0", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_hr_tm_t, nas_bias0) }, \
- { "nas_bias1", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_hr_tm_t, nas_bias1) }, \
- { "nas_bias2", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_hr_tm_t, nas_bias2) }, \
- { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 165, offsetof(mavlink_hr_tm_t, logger_error) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_HR_TM { \
- "HR_TM", \
- 48, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hr_tm_t, timestamp) }, \
- { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_hr_tm_t, ada_state) }, \
- { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_hr_tm_t, fmm_state) }, \
- { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_hr_tm_t, dpl_state) }, \
- { "ab_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_hr_tm_t, ab_state) }, \
- { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_hr_tm_t, nas_state) }, \
- { "pressure_ada", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hr_tm_t, pressure_ada) }, \
- { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hr_tm_t, pressure_digi) }, \
- { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hr_tm_t, pressure_static) }, \
- { "pressure_dpl", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hr_tm_t, pressure_dpl) }, \
- { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hr_tm_t, airspeed_pitot) }, \
- { "msl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hr_tm_t, msl_altitude) }, \
- { "ada_vert_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hr_tm_t, ada_vert_speed) }, \
- { "ada_vert_accel", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hr_tm_t, ada_vert_accel) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_hr_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_hr_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_hr_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_hr_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_hr_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_hr_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_hr_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_hr_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_hr_tm_t, mag_z) }, \
- { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_hr_tm_t, gps_fix) }, \
- { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_hr_tm_t, gps_lat) }, \
- { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_hr_tm_t, gps_lon) }, \
- { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_hr_tm_t, gps_alt) }, \
- { "vbat", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_hr_tm_t, vbat) }, \
- { "vsupply_5v", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_hr_tm_t, vsupply_5v) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_hr_tm_t, temperature) }, \
- { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 162, offsetof(mavlink_hr_tm_t, pin_launch) }, \
- { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 163, offsetof(mavlink_hr_tm_t, pin_nosecone) }, \
- { "servo_sensor", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_hr_tm_t, servo_sensor) }, \
- { "ab_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_hr_tm_t, ab_angle) }, \
- { "ab_estimated_cd", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_hr_tm_t, ab_estimated_cd) }, \
- { "nas_x", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_hr_tm_t, nas_x) }, \
- { "nas_y", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_hr_tm_t, nas_y) }, \
- { "nas_z", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_hr_tm_t, nas_z) }, \
- { "nas_vx", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_hr_tm_t, nas_vx) }, \
- { "nas_vy", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_hr_tm_t, nas_vy) }, \
- { "nas_vz", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_hr_tm_t, nas_vz) }, \
- { "nas_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_hr_tm_t, nas_roll) }, \
- { "nas_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_hr_tm_t, nas_pitch) }, \
- { "nas_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_hr_tm_t, nas_yaw) }, \
- { "nas_bias0", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_hr_tm_t, nas_bias0) }, \
- { "nas_bias1", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_hr_tm_t, nas_bias1) }, \
- { "nas_bias2", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_hr_tm_t, nas_bias2) }, \
- { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 165, offsetof(mavlink_hr_tm_t, logger_error) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a hr_tm 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 in milliseconds
- * @param ada_state ADA Controller State
- * @param fmm_state Flight Mode Manager State
- * @param dpl_state Deployment Controller State
- * @param ab_state Aerobrake FSM state
- * @param nas_state Navigation System FSM State
- * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane sensor
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param msl_altitude [m] Altitude above mean sea level
- * @param ada_vert_speed [m/s] Vertical speed estimated by ADA
- * @param ada_vert_accel [m/s^2] Vertical acceleration estimated by ADA
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param vbat [V] Battery voltage
- * @param vsupply_5v [V] Power supply 5V
- * @param temperature [degC] Temperature
- * @param pin_launch Launch pin status (1 = connected, 0 = disconnected)
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param servo_sensor Servo sensor status (1 = actuated, 0 = idle)
- * @param ab_angle [deg] Aerobrakes angle
- * @param ab_estimated_cd Estimated drag coefficient
- * @param nas_x [deg] Navigation system estimated X position (longitude)
- * @param nas_y [deg] Navigation system estimated Y position (latitude)
- * @param nas_z [m] Navigation system estimated Z position
- * @param nas_vx [m/s] Navigation system estimated north velocity
- * @param nas_vy [m/s] Navigation system estimated east velocity
- * @param nas_vz [m/s] Navigation system estimated down velocity
- * @param nas_roll [deg] Navigation system estimated attitude (roll)
- * @param nas_pitch [deg] Navigation system estimated attitude (pitch)
- * @param nas_yaw [deg] Navigation system estimated attitude (yaw)
- * @param nas_bias0 Navigation system bias
- * @param nas_bias1 Navigation system bias
- * @param nas_bias2 Navigation system bias
- * @param logger_error Logger error (0 = no error, -1 otherwise)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_hr_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t ab_state, uint8_t nas_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float msl_altitude, float ada_vert_speed, float ada_vert_accel, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float vbat, float vsupply_5v, float temperature, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t servo_sensor, float ab_angle, float ab_estimated_cd, float nas_x, float nas_y, float nas_z, float nas_vx, float nas_vy, float nas_vz, float nas_roll, float nas_pitch, float nas_yaw, float nas_bias0, float nas_bias1, float nas_bias2, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_HR_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_ada);
- _mav_put_float(buf, 12, pressure_digi);
- _mav_put_float(buf, 16, pressure_static);
- _mav_put_float(buf, 20, pressure_dpl);
- _mav_put_float(buf, 24, airspeed_pitot);
- _mav_put_float(buf, 28, msl_altitude);
- _mav_put_float(buf, 32, ada_vert_speed);
- _mav_put_float(buf, 36, ada_vert_accel);
- _mav_put_float(buf, 40, acc_x);
- _mav_put_float(buf, 44, acc_y);
- _mav_put_float(buf, 48, acc_z);
- _mav_put_float(buf, 52, gyro_x);
- _mav_put_float(buf, 56, gyro_y);
- _mav_put_float(buf, 60, gyro_z);
- _mav_put_float(buf, 64, mag_x);
- _mav_put_float(buf, 68, mag_y);
- _mav_put_float(buf, 72, mag_z);
- _mav_put_float(buf, 76, gps_lat);
- _mav_put_float(buf, 80, gps_lon);
- _mav_put_float(buf, 84, gps_alt);
- _mav_put_float(buf, 88, vbat);
- _mav_put_float(buf, 92, vsupply_5v);
- _mav_put_float(buf, 96, temperature);
- _mav_put_float(buf, 100, ab_angle);
- _mav_put_float(buf, 104, ab_estimated_cd);
- _mav_put_float(buf, 108, nas_x);
- _mav_put_float(buf, 112, nas_y);
- _mav_put_float(buf, 116, nas_z);
- _mav_put_float(buf, 120, nas_vx);
- _mav_put_float(buf, 124, nas_vy);
- _mav_put_float(buf, 128, nas_vz);
- _mav_put_float(buf, 132, nas_roll);
- _mav_put_float(buf, 136, nas_pitch);
- _mav_put_float(buf, 140, nas_yaw);
- _mav_put_float(buf, 144, nas_bias0);
- _mav_put_float(buf, 148, nas_bias1);
- _mav_put_float(buf, 152, nas_bias2);
- _mav_put_uint8_t(buf, 156, ada_state);
- _mav_put_uint8_t(buf, 157, fmm_state);
- _mav_put_uint8_t(buf, 158, dpl_state);
- _mav_put_uint8_t(buf, 159, ab_state);
- _mav_put_uint8_t(buf, 160, nas_state);
- _mav_put_uint8_t(buf, 161, gps_fix);
- _mav_put_uint8_t(buf, 162, pin_launch);
- _mav_put_uint8_t(buf, 163, pin_nosecone);
- _mav_put_uint8_t(buf, 164, servo_sensor);
- _mav_put_int8_t(buf, 165, logger_error);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HR_TM_LEN);
-#else
- mavlink_hr_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_ada = pressure_ada;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.pressure_dpl = pressure_dpl;
- packet.airspeed_pitot = airspeed_pitot;
- packet.msl_altitude = msl_altitude;
- packet.ada_vert_speed = ada_vert_speed;
- packet.ada_vert_accel = ada_vert_accel;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.vbat = vbat;
- packet.vsupply_5v = vsupply_5v;
- packet.temperature = temperature;
- packet.ab_angle = ab_angle;
- packet.ab_estimated_cd = ab_estimated_cd;
- packet.nas_x = nas_x;
- packet.nas_y = nas_y;
- packet.nas_z = nas_z;
- packet.nas_vx = nas_vx;
- packet.nas_vy = nas_vy;
- packet.nas_vz = nas_vz;
- packet.nas_roll = nas_roll;
- packet.nas_pitch = nas_pitch;
- packet.nas_yaw = nas_yaw;
- packet.nas_bias0 = nas_bias0;
- packet.nas_bias1 = nas_bias1;
- packet.nas_bias2 = nas_bias2;
- packet.ada_state = ada_state;
- packet.fmm_state = fmm_state;
- packet.dpl_state = dpl_state;
- packet.ab_state = ab_state;
- packet.nas_state = nas_state;
- packet.gps_fix = gps_fix;
- packet.pin_launch = pin_launch;
- packet.pin_nosecone = pin_nosecone;
- packet.servo_sensor = servo_sensor;
- packet.logger_error = logger_error;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HR_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_HR_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HR_TM_MIN_LEN, MAVLINK_MSG_ID_HR_TM_LEN, MAVLINK_MSG_ID_HR_TM_CRC);
-}
-
-/**
- * @brief Pack a hr_tm 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 in milliseconds
- * @param ada_state ADA Controller State
- * @param fmm_state Flight Mode Manager State
- * @param dpl_state Deployment Controller State
- * @param ab_state Aerobrake FSM state
- * @param nas_state Navigation System FSM State
- * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane sensor
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param msl_altitude [m] Altitude above mean sea level
- * @param ada_vert_speed [m/s] Vertical speed estimated by ADA
- * @param ada_vert_accel [m/s^2] Vertical acceleration estimated by ADA
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param vbat [V] Battery voltage
- * @param vsupply_5v [V] Power supply 5V
- * @param temperature [degC] Temperature
- * @param pin_launch Launch pin status (1 = connected, 0 = disconnected)
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param servo_sensor Servo sensor status (1 = actuated, 0 = idle)
- * @param ab_angle [deg] Aerobrakes angle
- * @param ab_estimated_cd Estimated drag coefficient
- * @param nas_x [deg] Navigation system estimated X position (longitude)
- * @param nas_y [deg] Navigation system estimated Y position (latitude)
- * @param nas_z [m] Navigation system estimated Z position
- * @param nas_vx [m/s] Navigation system estimated north velocity
- * @param nas_vy [m/s] Navigation system estimated east velocity
- * @param nas_vz [m/s] Navigation system estimated down velocity
- * @param nas_roll [deg] Navigation system estimated attitude (roll)
- * @param nas_pitch [deg] Navigation system estimated attitude (pitch)
- * @param nas_yaw [deg] Navigation system estimated attitude (yaw)
- * @param nas_bias0 Navigation system bias
- * @param nas_bias1 Navigation system bias
- * @param nas_bias2 Navigation system bias
- * @param logger_error Logger error (0 = no error, -1 otherwise)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_hr_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t ada_state,uint8_t fmm_state,uint8_t dpl_state,uint8_t ab_state,uint8_t nas_state,float pressure_ada,float pressure_digi,float pressure_static,float pressure_dpl,float airspeed_pitot,float msl_altitude,float ada_vert_speed,float ada_vert_accel,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float vbat,float vsupply_5v,float temperature,uint8_t pin_launch,uint8_t pin_nosecone,uint8_t servo_sensor,float ab_angle,float ab_estimated_cd,float nas_x,float nas_y,float nas_z,float nas_vx,float nas_vy,float nas_vz,float nas_roll,float nas_pitch,float nas_yaw,float nas_bias0,float nas_bias1,float nas_bias2,int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_HR_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_ada);
- _mav_put_float(buf, 12, pressure_digi);
- _mav_put_float(buf, 16, pressure_static);
- _mav_put_float(buf, 20, pressure_dpl);
- _mav_put_float(buf, 24, airspeed_pitot);
- _mav_put_float(buf, 28, msl_altitude);
- _mav_put_float(buf, 32, ada_vert_speed);
- _mav_put_float(buf, 36, ada_vert_accel);
- _mav_put_float(buf, 40, acc_x);
- _mav_put_float(buf, 44, acc_y);
- _mav_put_float(buf, 48, acc_z);
- _mav_put_float(buf, 52, gyro_x);
- _mav_put_float(buf, 56, gyro_y);
- _mav_put_float(buf, 60, gyro_z);
- _mav_put_float(buf, 64, mag_x);
- _mav_put_float(buf, 68, mag_y);
- _mav_put_float(buf, 72, mag_z);
- _mav_put_float(buf, 76, gps_lat);
- _mav_put_float(buf, 80, gps_lon);
- _mav_put_float(buf, 84, gps_alt);
- _mav_put_float(buf, 88, vbat);
- _mav_put_float(buf, 92, vsupply_5v);
- _mav_put_float(buf, 96, temperature);
- _mav_put_float(buf, 100, ab_angle);
- _mav_put_float(buf, 104, ab_estimated_cd);
- _mav_put_float(buf, 108, nas_x);
- _mav_put_float(buf, 112, nas_y);
- _mav_put_float(buf, 116, nas_z);
- _mav_put_float(buf, 120, nas_vx);
- _mav_put_float(buf, 124, nas_vy);
- _mav_put_float(buf, 128, nas_vz);
- _mav_put_float(buf, 132, nas_roll);
- _mav_put_float(buf, 136, nas_pitch);
- _mav_put_float(buf, 140, nas_yaw);
- _mav_put_float(buf, 144, nas_bias0);
- _mav_put_float(buf, 148, nas_bias1);
- _mav_put_float(buf, 152, nas_bias2);
- _mav_put_uint8_t(buf, 156, ada_state);
- _mav_put_uint8_t(buf, 157, fmm_state);
- _mav_put_uint8_t(buf, 158, dpl_state);
- _mav_put_uint8_t(buf, 159, ab_state);
- _mav_put_uint8_t(buf, 160, nas_state);
- _mav_put_uint8_t(buf, 161, gps_fix);
- _mav_put_uint8_t(buf, 162, pin_launch);
- _mav_put_uint8_t(buf, 163, pin_nosecone);
- _mav_put_uint8_t(buf, 164, servo_sensor);
- _mav_put_int8_t(buf, 165, logger_error);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HR_TM_LEN);
-#else
- mavlink_hr_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_ada = pressure_ada;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.pressure_dpl = pressure_dpl;
- packet.airspeed_pitot = airspeed_pitot;
- packet.msl_altitude = msl_altitude;
- packet.ada_vert_speed = ada_vert_speed;
- packet.ada_vert_accel = ada_vert_accel;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.vbat = vbat;
- packet.vsupply_5v = vsupply_5v;
- packet.temperature = temperature;
- packet.ab_angle = ab_angle;
- packet.ab_estimated_cd = ab_estimated_cd;
- packet.nas_x = nas_x;
- packet.nas_y = nas_y;
- packet.nas_z = nas_z;
- packet.nas_vx = nas_vx;
- packet.nas_vy = nas_vy;
- packet.nas_vz = nas_vz;
- packet.nas_roll = nas_roll;
- packet.nas_pitch = nas_pitch;
- packet.nas_yaw = nas_yaw;
- packet.nas_bias0 = nas_bias0;
- packet.nas_bias1 = nas_bias1;
- packet.nas_bias2 = nas_bias2;
- packet.ada_state = ada_state;
- packet.fmm_state = fmm_state;
- packet.dpl_state = dpl_state;
- packet.ab_state = ab_state;
- packet.nas_state = nas_state;
- packet.gps_fix = gps_fix;
- packet.pin_launch = pin_launch;
- packet.pin_nosecone = pin_nosecone;
- packet.servo_sensor = servo_sensor;
- packet.logger_error = logger_error;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HR_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_HR_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HR_TM_MIN_LEN, MAVLINK_MSG_ID_HR_TM_LEN, MAVLINK_MSG_ID_HR_TM_CRC);
-}
-
-/**
- * @brief Encode a hr_tm 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 hr_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_hr_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hr_tm_t* hr_tm)
-{
- return mavlink_msg_hr_tm_pack(system_id, component_id, msg, hr_tm->timestamp, hr_tm->ada_state, hr_tm->fmm_state, hr_tm->dpl_state, hr_tm->ab_state, hr_tm->nas_state, hr_tm->pressure_ada, hr_tm->pressure_digi, hr_tm->pressure_static, hr_tm->pressure_dpl, hr_tm->airspeed_pitot, hr_tm->msl_altitude, hr_tm->ada_vert_speed, hr_tm->ada_vert_accel, hr_tm->acc_x, hr_tm->acc_y, hr_tm->acc_z, hr_tm->gyro_x, hr_tm->gyro_y, hr_tm->gyro_z, hr_tm->mag_x, hr_tm->mag_y, hr_tm->mag_z, hr_tm->gps_fix, hr_tm->gps_lat, hr_tm->gps_lon, hr_tm->gps_alt, hr_tm->vbat, hr_tm->vsupply_5v, hr_tm->temperature, hr_tm->pin_launch, hr_tm->pin_nosecone, hr_tm->servo_sensor, hr_tm->ab_angle, hr_tm->ab_estimated_cd, hr_tm->nas_x, hr_tm->nas_y, hr_tm->nas_z, hr_tm->nas_vx, hr_tm->nas_vy, hr_tm->nas_vz, hr_tm->nas_roll, hr_tm->nas_pitch, hr_tm->nas_yaw, hr_tm->nas_bias0, hr_tm->nas_bias1, hr_tm->nas_bias2, hr_tm->logger_error);
-}
-
-/**
- * @brief Encode a hr_tm 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 hr_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_hr_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hr_tm_t* hr_tm)
-{
- return mavlink_msg_hr_tm_pack_chan(system_id, component_id, chan, msg, hr_tm->timestamp, hr_tm->ada_state, hr_tm->fmm_state, hr_tm->dpl_state, hr_tm->ab_state, hr_tm->nas_state, hr_tm->pressure_ada, hr_tm->pressure_digi, hr_tm->pressure_static, hr_tm->pressure_dpl, hr_tm->airspeed_pitot, hr_tm->msl_altitude, hr_tm->ada_vert_speed, hr_tm->ada_vert_accel, hr_tm->acc_x, hr_tm->acc_y, hr_tm->acc_z, hr_tm->gyro_x, hr_tm->gyro_y, hr_tm->gyro_z, hr_tm->mag_x, hr_tm->mag_y, hr_tm->mag_z, hr_tm->gps_fix, hr_tm->gps_lat, hr_tm->gps_lon, hr_tm->gps_alt, hr_tm->vbat, hr_tm->vsupply_5v, hr_tm->temperature, hr_tm->pin_launch, hr_tm->pin_nosecone, hr_tm->servo_sensor, hr_tm->ab_angle, hr_tm->ab_estimated_cd, hr_tm->nas_x, hr_tm->nas_y, hr_tm->nas_z, hr_tm->nas_vx, hr_tm->nas_vy, hr_tm->nas_vz, hr_tm->nas_roll, hr_tm->nas_pitch, hr_tm->nas_yaw, hr_tm->nas_bias0, hr_tm->nas_bias1, hr_tm->nas_bias2, hr_tm->logger_error);
-}
-
-/**
- * @brief Send a hr_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [ms] Timestamp in milliseconds
- * @param ada_state ADA Controller State
- * @param fmm_state Flight Mode Manager State
- * @param dpl_state Deployment Controller State
- * @param ab_state Aerobrake FSM state
- * @param nas_state Navigation System FSM State
- * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane sensor
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param msl_altitude [m] Altitude above mean sea level
- * @param ada_vert_speed [m/s] Vertical speed estimated by ADA
- * @param ada_vert_accel [m/s^2] Vertical acceleration estimated by ADA
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param vbat [V] Battery voltage
- * @param vsupply_5v [V] Power supply 5V
- * @param temperature [degC] Temperature
- * @param pin_launch Launch pin status (1 = connected, 0 = disconnected)
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param servo_sensor Servo sensor status (1 = actuated, 0 = idle)
- * @param ab_angle [deg] Aerobrakes angle
- * @param ab_estimated_cd Estimated drag coefficient
- * @param nas_x [deg] Navigation system estimated X position (longitude)
- * @param nas_y [deg] Navigation system estimated Y position (latitude)
- * @param nas_z [m] Navigation system estimated Z position
- * @param nas_vx [m/s] Navigation system estimated north velocity
- * @param nas_vy [m/s] Navigation system estimated east velocity
- * @param nas_vz [m/s] Navigation system estimated down velocity
- * @param nas_roll [deg] Navigation system estimated attitude (roll)
- * @param nas_pitch [deg] Navigation system estimated attitude (pitch)
- * @param nas_yaw [deg] Navigation system estimated attitude (yaw)
- * @param nas_bias0 Navigation system bias
- * @param nas_bias1 Navigation system bias
- * @param nas_bias2 Navigation system bias
- * @param logger_error Logger error (0 = no error, -1 otherwise)
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_hr_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t ab_state, uint8_t nas_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float msl_altitude, float ada_vert_speed, float ada_vert_accel, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float vbat, float vsupply_5v, float temperature, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t servo_sensor, float ab_angle, float ab_estimated_cd, float nas_x, float nas_y, float nas_z, float nas_vx, float nas_vy, float nas_vz, float nas_roll, float nas_pitch, float nas_yaw, float nas_bias0, float nas_bias1, float nas_bias2, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_HR_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_ada);
- _mav_put_float(buf, 12, pressure_digi);
- _mav_put_float(buf, 16, pressure_static);
- _mav_put_float(buf, 20, pressure_dpl);
- _mav_put_float(buf, 24, airspeed_pitot);
- _mav_put_float(buf, 28, msl_altitude);
- _mav_put_float(buf, 32, ada_vert_speed);
- _mav_put_float(buf, 36, ada_vert_accel);
- _mav_put_float(buf, 40, acc_x);
- _mav_put_float(buf, 44, acc_y);
- _mav_put_float(buf, 48, acc_z);
- _mav_put_float(buf, 52, gyro_x);
- _mav_put_float(buf, 56, gyro_y);
- _mav_put_float(buf, 60, gyro_z);
- _mav_put_float(buf, 64, mag_x);
- _mav_put_float(buf, 68, mag_y);
- _mav_put_float(buf, 72, mag_z);
- _mav_put_float(buf, 76, gps_lat);
- _mav_put_float(buf, 80, gps_lon);
- _mav_put_float(buf, 84, gps_alt);
- _mav_put_float(buf, 88, vbat);
- _mav_put_float(buf, 92, vsupply_5v);
- _mav_put_float(buf, 96, temperature);
- _mav_put_float(buf, 100, ab_angle);
- _mav_put_float(buf, 104, ab_estimated_cd);
- _mav_put_float(buf, 108, nas_x);
- _mav_put_float(buf, 112, nas_y);
- _mav_put_float(buf, 116, nas_z);
- _mav_put_float(buf, 120, nas_vx);
- _mav_put_float(buf, 124, nas_vy);
- _mav_put_float(buf, 128, nas_vz);
- _mav_put_float(buf, 132, nas_roll);
- _mav_put_float(buf, 136, nas_pitch);
- _mav_put_float(buf, 140, nas_yaw);
- _mav_put_float(buf, 144, nas_bias0);
- _mav_put_float(buf, 148, nas_bias1);
- _mav_put_float(buf, 152, nas_bias2);
- _mav_put_uint8_t(buf, 156, ada_state);
- _mav_put_uint8_t(buf, 157, fmm_state);
- _mav_put_uint8_t(buf, 158, dpl_state);
- _mav_put_uint8_t(buf, 159, ab_state);
- _mav_put_uint8_t(buf, 160, nas_state);
- _mav_put_uint8_t(buf, 161, gps_fix);
- _mav_put_uint8_t(buf, 162, pin_launch);
- _mav_put_uint8_t(buf, 163, pin_nosecone);
- _mav_put_uint8_t(buf, 164, servo_sensor);
- _mav_put_int8_t(buf, 165, logger_error);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HR_TM, buf, MAVLINK_MSG_ID_HR_TM_MIN_LEN, MAVLINK_MSG_ID_HR_TM_LEN, MAVLINK_MSG_ID_HR_TM_CRC);
-#else
- mavlink_hr_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_ada = pressure_ada;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.pressure_dpl = pressure_dpl;
- packet.airspeed_pitot = airspeed_pitot;
- packet.msl_altitude = msl_altitude;
- packet.ada_vert_speed = ada_vert_speed;
- packet.ada_vert_accel = ada_vert_accel;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.vbat = vbat;
- packet.vsupply_5v = vsupply_5v;
- packet.temperature = temperature;
- packet.ab_angle = ab_angle;
- packet.ab_estimated_cd = ab_estimated_cd;
- packet.nas_x = nas_x;
- packet.nas_y = nas_y;
- packet.nas_z = nas_z;
- packet.nas_vx = nas_vx;
- packet.nas_vy = nas_vy;
- packet.nas_vz = nas_vz;
- packet.nas_roll = nas_roll;
- packet.nas_pitch = nas_pitch;
- packet.nas_yaw = nas_yaw;
- packet.nas_bias0 = nas_bias0;
- packet.nas_bias1 = nas_bias1;
- packet.nas_bias2 = nas_bias2;
- packet.ada_state = ada_state;
- packet.fmm_state = fmm_state;
- packet.dpl_state = dpl_state;
- packet.ab_state = ab_state;
- packet.nas_state = nas_state;
- packet.gps_fix = gps_fix;
- packet.pin_launch = pin_launch;
- packet.pin_nosecone = pin_nosecone;
- packet.servo_sensor = servo_sensor;
- packet.logger_error = logger_error;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HR_TM, (const char *)&packet, MAVLINK_MSG_ID_HR_TM_MIN_LEN, MAVLINK_MSG_ID_HR_TM_LEN, MAVLINK_MSG_ID_HR_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a hr_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_hr_tm_send_struct(mavlink_channel_t chan, const mavlink_hr_tm_t* hr_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_hr_tm_send(chan, hr_tm->timestamp, hr_tm->ada_state, hr_tm->fmm_state, hr_tm->dpl_state, hr_tm->ab_state, hr_tm->nas_state, hr_tm->pressure_ada, hr_tm->pressure_digi, hr_tm->pressure_static, hr_tm->pressure_dpl, hr_tm->airspeed_pitot, hr_tm->msl_altitude, hr_tm->ada_vert_speed, hr_tm->ada_vert_accel, hr_tm->acc_x, hr_tm->acc_y, hr_tm->acc_z, hr_tm->gyro_x, hr_tm->gyro_y, hr_tm->gyro_z, hr_tm->mag_x, hr_tm->mag_y, hr_tm->mag_z, hr_tm->gps_fix, hr_tm->gps_lat, hr_tm->gps_lon, hr_tm->gps_alt, hr_tm->vbat, hr_tm->vsupply_5v, hr_tm->temperature, hr_tm->pin_launch, hr_tm->pin_nosecone, hr_tm->servo_sensor, hr_tm->ab_angle, hr_tm->ab_estimated_cd, hr_tm->nas_x, hr_tm->nas_y, hr_tm->nas_z, hr_tm->nas_vx, hr_tm->nas_vy, hr_tm->nas_vz, hr_tm->nas_roll, hr_tm->nas_pitch, hr_tm->nas_yaw, hr_tm->nas_bias0, hr_tm->nas_bias1, hr_tm->nas_bias2, hr_tm->logger_error);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HR_TM, (const char *)hr_tm, MAVLINK_MSG_ID_HR_TM_MIN_LEN, MAVLINK_MSG_ID_HR_TM_LEN, MAVLINK_MSG_ID_HR_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_HR_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_hr_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t ab_state, uint8_t nas_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float msl_altitude, float ada_vert_speed, float ada_vert_accel, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float vbat, float vsupply_5v, float temperature, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t servo_sensor, float ab_angle, float ab_estimated_cd, float nas_x, float nas_y, float nas_z, float nas_vx, float nas_vy, float nas_vz, float nas_roll, float nas_pitch, float nas_yaw, float nas_bias0, float nas_bias1, float nas_bias2, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_ada);
- _mav_put_float(buf, 12, pressure_digi);
- _mav_put_float(buf, 16, pressure_static);
- _mav_put_float(buf, 20, pressure_dpl);
- _mav_put_float(buf, 24, airspeed_pitot);
- _mav_put_float(buf, 28, msl_altitude);
- _mav_put_float(buf, 32, ada_vert_speed);
- _mav_put_float(buf, 36, ada_vert_accel);
- _mav_put_float(buf, 40, acc_x);
- _mav_put_float(buf, 44, acc_y);
- _mav_put_float(buf, 48, acc_z);
- _mav_put_float(buf, 52, gyro_x);
- _mav_put_float(buf, 56, gyro_y);
- _mav_put_float(buf, 60, gyro_z);
- _mav_put_float(buf, 64, mag_x);
- _mav_put_float(buf, 68, mag_y);
- _mav_put_float(buf, 72, mag_z);
- _mav_put_float(buf, 76, gps_lat);
- _mav_put_float(buf, 80, gps_lon);
- _mav_put_float(buf, 84, gps_alt);
- _mav_put_float(buf, 88, vbat);
- _mav_put_float(buf, 92, vsupply_5v);
- _mav_put_float(buf, 96, temperature);
- _mav_put_float(buf, 100, ab_angle);
- _mav_put_float(buf, 104, ab_estimated_cd);
- _mav_put_float(buf, 108, nas_x);
- _mav_put_float(buf, 112, nas_y);
- _mav_put_float(buf, 116, nas_z);
- _mav_put_float(buf, 120, nas_vx);
- _mav_put_float(buf, 124, nas_vy);
- _mav_put_float(buf, 128, nas_vz);
- _mav_put_float(buf, 132, nas_roll);
- _mav_put_float(buf, 136, nas_pitch);
- _mav_put_float(buf, 140, nas_yaw);
- _mav_put_float(buf, 144, nas_bias0);
- _mav_put_float(buf, 148, nas_bias1);
- _mav_put_float(buf, 152, nas_bias2);
- _mav_put_uint8_t(buf, 156, ada_state);
- _mav_put_uint8_t(buf, 157, fmm_state);
- _mav_put_uint8_t(buf, 158, dpl_state);
- _mav_put_uint8_t(buf, 159, ab_state);
- _mav_put_uint8_t(buf, 160, nas_state);
- _mav_put_uint8_t(buf, 161, gps_fix);
- _mav_put_uint8_t(buf, 162, pin_launch);
- _mav_put_uint8_t(buf, 163, pin_nosecone);
- _mav_put_uint8_t(buf, 164, servo_sensor);
- _mav_put_int8_t(buf, 165, logger_error);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HR_TM, buf, MAVLINK_MSG_ID_HR_TM_MIN_LEN, MAVLINK_MSG_ID_HR_TM_LEN, MAVLINK_MSG_ID_HR_TM_CRC);
-#else
- mavlink_hr_tm_t *packet = (mavlink_hr_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->pressure_ada = pressure_ada;
- packet->pressure_digi = pressure_digi;
- packet->pressure_static = pressure_static;
- packet->pressure_dpl = pressure_dpl;
- packet->airspeed_pitot = airspeed_pitot;
- packet->msl_altitude = msl_altitude;
- packet->ada_vert_speed = ada_vert_speed;
- packet->ada_vert_accel = ada_vert_accel;
- packet->acc_x = acc_x;
- packet->acc_y = acc_y;
- packet->acc_z = acc_z;
- packet->gyro_x = gyro_x;
- packet->gyro_y = gyro_y;
- packet->gyro_z = gyro_z;
- packet->mag_x = mag_x;
- packet->mag_y = mag_y;
- packet->mag_z = mag_z;
- packet->gps_lat = gps_lat;
- packet->gps_lon = gps_lon;
- packet->gps_alt = gps_alt;
- packet->vbat = vbat;
- packet->vsupply_5v = vsupply_5v;
- packet->temperature = temperature;
- packet->ab_angle = ab_angle;
- packet->ab_estimated_cd = ab_estimated_cd;
- packet->nas_x = nas_x;
- packet->nas_y = nas_y;
- packet->nas_z = nas_z;
- packet->nas_vx = nas_vx;
- packet->nas_vy = nas_vy;
- packet->nas_vz = nas_vz;
- packet->nas_roll = nas_roll;
- packet->nas_pitch = nas_pitch;
- packet->nas_yaw = nas_yaw;
- packet->nas_bias0 = nas_bias0;
- packet->nas_bias1 = nas_bias1;
- packet->nas_bias2 = nas_bias2;
- packet->ada_state = ada_state;
- packet->fmm_state = fmm_state;
- packet->dpl_state = dpl_state;
- packet->ab_state = ab_state;
- packet->nas_state = nas_state;
- packet->gps_fix = gps_fix;
- packet->pin_launch = pin_launch;
- packet->pin_nosecone = pin_nosecone;
- packet->servo_sensor = servo_sensor;
- packet->logger_error = logger_error;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HR_TM, (const char *)packet, MAVLINK_MSG_ID_HR_TM_MIN_LEN, MAVLINK_MSG_ID_HR_TM_LEN, MAVLINK_MSG_ID_HR_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE HR_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from hr_tm message
- *
- * @return [ms] Timestamp in milliseconds
- */
-static inline uint64_t mavlink_msg_hr_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field ada_state from hr_tm message
- *
- * @return ADA Controller State
- */
-static inline uint8_t mavlink_msg_hr_tm_get_ada_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 156);
-}
-
-/**
- * @brief Get field fmm_state from hr_tm message
- *
- * @return Flight Mode Manager State
- */
-static inline uint8_t mavlink_msg_hr_tm_get_fmm_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 157);
-}
-
-/**
- * @brief Get field dpl_state from hr_tm message
- *
- * @return Deployment Controller State
- */
-static inline uint8_t mavlink_msg_hr_tm_get_dpl_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 158);
-}
-
-/**
- * @brief Get field ab_state from hr_tm message
- *
- * @return Aerobrake FSM state
- */
-static inline uint8_t mavlink_msg_hr_tm_get_ab_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 159);
-}
-
-/**
- * @brief Get field nas_state from hr_tm message
- *
- * @return Navigation System FSM State
- */
-static inline uint8_t mavlink_msg_hr_tm_get_nas_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 160);
-}
-
-/**
- * @brief Get field pressure_ada from hr_tm message
- *
- * @return [Pa] Atmospheric pressure estimated by ADA
- */
-static inline float mavlink_msg_hr_tm_get_pressure_ada(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field pressure_digi from hr_tm message
- *
- * @return [Pa] Pressure from digital sensor
- */
-static inline float mavlink_msg_hr_tm_get_pressure_digi(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field pressure_static from hr_tm message
- *
- * @return [Pa] Pressure from static port
- */
-static inline float mavlink_msg_hr_tm_get_pressure_static(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field pressure_dpl from hr_tm message
- *
- * @return [Pa] Pressure from deployment vane sensor
- */
-static inline float mavlink_msg_hr_tm_get_pressure_dpl(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field airspeed_pitot from hr_tm message
- *
- * @return [m/s] Pitot airspeed
- */
-static inline float mavlink_msg_hr_tm_get_airspeed_pitot(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field msl_altitude from hr_tm message
- *
- * @return [m] Altitude above mean sea level
- */
-static inline float mavlink_msg_hr_tm_get_msl_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field ada_vert_speed from hr_tm message
- *
- * @return [m/s] Vertical speed estimated by ADA
- */
-static inline float mavlink_msg_hr_tm_get_ada_vert_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field ada_vert_accel from hr_tm message
- *
- * @return [m/s^2] Vertical acceleration estimated by ADA
- */
-static inline float mavlink_msg_hr_tm_get_ada_vert_accel(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field acc_x from hr_tm message
- *
- * @return [m/s^2] Acceleration on X axis (body)
- */
-static inline float mavlink_msg_hr_tm_get_acc_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field acc_y from hr_tm message
- *
- * @return [m/s^2] Acceleration on Y axis (body)
- */
-static inline float mavlink_msg_hr_tm_get_acc_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field acc_z from hr_tm message
- *
- * @return [m/s^2] Acceleration on Z axis (body)
- */
-static inline float mavlink_msg_hr_tm_get_acc_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field gyro_x from hr_tm message
- *
- * @return [rad/s] Angular speed on X axis (body)
- */
-static inline float mavlink_msg_hr_tm_get_gyro_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field gyro_y from hr_tm message
- *
- * @return [rad/s] Angular speed on Y axis (body)
- */
-static inline float mavlink_msg_hr_tm_get_gyro_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field gyro_z from hr_tm message
- *
- * @return [rad/s] Angular speed on Z axis (body)
- */
-static inline float mavlink_msg_hr_tm_get_gyro_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field mag_x from hr_tm message
- *
- * @return [uT] Magnetic field on X axis (body)
- */
-static inline float mavlink_msg_hr_tm_get_mag_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field mag_y from hr_tm message
- *
- * @return [uT] Magnetic field on Y axis (body)
- */
-static inline float mavlink_msg_hr_tm_get_mag_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field mag_z from hr_tm message
- *
- * @return [uT] Magnetic field on Z axis (body)
- */
-static inline float mavlink_msg_hr_tm_get_mag_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 72);
-}
-
-/**
- * @brief Get field gps_fix from hr_tm message
- *
- * @return GPS fix (1 = fix, 0 = no fix)
- */
-static inline uint8_t mavlink_msg_hr_tm_get_gps_fix(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 161);
-}
-
-/**
- * @brief Get field gps_lat from hr_tm message
- *
- * @return [deg] Latitude
- */
-static inline float mavlink_msg_hr_tm_get_gps_lat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 76);
-}
-
-/**
- * @brief Get field gps_lon from hr_tm message
- *
- * @return [deg] Longitude
- */
-static inline float mavlink_msg_hr_tm_get_gps_lon(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 80);
-}
-
-/**
- * @brief Get field gps_alt from hr_tm message
- *
- * @return [m] GPS Altitude
- */
-static inline float mavlink_msg_hr_tm_get_gps_alt(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 84);
-}
-
-/**
- * @brief Get field vbat from hr_tm message
- *
- * @return [V] Battery voltage
- */
-static inline float mavlink_msg_hr_tm_get_vbat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 88);
-}
-
-/**
- * @brief Get field vsupply_5v from hr_tm message
- *
- * @return [V] Power supply 5V
- */
-static inline float mavlink_msg_hr_tm_get_vsupply_5v(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 92);
-}
-
-/**
- * @brief Get field temperature from hr_tm message
- *
- * @return [degC] Temperature
- */
-static inline float mavlink_msg_hr_tm_get_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 96);
-}
-
-/**
- * @brief Get field pin_launch from hr_tm message
- *
- * @return Launch pin status (1 = connected, 0 = disconnected)
- */
-static inline uint8_t mavlink_msg_hr_tm_get_pin_launch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 162);
-}
-
-/**
- * @brief Get field pin_nosecone from hr_tm message
- *
- * @return Nosecone pin status (1 = connected, 0 = disconnected)
- */
-static inline uint8_t mavlink_msg_hr_tm_get_pin_nosecone(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 163);
-}
-
-/**
- * @brief Get field servo_sensor from hr_tm message
- *
- * @return Servo sensor status (1 = actuated, 0 = idle)
- */
-static inline uint8_t mavlink_msg_hr_tm_get_servo_sensor(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 164);
-}
-
-/**
- * @brief Get field ab_angle from hr_tm message
- *
- * @return [deg] Aerobrakes angle
- */
-static inline float mavlink_msg_hr_tm_get_ab_angle(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 100);
-}
-
-/**
- * @brief Get field ab_estimated_cd from hr_tm message
- *
- * @return Estimated drag coefficient
- */
-static inline float mavlink_msg_hr_tm_get_ab_estimated_cd(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 104);
-}
-
-/**
- * @brief Get field nas_x from hr_tm message
- *
- * @return [deg] Navigation system estimated X position (longitude)
- */
-static inline float mavlink_msg_hr_tm_get_nas_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 108);
-}
-
-/**
- * @brief Get field nas_y from hr_tm message
- *
- * @return [deg] Navigation system estimated Y position (latitude)
- */
-static inline float mavlink_msg_hr_tm_get_nas_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 112);
-}
-
-/**
- * @brief Get field nas_z from hr_tm message
- *
- * @return [m] Navigation system estimated Z position
- */
-static inline float mavlink_msg_hr_tm_get_nas_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 116);
-}
-
-/**
- * @brief Get field nas_vx from hr_tm message
- *
- * @return [m/s] Navigation system estimated north velocity
- */
-static inline float mavlink_msg_hr_tm_get_nas_vx(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 120);
-}
-
-/**
- * @brief Get field nas_vy from hr_tm message
- *
- * @return [m/s] Navigation system estimated east velocity
- */
-static inline float mavlink_msg_hr_tm_get_nas_vy(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 124);
-}
-
-/**
- * @brief Get field nas_vz from hr_tm message
- *
- * @return [m/s] Navigation system estimated down velocity
- */
-static inline float mavlink_msg_hr_tm_get_nas_vz(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 128);
-}
-
-/**
- * @brief Get field nas_roll from hr_tm message
- *
- * @return [deg] Navigation system estimated attitude (roll)
- */
-static inline float mavlink_msg_hr_tm_get_nas_roll(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 132);
-}
-
-/**
- * @brief Get field nas_pitch from hr_tm message
- *
- * @return [deg] Navigation system estimated attitude (pitch)
- */
-static inline float mavlink_msg_hr_tm_get_nas_pitch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 136);
-}
-
-/**
- * @brief Get field nas_yaw from hr_tm message
- *
- * @return [deg] Navigation system estimated attitude (yaw)
- */
-static inline float mavlink_msg_hr_tm_get_nas_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 140);
-}
-
-/**
- * @brief Get field nas_bias0 from hr_tm message
- *
- * @return Navigation system bias
- */
-static inline float mavlink_msg_hr_tm_get_nas_bias0(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 144);
-}
-
-/**
- * @brief Get field nas_bias1 from hr_tm message
- *
- * @return Navigation system bias
- */
-static inline float mavlink_msg_hr_tm_get_nas_bias1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 148);
-}
-
-/**
- * @brief Get field nas_bias2 from hr_tm message
- *
- * @return Navigation system bias
- */
-static inline float mavlink_msg_hr_tm_get_nas_bias2(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 152);
-}
-
-/**
- * @brief Get field logger_error from hr_tm message
- *
- * @return Logger error (0 = no error, -1 otherwise)
- */
-static inline int8_t mavlink_msg_hr_tm_get_logger_error(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int8_t(msg, 165);
-}
-
-/**
- * @brief Decode a hr_tm message into a struct
- *
- * @param msg The message to decode
- * @param hr_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_hr_tm_decode(const mavlink_message_t* msg, mavlink_hr_tm_t* hr_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- hr_tm->timestamp = mavlink_msg_hr_tm_get_timestamp(msg);
- hr_tm->pressure_ada = mavlink_msg_hr_tm_get_pressure_ada(msg);
- hr_tm->pressure_digi = mavlink_msg_hr_tm_get_pressure_digi(msg);
- hr_tm->pressure_static = mavlink_msg_hr_tm_get_pressure_static(msg);
- hr_tm->pressure_dpl = mavlink_msg_hr_tm_get_pressure_dpl(msg);
- hr_tm->airspeed_pitot = mavlink_msg_hr_tm_get_airspeed_pitot(msg);
- hr_tm->msl_altitude = mavlink_msg_hr_tm_get_msl_altitude(msg);
- hr_tm->ada_vert_speed = mavlink_msg_hr_tm_get_ada_vert_speed(msg);
- hr_tm->ada_vert_accel = mavlink_msg_hr_tm_get_ada_vert_accel(msg);
- hr_tm->acc_x = mavlink_msg_hr_tm_get_acc_x(msg);
- hr_tm->acc_y = mavlink_msg_hr_tm_get_acc_y(msg);
- hr_tm->acc_z = mavlink_msg_hr_tm_get_acc_z(msg);
- hr_tm->gyro_x = mavlink_msg_hr_tm_get_gyro_x(msg);
- hr_tm->gyro_y = mavlink_msg_hr_tm_get_gyro_y(msg);
- hr_tm->gyro_z = mavlink_msg_hr_tm_get_gyro_z(msg);
- hr_tm->mag_x = mavlink_msg_hr_tm_get_mag_x(msg);
- hr_tm->mag_y = mavlink_msg_hr_tm_get_mag_y(msg);
- hr_tm->mag_z = mavlink_msg_hr_tm_get_mag_z(msg);
- hr_tm->gps_lat = mavlink_msg_hr_tm_get_gps_lat(msg);
- hr_tm->gps_lon = mavlink_msg_hr_tm_get_gps_lon(msg);
- hr_tm->gps_alt = mavlink_msg_hr_tm_get_gps_alt(msg);
- hr_tm->vbat = mavlink_msg_hr_tm_get_vbat(msg);
- hr_tm->vsupply_5v = mavlink_msg_hr_tm_get_vsupply_5v(msg);
- hr_tm->temperature = mavlink_msg_hr_tm_get_temperature(msg);
- hr_tm->ab_angle = mavlink_msg_hr_tm_get_ab_angle(msg);
- hr_tm->ab_estimated_cd = mavlink_msg_hr_tm_get_ab_estimated_cd(msg);
- hr_tm->nas_x = mavlink_msg_hr_tm_get_nas_x(msg);
- hr_tm->nas_y = mavlink_msg_hr_tm_get_nas_y(msg);
- hr_tm->nas_z = mavlink_msg_hr_tm_get_nas_z(msg);
- hr_tm->nas_vx = mavlink_msg_hr_tm_get_nas_vx(msg);
- hr_tm->nas_vy = mavlink_msg_hr_tm_get_nas_vy(msg);
- hr_tm->nas_vz = mavlink_msg_hr_tm_get_nas_vz(msg);
- hr_tm->nas_roll = mavlink_msg_hr_tm_get_nas_roll(msg);
- hr_tm->nas_pitch = mavlink_msg_hr_tm_get_nas_pitch(msg);
- hr_tm->nas_yaw = mavlink_msg_hr_tm_get_nas_yaw(msg);
- hr_tm->nas_bias0 = mavlink_msg_hr_tm_get_nas_bias0(msg);
- hr_tm->nas_bias1 = mavlink_msg_hr_tm_get_nas_bias1(msg);
- hr_tm->nas_bias2 = mavlink_msg_hr_tm_get_nas_bias2(msg);
- hr_tm->ada_state = mavlink_msg_hr_tm_get_ada_state(msg);
- hr_tm->fmm_state = mavlink_msg_hr_tm_get_fmm_state(msg);
- hr_tm->dpl_state = mavlink_msg_hr_tm_get_dpl_state(msg);
- hr_tm->ab_state = mavlink_msg_hr_tm_get_ab_state(msg);
- hr_tm->nas_state = mavlink_msg_hr_tm_get_nas_state(msg);
- hr_tm->gps_fix = mavlink_msg_hr_tm_get_gps_fix(msg);
- hr_tm->pin_launch = mavlink_msg_hr_tm_get_pin_launch(msg);
- hr_tm->pin_nosecone = mavlink_msg_hr_tm_get_pin_nosecone(msg);
- hr_tm->servo_sensor = mavlink_msg_hr_tm_get_servo_sensor(msg);
- hr_tm->logger_error = mavlink_msg_hr_tm_get_logger_error(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_HR_TM_LEN? msg->len : MAVLINK_MSG_ID_HR_TM_LEN;
- memset(hr_tm, 0, MAVLINK_MSG_ID_HR_TM_LEN);
- memcpy(hr_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_lis3mdl_tm.h b/mavlink_lib/lynx/mavlink_msg_lis3mdl_tm.h
deleted file mode 100644
index 2ca9aa15e696f7582c4792bc8f7c65b9644745c4..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_lis3mdl_tm.h
+++ /dev/null
@@ -1,313 +0,0 @@
-#pragma once
-// MESSAGE LIS3MDL_TM PACKING
-
-#define MAVLINK_MSG_ID_LIS3MDL_TM 174
-
-MAVPACKED(
-typedef struct __mavlink_lis3mdl_tm_t {
- uint64_t timestamp; /*< [ms] When was this logged*/
- float mag_x; /*< [rad/s] X axis compass*/
- float mag_y; /*< [rad/s] Y axis compass*/
- float mag_z; /*< [rad/s] Z axis compass*/
- float temp; /*< [deg] Temperature*/
-}) mavlink_lis3mdl_tm_t;
-
-#define MAVLINK_MSG_ID_LIS3MDL_TM_LEN 24
-#define MAVLINK_MSG_ID_LIS3MDL_TM_MIN_LEN 24
-#define MAVLINK_MSG_ID_174_LEN 24
-#define MAVLINK_MSG_ID_174_MIN_LEN 24
-
-#define MAVLINK_MSG_ID_LIS3MDL_TM_CRC 129
-#define MAVLINK_MSG_ID_174_CRC 129
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_LIS3MDL_TM { \
- 174, \
- "LIS3MDL_TM", \
- 5, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_lis3mdl_tm_t, timestamp) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_lis3mdl_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_lis3mdl_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_lis3mdl_tm_t, mag_z) }, \
- { "temp", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_lis3mdl_tm_t, temp) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_LIS3MDL_TM { \
- "LIS3MDL_TM", \
- 5, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_lis3mdl_tm_t, timestamp) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_lis3mdl_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_lis3mdl_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_lis3mdl_tm_t, mag_z) }, \
- { "temp", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_lis3mdl_tm_t, temp) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a lis3mdl_tm 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] When was this logged
- * @param mag_x [rad/s] X axis compass
- * @param mag_y [rad/s] Y axis compass
- * @param mag_z [rad/s] Z axis compass
- * @param temp [deg] Temperature
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_lis3mdl_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, float mag_x, float mag_y, float mag_z, float temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LIS3MDL_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, mag_x);
- _mav_put_float(buf, 12, mag_y);
- _mav_put_float(buf, 16, mag_z);
- _mav_put_float(buf, 20, temp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LIS3MDL_TM_LEN);
-#else
- mavlink_lis3mdl_tm_t packet;
- packet.timestamp = timestamp;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.temp = temp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LIS3MDL_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LIS3MDL_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LIS3MDL_TM_MIN_LEN, MAVLINK_MSG_ID_LIS3MDL_TM_LEN, MAVLINK_MSG_ID_LIS3MDL_TM_CRC);
-}
-
-/**
- * @brief Pack a lis3mdl_tm 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] When was this logged
- * @param mag_x [rad/s] X axis compass
- * @param mag_y [rad/s] Y axis compass
- * @param mag_z [rad/s] Z axis compass
- * @param temp [deg] Temperature
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_lis3mdl_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,float mag_x,float mag_y,float mag_z,float temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LIS3MDL_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, mag_x);
- _mav_put_float(buf, 12, mag_y);
- _mav_put_float(buf, 16, mag_z);
- _mav_put_float(buf, 20, temp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LIS3MDL_TM_LEN);
-#else
- mavlink_lis3mdl_tm_t packet;
- packet.timestamp = timestamp;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.temp = temp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LIS3MDL_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LIS3MDL_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LIS3MDL_TM_MIN_LEN, MAVLINK_MSG_ID_LIS3MDL_TM_LEN, MAVLINK_MSG_ID_LIS3MDL_TM_CRC);
-}
-
-/**
- * @brief Encode a lis3mdl_tm 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 lis3mdl_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_lis3mdl_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_lis3mdl_tm_t* lis3mdl_tm)
-{
- return mavlink_msg_lis3mdl_tm_pack(system_id, component_id, msg, lis3mdl_tm->timestamp, lis3mdl_tm->mag_x, lis3mdl_tm->mag_y, lis3mdl_tm->mag_z, lis3mdl_tm->temp);
-}
-
-/**
- * @brief Encode a lis3mdl_tm 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 lis3mdl_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_lis3mdl_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_lis3mdl_tm_t* lis3mdl_tm)
-{
- return mavlink_msg_lis3mdl_tm_pack_chan(system_id, component_id, chan, msg, lis3mdl_tm->timestamp, lis3mdl_tm->mag_x, lis3mdl_tm->mag_y, lis3mdl_tm->mag_z, lis3mdl_tm->temp);
-}
-
-/**
- * @brief Send a lis3mdl_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [ms] When was this logged
- * @param mag_x [rad/s] X axis compass
- * @param mag_y [rad/s] Y axis compass
- * @param mag_z [rad/s] Z axis compass
- * @param temp [deg] Temperature
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_lis3mdl_tm_send(mavlink_channel_t chan, uint64_t timestamp, float mag_x, float mag_y, float mag_z, float temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LIS3MDL_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, mag_x);
- _mav_put_float(buf, 12, mag_y);
- _mav_put_float(buf, 16, mag_z);
- _mav_put_float(buf, 20, temp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIS3MDL_TM, buf, MAVLINK_MSG_ID_LIS3MDL_TM_MIN_LEN, MAVLINK_MSG_ID_LIS3MDL_TM_LEN, MAVLINK_MSG_ID_LIS3MDL_TM_CRC);
-#else
- mavlink_lis3mdl_tm_t packet;
- packet.timestamp = timestamp;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.temp = temp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIS3MDL_TM, (const char *)&packet, MAVLINK_MSG_ID_LIS3MDL_TM_MIN_LEN, MAVLINK_MSG_ID_LIS3MDL_TM_LEN, MAVLINK_MSG_ID_LIS3MDL_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a lis3mdl_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_lis3mdl_tm_send_struct(mavlink_channel_t chan, const mavlink_lis3mdl_tm_t* lis3mdl_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_lis3mdl_tm_send(chan, lis3mdl_tm->timestamp, lis3mdl_tm->mag_x, lis3mdl_tm->mag_y, lis3mdl_tm->mag_z, lis3mdl_tm->temp);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIS3MDL_TM, (const char *)lis3mdl_tm, MAVLINK_MSG_ID_LIS3MDL_TM_MIN_LEN, MAVLINK_MSG_ID_LIS3MDL_TM_LEN, MAVLINK_MSG_ID_LIS3MDL_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_LIS3MDL_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_lis3mdl_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float mag_x, float mag_y, float mag_z, float temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, mag_x);
- _mav_put_float(buf, 12, mag_y);
- _mav_put_float(buf, 16, mag_z);
- _mav_put_float(buf, 20, temp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIS3MDL_TM, buf, MAVLINK_MSG_ID_LIS3MDL_TM_MIN_LEN, MAVLINK_MSG_ID_LIS3MDL_TM_LEN, MAVLINK_MSG_ID_LIS3MDL_TM_CRC);
-#else
- mavlink_lis3mdl_tm_t *packet = (mavlink_lis3mdl_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->mag_x = mag_x;
- packet->mag_y = mag_y;
- packet->mag_z = mag_z;
- packet->temp = temp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIS3MDL_TM, (const char *)packet, MAVLINK_MSG_ID_LIS3MDL_TM_MIN_LEN, MAVLINK_MSG_ID_LIS3MDL_TM_LEN, MAVLINK_MSG_ID_LIS3MDL_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE LIS3MDL_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from lis3mdl_tm message
- *
- * @return [ms] When was this logged
- */
-static inline uint64_t mavlink_msg_lis3mdl_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field mag_x from lis3mdl_tm message
- *
- * @return [rad/s] X axis compass
- */
-static inline float mavlink_msg_lis3mdl_tm_get_mag_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field mag_y from lis3mdl_tm message
- *
- * @return [rad/s] Y axis compass
- */
-static inline float mavlink_msg_lis3mdl_tm_get_mag_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field mag_z from lis3mdl_tm message
- *
- * @return [rad/s] Z axis compass
- */
-static inline float mavlink_msg_lis3mdl_tm_get_mag_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field temp from lis3mdl_tm message
- *
- * @return [deg] Temperature
- */
-static inline float mavlink_msg_lis3mdl_tm_get_temp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Decode a lis3mdl_tm message into a struct
- *
- * @param msg The message to decode
- * @param lis3mdl_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_lis3mdl_tm_decode(const mavlink_message_t* msg, mavlink_lis3mdl_tm_t* lis3mdl_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- lis3mdl_tm->timestamp = mavlink_msg_lis3mdl_tm_get_timestamp(msg);
- lis3mdl_tm->mag_x = mavlink_msg_lis3mdl_tm_get_mag_x(msg);
- lis3mdl_tm->mag_y = mavlink_msg_lis3mdl_tm_get_mag_y(msg);
- lis3mdl_tm->mag_z = mavlink_msg_lis3mdl_tm_get_mag_z(msg);
- lis3mdl_tm->temp = mavlink_msg_lis3mdl_tm_get_temp(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_LIS3MDL_TM_LEN? msg->len : MAVLINK_MSG_ID_LIS3MDL_TM_LEN;
- memset(lis3mdl_tm, 0, MAVLINK_MSG_ID_LIS3MDL_TM_LEN);
- memcpy(lis3mdl_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_logger_tm.h b/mavlink_lib/lynx/mavlink_msg_logger_tm.h
deleted file mode 100644
index 5a84a0f0a149ddf4d3712b1319cbc6b2e0f81af2..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_logger_tm.h
+++ /dev/null
@@ -1,463 +0,0 @@
-#pragma once
-// MESSAGE LOGGER_TM PACKING
-
-#define MAVLINK_MSG_ID_LOGGER_TM 163
-
-MAVPACKED(
-typedef struct __mavlink_logger_tm_t {
- uint64_t timestamp; /*< [ms] Timestamp*/
- int32_t statTooLargeSamples; /*< Number of dropped samples because too large*/
- int32_t statDroppedSamples; /*< Number of dropped samples due to fifo full*/
- int32_t statQueuedSamples; /*< Number of samples written to buffer*/
- int32_t statBufferFilled; /*< Number of buffers filled*/
- int32_t statBufferWritten; /*< Number of buffers written to disk*/
- int32_t statWriteFailed; /*< Number of fwrite() that failed*/
- int32_t statWriteError; /*< Error of the last fwrite() that failed*/
- int32_t statWriteTime; /*< Time to perform an fwrite() of a buffer*/
- int32_t statMaxWriteTime; /*< Max time to perform an fwrite() of a buffer*/
- uint16_t statLogNumber; /*< Currently active log file*/
-}) mavlink_logger_tm_t;
-
-#define MAVLINK_MSG_ID_LOGGER_TM_LEN 46
-#define MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN 46
-#define MAVLINK_MSG_ID_163_LEN 46
-#define MAVLINK_MSG_ID_163_MIN_LEN 46
-
-#define MAVLINK_MSG_ID_LOGGER_TM_CRC 163
-#define MAVLINK_MSG_ID_163_CRC 163
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_LOGGER_TM { \
- 163, \
- "LOGGER_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_logger_tm_t, timestamp) }, \
- { "statLogNumber", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_logger_tm_t, statLogNumber) }, \
- { "statTooLargeSamples", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_logger_tm_t, statTooLargeSamples) }, \
- { "statDroppedSamples", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_logger_tm_t, statDroppedSamples) }, \
- { "statQueuedSamples", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_logger_tm_t, statQueuedSamples) }, \
- { "statBufferFilled", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_logger_tm_t, statBufferFilled) }, \
- { "statBufferWritten", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_logger_tm_t, statBufferWritten) }, \
- { "statWriteFailed", NULL, MAVLINK_TYPE_INT32_T, 0, 28, offsetof(mavlink_logger_tm_t, statWriteFailed) }, \
- { "statWriteError", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_logger_tm_t, statWriteError) }, \
- { "statWriteTime", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_logger_tm_t, statWriteTime) }, \
- { "statMaxWriteTime", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_logger_tm_t, statMaxWriteTime) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_LOGGER_TM { \
- "LOGGER_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_logger_tm_t, timestamp) }, \
- { "statLogNumber", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_logger_tm_t, statLogNumber) }, \
- { "statTooLargeSamples", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_logger_tm_t, statTooLargeSamples) }, \
- { "statDroppedSamples", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_logger_tm_t, statDroppedSamples) }, \
- { "statQueuedSamples", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_logger_tm_t, statQueuedSamples) }, \
- { "statBufferFilled", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_logger_tm_t, statBufferFilled) }, \
- { "statBufferWritten", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_logger_tm_t, statBufferWritten) }, \
- { "statWriteFailed", NULL, MAVLINK_TYPE_INT32_T, 0, 28, offsetof(mavlink_logger_tm_t, statWriteFailed) }, \
- { "statWriteError", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_logger_tm_t, statWriteError) }, \
- { "statWriteTime", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_logger_tm_t, statWriteTime) }, \
- { "statMaxWriteTime", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_logger_tm_t, statMaxWriteTime) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a logger_tm 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
- * @param statLogNumber Currently active log file
- * @param statTooLargeSamples Number of dropped samples because too large
- * @param statDroppedSamples Number of dropped samples due to fifo full
- * @param statQueuedSamples Number of samples written to buffer
- * @param statBufferFilled Number of buffers filled
- * @param statBufferWritten Number of buffers written to disk
- * @param statWriteFailed Number of fwrite() that failed
- * @param statWriteError Error of the last fwrite() that failed
- * @param statWriteTime Time to perform an fwrite() of a buffer
- * @param statMaxWriteTime Max time to perform an fwrite() of a buffer
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_logger_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint16_t statLogNumber, int32_t statTooLargeSamples, int32_t statDroppedSamples, int32_t statQueuedSamples, int32_t statBufferFilled, int32_t statBufferWritten, int32_t statWriteFailed, int32_t statWriteError, int32_t statWriteTime, int32_t statMaxWriteTime)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOGGER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 8, statTooLargeSamples);
- _mav_put_int32_t(buf, 12, statDroppedSamples);
- _mav_put_int32_t(buf, 16, statQueuedSamples);
- _mav_put_int32_t(buf, 20, statBufferFilled);
- _mav_put_int32_t(buf, 24, statBufferWritten);
- _mav_put_int32_t(buf, 28, statWriteFailed);
- _mav_put_int32_t(buf, 32, statWriteError);
- _mav_put_int32_t(buf, 36, statWriteTime);
- _mav_put_int32_t(buf, 40, statMaxWriteTime);
- _mav_put_uint16_t(buf, 44, statLogNumber);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGER_TM_LEN);
-#else
- mavlink_logger_tm_t packet;
- packet.timestamp = timestamp;
- packet.statTooLargeSamples = statTooLargeSamples;
- packet.statDroppedSamples = statDroppedSamples;
- packet.statQueuedSamples = statQueuedSamples;
- packet.statBufferFilled = statBufferFilled;
- packet.statBufferWritten = statBufferWritten;
- packet.statWriteFailed = statWriteFailed;
- packet.statWriteError = statWriteError;
- packet.statWriteTime = statWriteTime;
- packet.statMaxWriteTime = statMaxWriteTime;
- packet.statLogNumber = statLogNumber;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGER_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LOGGER_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-}
-
-/**
- * @brief Pack a logger_tm 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
- * @param statLogNumber Currently active log file
- * @param statTooLargeSamples Number of dropped samples because too large
- * @param statDroppedSamples Number of dropped samples due to fifo full
- * @param statQueuedSamples Number of samples written to buffer
- * @param statBufferFilled Number of buffers filled
- * @param statBufferWritten Number of buffers written to disk
- * @param statWriteFailed Number of fwrite() that failed
- * @param statWriteError Error of the last fwrite() that failed
- * @param statWriteTime Time to perform an fwrite() of a buffer
- * @param statMaxWriteTime Max time to perform an fwrite() of a buffer
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_logger_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint16_t statLogNumber,int32_t statTooLargeSamples,int32_t statDroppedSamples,int32_t statQueuedSamples,int32_t statBufferFilled,int32_t statBufferWritten,int32_t statWriteFailed,int32_t statWriteError,int32_t statWriteTime,int32_t statMaxWriteTime)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOGGER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 8, statTooLargeSamples);
- _mav_put_int32_t(buf, 12, statDroppedSamples);
- _mav_put_int32_t(buf, 16, statQueuedSamples);
- _mav_put_int32_t(buf, 20, statBufferFilled);
- _mav_put_int32_t(buf, 24, statBufferWritten);
- _mav_put_int32_t(buf, 28, statWriteFailed);
- _mav_put_int32_t(buf, 32, statWriteError);
- _mav_put_int32_t(buf, 36, statWriteTime);
- _mav_put_int32_t(buf, 40, statMaxWriteTime);
- _mav_put_uint16_t(buf, 44, statLogNumber);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGER_TM_LEN);
-#else
- mavlink_logger_tm_t packet;
- packet.timestamp = timestamp;
- packet.statTooLargeSamples = statTooLargeSamples;
- packet.statDroppedSamples = statDroppedSamples;
- packet.statQueuedSamples = statQueuedSamples;
- packet.statBufferFilled = statBufferFilled;
- packet.statBufferWritten = statBufferWritten;
- packet.statWriteFailed = statWriteFailed;
- packet.statWriteError = statWriteError;
- packet.statWriteTime = statWriteTime;
- packet.statMaxWriteTime = statMaxWriteTime;
- packet.statLogNumber = statLogNumber;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGER_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LOGGER_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-}
-
-/**
- * @brief Encode a logger_tm 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 logger_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_logger_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_logger_tm_t* logger_tm)
-{
- return mavlink_msg_logger_tm_pack(system_id, component_id, msg, logger_tm->timestamp, logger_tm->statLogNumber, logger_tm->statTooLargeSamples, logger_tm->statDroppedSamples, logger_tm->statQueuedSamples, logger_tm->statBufferFilled, logger_tm->statBufferWritten, logger_tm->statWriteFailed, logger_tm->statWriteError, logger_tm->statWriteTime, logger_tm->statMaxWriteTime);
-}
-
-/**
- * @brief Encode a logger_tm 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 logger_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_logger_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_logger_tm_t* logger_tm)
-{
- return mavlink_msg_logger_tm_pack_chan(system_id, component_id, chan, msg, logger_tm->timestamp, logger_tm->statLogNumber, logger_tm->statTooLargeSamples, logger_tm->statDroppedSamples, logger_tm->statQueuedSamples, logger_tm->statBufferFilled, logger_tm->statBufferWritten, logger_tm->statWriteFailed, logger_tm->statWriteError, logger_tm->statWriteTime, logger_tm->statMaxWriteTime);
-}
-
-/**
- * @brief Send a logger_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [ms] Timestamp
- * @param statLogNumber Currently active log file
- * @param statTooLargeSamples Number of dropped samples because too large
- * @param statDroppedSamples Number of dropped samples due to fifo full
- * @param statQueuedSamples Number of samples written to buffer
- * @param statBufferFilled Number of buffers filled
- * @param statBufferWritten Number of buffers written to disk
- * @param statWriteFailed Number of fwrite() that failed
- * @param statWriteError Error of the last fwrite() that failed
- * @param statWriteTime Time to perform an fwrite() of a buffer
- * @param statMaxWriteTime Max time to perform an fwrite() of a buffer
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_logger_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint16_t statLogNumber, int32_t statTooLargeSamples, int32_t statDroppedSamples, int32_t statQueuedSamples, int32_t statBufferFilled, int32_t statBufferWritten, int32_t statWriteFailed, int32_t statWriteError, int32_t statWriteTime, int32_t statMaxWriteTime)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOGGER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 8, statTooLargeSamples);
- _mav_put_int32_t(buf, 12, statDroppedSamples);
- _mav_put_int32_t(buf, 16, statQueuedSamples);
- _mav_put_int32_t(buf, 20, statBufferFilled);
- _mav_put_int32_t(buf, 24, statBufferWritten);
- _mav_put_int32_t(buf, 28, statWriteFailed);
- _mav_put_int32_t(buf, 32, statWriteError);
- _mav_put_int32_t(buf, 36, statWriteTime);
- _mav_put_int32_t(buf, 40, statMaxWriteTime);
- _mav_put_uint16_t(buf, 44, statLogNumber);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, buf, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#else
- mavlink_logger_tm_t packet;
- packet.timestamp = timestamp;
- packet.statTooLargeSamples = statTooLargeSamples;
- packet.statDroppedSamples = statDroppedSamples;
- packet.statQueuedSamples = statQueuedSamples;
- packet.statBufferFilled = statBufferFilled;
- packet.statBufferWritten = statBufferWritten;
- packet.statWriteFailed = statWriteFailed;
- packet.statWriteError = statWriteError;
- packet.statWriteTime = statWriteTime;
- packet.statMaxWriteTime = statMaxWriteTime;
- packet.statLogNumber = statLogNumber;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, (const char *)&packet, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a logger_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_logger_tm_send_struct(mavlink_channel_t chan, const mavlink_logger_tm_t* logger_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_logger_tm_send(chan, logger_tm->timestamp, logger_tm->statLogNumber, logger_tm->statTooLargeSamples, logger_tm->statDroppedSamples, logger_tm->statQueuedSamples, logger_tm->statBufferFilled, logger_tm->statBufferWritten, logger_tm->statWriteFailed, logger_tm->statWriteError, logger_tm->statWriteTime, logger_tm->statMaxWriteTime);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, (const char *)logger_tm, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_LOGGER_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_logger_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint16_t statLogNumber, int32_t statTooLargeSamples, int32_t statDroppedSamples, int32_t statQueuedSamples, int32_t statBufferFilled, int32_t statBufferWritten, int32_t statWriteFailed, int32_t statWriteError, int32_t statWriteTime, int32_t statMaxWriteTime)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 8, statTooLargeSamples);
- _mav_put_int32_t(buf, 12, statDroppedSamples);
- _mav_put_int32_t(buf, 16, statQueuedSamples);
- _mav_put_int32_t(buf, 20, statBufferFilled);
- _mav_put_int32_t(buf, 24, statBufferWritten);
- _mav_put_int32_t(buf, 28, statWriteFailed);
- _mav_put_int32_t(buf, 32, statWriteError);
- _mav_put_int32_t(buf, 36, statWriteTime);
- _mav_put_int32_t(buf, 40, statMaxWriteTime);
- _mav_put_uint16_t(buf, 44, statLogNumber);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, buf, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#else
- mavlink_logger_tm_t *packet = (mavlink_logger_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->statTooLargeSamples = statTooLargeSamples;
- packet->statDroppedSamples = statDroppedSamples;
- packet->statQueuedSamples = statQueuedSamples;
- packet->statBufferFilled = statBufferFilled;
- packet->statBufferWritten = statBufferWritten;
- packet->statWriteFailed = statWriteFailed;
- packet->statWriteError = statWriteError;
- packet->statWriteTime = statWriteTime;
- packet->statMaxWriteTime = statMaxWriteTime;
- packet->statLogNumber = statLogNumber;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, (const char *)packet, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE LOGGER_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from logger_tm message
- *
- * @return [ms] Timestamp
- */
-static inline uint64_t mavlink_msg_logger_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field statLogNumber from logger_tm message
- *
- * @return Currently active log file
- */
-static inline uint16_t mavlink_msg_logger_tm_get_statLogNumber(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 44);
-}
-
-/**
- * @brief Get field statTooLargeSamples from logger_tm message
- *
- * @return Number of dropped samples because too large
- */
-static inline int32_t mavlink_msg_logger_tm_get_statTooLargeSamples(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 8);
-}
-
-/**
- * @brief Get field statDroppedSamples from logger_tm message
- *
- * @return Number of dropped samples due to fifo full
- */
-static inline int32_t mavlink_msg_logger_tm_get_statDroppedSamples(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 12);
-}
-
-/**
- * @brief Get field statQueuedSamples from logger_tm message
- *
- * @return Number of samples written to buffer
- */
-static inline int32_t mavlink_msg_logger_tm_get_statQueuedSamples(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 16);
-}
-
-/**
- * @brief Get field statBufferFilled from logger_tm message
- *
- * @return Number of buffers filled
- */
-static inline int32_t mavlink_msg_logger_tm_get_statBufferFilled(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 20);
-}
-
-/**
- * @brief Get field statBufferWritten from logger_tm message
- *
- * @return Number of buffers written to disk
- */
-static inline int32_t mavlink_msg_logger_tm_get_statBufferWritten(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 24);
-}
-
-/**
- * @brief Get field statWriteFailed from logger_tm message
- *
- * @return Number of fwrite() that failed
- */
-static inline int32_t mavlink_msg_logger_tm_get_statWriteFailed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 28);
-}
-
-/**
- * @brief Get field statWriteError from logger_tm message
- *
- * @return Error of the last fwrite() that failed
- */
-static inline int32_t mavlink_msg_logger_tm_get_statWriteError(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 32);
-}
-
-/**
- * @brief Get field statWriteTime from logger_tm message
- *
- * @return Time to perform an fwrite() of a buffer
- */
-static inline int32_t mavlink_msg_logger_tm_get_statWriteTime(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 36);
-}
-
-/**
- * @brief Get field statMaxWriteTime from logger_tm message
- *
- * @return Max time to perform an fwrite() of a buffer
- */
-static inline int32_t mavlink_msg_logger_tm_get_statMaxWriteTime(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 40);
-}
-
-/**
- * @brief Decode a logger_tm message into a struct
- *
- * @param msg The message to decode
- * @param logger_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_logger_tm_decode(const mavlink_message_t* msg, mavlink_logger_tm_t* logger_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- logger_tm->timestamp = mavlink_msg_logger_tm_get_timestamp(msg);
- logger_tm->statTooLargeSamples = mavlink_msg_logger_tm_get_statTooLargeSamples(msg);
- logger_tm->statDroppedSamples = mavlink_msg_logger_tm_get_statDroppedSamples(msg);
- logger_tm->statQueuedSamples = mavlink_msg_logger_tm_get_statQueuedSamples(msg);
- logger_tm->statBufferFilled = mavlink_msg_logger_tm_get_statBufferFilled(msg);
- logger_tm->statBufferWritten = mavlink_msg_logger_tm_get_statBufferWritten(msg);
- logger_tm->statWriteFailed = mavlink_msg_logger_tm_get_statWriteFailed(msg);
- logger_tm->statWriteError = mavlink_msg_logger_tm_get_statWriteError(msg);
- logger_tm->statWriteTime = mavlink_msg_logger_tm_get_statWriteTime(msg);
- logger_tm->statMaxWriteTime = mavlink_msg_logger_tm_get_statMaxWriteTime(msg);
- logger_tm->statLogNumber = mavlink_msg_logger_tm_get_statLogNumber(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_LOGGER_TM_LEN? msg->len : MAVLINK_MSG_ID_LOGGER_TM_LEN;
- memset(logger_tm, 0, MAVLINK_MSG_ID_LOGGER_TM_LEN);
- memcpy(logger_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_lr_tm.h b/mavlink_lib/lynx/mavlink_msg_lr_tm.h
deleted file mode 100644
index 62d249b715a04456db37be6c07604f7cbdf9ced0..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_lr_tm.h
+++ /dev/null
@@ -1,788 +0,0 @@
-#pragma once
-// MESSAGE LR_TM PACKING
-
-#define MAVLINK_MSG_ID_LR_TM 181
-
-MAVPACKED(
-typedef struct __mavlink_lr_tm_t {
- uint64_t liftoff_ts; /*< [ms] System clock at liftoff*/
- uint64_t liftoff_max_acc_ts; /*< [ms] System clock at the maximum liftoff acceleration*/
- uint64_t max_z_speed_ts; /*< [ms] System clock at ADA max vertical speed*/
- uint64_t apogee_ts; /*< [ms] System clock at apogee*/
- uint64_t drogue_dpl_ts; /*< [ms] System clock at drouge deployment*/
- uint64_t main_dpl_altitude_ts; /*< [ms] System clock at main chute deployment*/
- float liftoff_max_acc; /*< [m/s2] Maximum liftoff acceleration*/
- float max_z_speed; /*< [m/s] Max measured vertical speed - ADA*/
- float max_airspeed_pitot; /*< [m/s] Max speed read by the pitot tube*/
- float max_speed_altitude; /*< [m] Altitude at max speed*/
- float apogee_lat; /*< [deg] Apogee latitude*/
- float apogee_lon; /*< [deg] Apogee longitude*/
- float static_min_pressure; /*< [Pa] Apogee pressure - Static ports*/
- float digital_min_pressure; /*< [Pa] Apogee pressure - Digital barometer*/
- float ada_min_pressure; /*< [Pa] Apogee pressure - ADA filtered*/
- float baro_max_altitutde; /*< [m] Apogee altitude - Digital barometer*/
- float gps_max_altitude; /*< [m] Apogee altitude - GPS*/
- float drogue_dpl_max_acc; /*< [m/s2] Max acceleration during drouge deployment*/
- float dpl_vane_max_pressure; /*< [Pa] Max pressure in the deployment bay during drogue deployment*/
- float main_dpl_altitude; /*< [m] Altittude at main deployment (m.s.l)*/
- float main_dpl_zspeed; /*< [m/s] Vertical speed at main deployment (sensor z axis)*/
- float main_dpl_acc; /*< [m/s2] Max measured vertical acceleration (sensor z axis) after main parachute deployment*/
- float cpu_load; /*< CPU load in percentage*/
- uint32_t free_heap; /*< Amount of available heap in memory*/
-}) mavlink_lr_tm_t;
-
-#define MAVLINK_MSG_ID_LR_TM_LEN 120
-#define MAVLINK_MSG_ID_LR_TM_MIN_LEN 120
-#define MAVLINK_MSG_ID_181_LEN 120
-#define MAVLINK_MSG_ID_181_MIN_LEN 120
-
-#define MAVLINK_MSG_ID_LR_TM_CRC 11
-#define MAVLINK_MSG_ID_181_CRC 11
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_LR_TM { \
- 181, \
- "LR_TM", \
- 24, \
- { { "liftoff_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_lr_tm_t, liftoff_ts) }, \
- { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_lr_tm_t, liftoff_max_acc_ts) }, \
- { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_lr_tm_t, liftoff_max_acc) }, \
- { "max_z_speed_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_lr_tm_t, max_z_speed_ts) }, \
- { "max_z_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_lr_tm_t, max_z_speed) }, \
- { "max_airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_lr_tm_t, max_airspeed_pitot) }, \
- { "max_speed_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_lr_tm_t, max_speed_altitude) }, \
- { "apogee_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 24, offsetof(mavlink_lr_tm_t, apogee_ts) }, \
- { "apogee_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_lr_tm_t, apogee_lat) }, \
- { "apogee_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_lr_tm_t, apogee_lon) }, \
- { "static_min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_lr_tm_t, static_min_pressure) }, \
- { "digital_min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_lr_tm_t, digital_min_pressure) }, \
- { "ada_min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_lr_tm_t, ada_min_pressure) }, \
- { "baro_max_altitutde", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_lr_tm_t, baro_max_altitutde) }, \
- { "gps_max_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_lr_tm_t, gps_max_altitude) }, \
- { "drogue_dpl_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 32, offsetof(mavlink_lr_tm_t, drogue_dpl_ts) }, \
- { "drogue_dpl_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_lr_tm_t, drogue_dpl_max_acc) }, \
- { "dpl_vane_max_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_lr_tm_t, dpl_vane_max_pressure) }, \
- { "main_dpl_altitude_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 40, offsetof(mavlink_lr_tm_t, main_dpl_altitude_ts) }, \
- { "main_dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_lr_tm_t, main_dpl_altitude) }, \
- { "main_dpl_zspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_lr_tm_t, main_dpl_zspeed) }, \
- { "main_dpl_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_lr_tm_t, main_dpl_acc) }, \
- { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_lr_tm_t, cpu_load) }, \
- { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 116, offsetof(mavlink_lr_tm_t, free_heap) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_LR_TM { \
- "LR_TM", \
- 24, \
- { { "liftoff_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_lr_tm_t, liftoff_ts) }, \
- { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_lr_tm_t, liftoff_max_acc_ts) }, \
- { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_lr_tm_t, liftoff_max_acc) }, \
- { "max_z_speed_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_lr_tm_t, max_z_speed_ts) }, \
- { "max_z_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_lr_tm_t, max_z_speed) }, \
- { "max_airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_lr_tm_t, max_airspeed_pitot) }, \
- { "max_speed_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_lr_tm_t, max_speed_altitude) }, \
- { "apogee_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 24, offsetof(mavlink_lr_tm_t, apogee_ts) }, \
- { "apogee_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_lr_tm_t, apogee_lat) }, \
- { "apogee_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_lr_tm_t, apogee_lon) }, \
- { "static_min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_lr_tm_t, static_min_pressure) }, \
- { "digital_min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_lr_tm_t, digital_min_pressure) }, \
- { "ada_min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_lr_tm_t, ada_min_pressure) }, \
- { "baro_max_altitutde", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_lr_tm_t, baro_max_altitutde) }, \
- { "gps_max_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_lr_tm_t, gps_max_altitude) }, \
- { "drogue_dpl_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 32, offsetof(mavlink_lr_tm_t, drogue_dpl_ts) }, \
- { "drogue_dpl_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_lr_tm_t, drogue_dpl_max_acc) }, \
- { "dpl_vane_max_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_lr_tm_t, dpl_vane_max_pressure) }, \
- { "main_dpl_altitude_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 40, offsetof(mavlink_lr_tm_t, main_dpl_altitude_ts) }, \
- { "main_dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_lr_tm_t, main_dpl_altitude) }, \
- { "main_dpl_zspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_lr_tm_t, main_dpl_zspeed) }, \
- { "main_dpl_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_lr_tm_t, main_dpl_acc) }, \
- { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_lr_tm_t, cpu_load) }, \
- { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 116, offsetof(mavlink_lr_tm_t, free_heap) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a lr_tm 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 liftoff_ts [ms] System clock at liftoff
- * @param liftoff_max_acc_ts [ms] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param max_z_speed_ts [ms] System clock at ADA max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed - ADA
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [ms] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param static_min_pressure [Pa] Apogee pressure - Static ports
- * @param digital_min_pressure [Pa] Apogee pressure - Digital barometer
- * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered
- * @param baro_max_altitutde [m] Apogee altitude - Digital barometer
- * @param gps_max_altitude [m] Apogee altitude - GPS
- * @param drogue_dpl_ts [ms] System clock at drouge deployment
- * @param drogue_dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param dpl_vane_max_pressure [Pa] Max pressure in the deployment bay during drogue deployment
- * @param main_dpl_altitude_ts [ms] System clock at main chute deployment
- * @param main_dpl_altitude [m] Altittude at main deployment (m.s.l)
- * @param main_dpl_zspeed [m/s] Vertical speed at main deployment (sensor z axis)
- * @param main_dpl_acc [m/s2] Max measured vertical acceleration (sensor z axis) after main parachute deployment
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_lr_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float static_min_pressure, float digital_min_pressure, float ada_min_pressure, float baro_max_altitutde, float gps_max_altitude, uint64_t drogue_dpl_ts, float drogue_dpl_max_acc, float dpl_vane_max_pressure, uint64_t main_dpl_altitude_ts, float main_dpl_altitude, float main_dpl_zspeed, float main_dpl_acc, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LR_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_ts);
- _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 16, max_z_speed_ts);
- _mav_put_uint64_t(buf, 24, apogee_ts);
- _mav_put_uint64_t(buf, 32, drogue_dpl_ts);
- _mav_put_uint64_t(buf, 40, main_dpl_altitude_ts);
- _mav_put_float(buf, 48, liftoff_max_acc);
- _mav_put_float(buf, 52, max_z_speed);
- _mav_put_float(buf, 56, max_airspeed_pitot);
- _mav_put_float(buf, 60, max_speed_altitude);
- _mav_put_float(buf, 64, apogee_lat);
- _mav_put_float(buf, 68, apogee_lon);
- _mav_put_float(buf, 72, static_min_pressure);
- _mav_put_float(buf, 76, digital_min_pressure);
- _mav_put_float(buf, 80, ada_min_pressure);
- _mav_put_float(buf, 84, baro_max_altitutde);
- _mav_put_float(buf, 88, gps_max_altitude);
- _mav_put_float(buf, 92, drogue_dpl_max_acc);
- _mav_put_float(buf, 96, dpl_vane_max_pressure);
- _mav_put_float(buf, 100, main_dpl_altitude);
- _mav_put_float(buf, 104, main_dpl_zspeed);
- _mav_put_float(buf, 108, main_dpl_acc);
- _mav_put_float(buf, 112, cpu_load);
- _mav_put_uint32_t(buf, 116, free_heap);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LR_TM_LEN);
-#else
- mavlink_lr_tm_t packet;
- packet.liftoff_ts = liftoff_ts;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.drogue_dpl_ts = drogue_dpl_ts;
- packet.main_dpl_altitude_ts = main_dpl_altitude_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.static_min_pressure = static_min_pressure;
- packet.digital_min_pressure = digital_min_pressure;
- packet.ada_min_pressure = ada_min_pressure;
- packet.baro_max_altitutde = baro_max_altitutde;
- packet.gps_max_altitude = gps_max_altitude;
- packet.drogue_dpl_max_acc = drogue_dpl_max_acc;
- packet.dpl_vane_max_pressure = dpl_vane_max_pressure;
- packet.main_dpl_altitude = main_dpl_altitude;
- packet.main_dpl_zspeed = main_dpl_zspeed;
- packet.main_dpl_acc = main_dpl_acc;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LR_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LR_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LR_TM_MIN_LEN, MAVLINK_MSG_ID_LR_TM_LEN, MAVLINK_MSG_ID_LR_TM_CRC);
-}
-
-/**
- * @brief Pack a lr_tm 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 liftoff_ts [ms] System clock at liftoff
- * @param liftoff_max_acc_ts [ms] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param max_z_speed_ts [ms] System clock at ADA max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed - ADA
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [ms] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param static_min_pressure [Pa] Apogee pressure - Static ports
- * @param digital_min_pressure [Pa] Apogee pressure - Digital barometer
- * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered
- * @param baro_max_altitutde [m] Apogee altitude - Digital barometer
- * @param gps_max_altitude [m] Apogee altitude - GPS
- * @param drogue_dpl_ts [ms] System clock at drouge deployment
- * @param drogue_dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param dpl_vane_max_pressure [Pa] Max pressure in the deployment bay during drogue deployment
- * @param main_dpl_altitude_ts [ms] System clock at main chute deployment
- * @param main_dpl_altitude [m] Altittude at main deployment (m.s.l)
- * @param main_dpl_zspeed [m/s] Vertical speed at main deployment (sensor z axis)
- * @param main_dpl_acc [m/s2] Max measured vertical acceleration (sensor z axis) after main parachute deployment
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_lr_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t liftoff_ts,uint64_t liftoff_max_acc_ts,float liftoff_max_acc,uint64_t max_z_speed_ts,float max_z_speed,float max_airspeed_pitot,float max_speed_altitude,uint64_t apogee_ts,float apogee_lat,float apogee_lon,float static_min_pressure,float digital_min_pressure,float ada_min_pressure,float baro_max_altitutde,float gps_max_altitude,uint64_t drogue_dpl_ts,float drogue_dpl_max_acc,float dpl_vane_max_pressure,uint64_t main_dpl_altitude_ts,float main_dpl_altitude,float main_dpl_zspeed,float main_dpl_acc,float cpu_load,uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LR_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_ts);
- _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 16, max_z_speed_ts);
- _mav_put_uint64_t(buf, 24, apogee_ts);
- _mav_put_uint64_t(buf, 32, drogue_dpl_ts);
- _mav_put_uint64_t(buf, 40, main_dpl_altitude_ts);
- _mav_put_float(buf, 48, liftoff_max_acc);
- _mav_put_float(buf, 52, max_z_speed);
- _mav_put_float(buf, 56, max_airspeed_pitot);
- _mav_put_float(buf, 60, max_speed_altitude);
- _mav_put_float(buf, 64, apogee_lat);
- _mav_put_float(buf, 68, apogee_lon);
- _mav_put_float(buf, 72, static_min_pressure);
- _mav_put_float(buf, 76, digital_min_pressure);
- _mav_put_float(buf, 80, ada_min_pressure);
- _mav_put_float(buf, 84, baro_max_altitutde);
- _mav_put_float(buf, 88, gps_max_altitude);
- _mav_put_float(buf, 92, drogue_dpl_max_acc);
- _mav_put_float(buf, 96, dpl_vane_max_pressure);
- _mav_put_float(buf, 100, main_dpl_altitude);
- _mav_put_float(buf, 104, main_dpl_zspeed);
- _mav_put_float(buf, 108, main_dpl_acc);
- _mav_put_float(buf, 112, cpu_load);
- _mav_put_uint32_t(buf, 116, free_heap);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LR_TM_LEN);
-#else
- mavlink_lr_tm_t packet;
- packet.liftoff_ts = liftoff_ts;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.drogue_dpl_ts = drogue_dpl_ts;
- packet.main_dpl_altitude_ts = main_dpl_altitude_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.static_min_pressure = static_min_pressure;
- packet.digital_min_pressure = digital_min_pressure;
- packet.ada_min_pressure = ada_min_pressure;
- packet.baro_max_altitutde = baro_max_altitutde;
- packet.gps_max_altitude = gps_max_altitude;
- packet.drogue_dpl_max_acc = drogue_dpl_max_acc;
- packet.dpl_vane_max_pressure = dpl_vane_max_pressure;
- packet.main_dpl_altitude = main_dpl_altitude;
- packet.main_dpl_zspeed = main_dpl_zspeed;
- packet.main_dpl_acc = main_dpl_acc;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LR_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LR_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LR_TM_MIN_LEN, MAVLINK_MSG_ID_LR_TM_LEN, MAVLINK_MSG_ID_LR_TM_CRC);
-}
-
-/**
- * @brief Encode a lr_tm 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 lr_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_lr_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_lr_tm_t* lr_tm)
-{
- return mavlink_msg_lr_tm_pack(system_id, component_id, msg, lr_tm->liftoff_ts, lr_tm->liftoff_max_acc_ts, lr_tm->liftoff_max_acc, lr_tm->max_z_speed_ts, lr_tm->max_z_speed, lr_tm->max_airspeed_pitot, lr_tm->max_speed_altitude, lr_tm->apogee_ts, lr_tm->apogee_lat, lr_tm->apogee_lon, lr_tm->static_min_pressure, lr_tm->digital_min_pressure, lr_tm->ada_min_pressure, lr_tm->baro_max_altitutde, lr_tm->gps_max_altitude, lr_tm->drogue_dpl_ts, lr_tm->drogue_dpl_max_acc, lr_tm->dpl_vane_max_pressure, lr_tm->main_dpl_altitude_ts, lr_tm->main_dpl_altitude, lr_tm->main_dpl_zspeed, lr_tm->main_dpl_acc, lr_tm->cpu_load, lr_tm->free_heap);
-}
-
-/**
- * @brief Encode a lr_tm 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 lr_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_lr_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_lr_tm_t* lr_tm)
-{
- return mavlink_msg_lr_tm_pack_chan(system_id, component_id, chan, msg, lr_tm->liftoff_ts, lr_tm->liftoff_max_acc_ts, lr_tm->liftoff_max_acc, lr_tm->max_z_speed_ts, lr_tm->max_z_speed, lr_tm->max_airspeed_pitot, lr_tm->max_speed_altitude, lr_tm->apogee_ts, lr_tm->apogee_lat, lr_tm->apogee_lon, lr_tm->static_min_pressure, lr_tm->digital_min_pressure, lr_tm->ada_min_pressure, lr_tm->baro_max_altitutde, lr_tm->gps_max_altitude, lr_tm->drogue_dpl_ts, lr_tm->drogue_dpl_max_acc, lr_tm->dpl_vane_max_pressure, lr_tm->main_dpl_altitude_ts, lr_tm->main_dpl_altitude, lr_tm->main_dpl_zspeed, lr_tm->main_dpl_acc, lr_tm->cpu_load, lr_tm->free_heap);
-}
-
-/**
- * @brief Send a lr_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param liftoff_ts [ms] System clock at liftoff
- * @param liftoff_max_acc_ts [ms] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param max_z_speed_ts [ms] System clock at ADA max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed - ADA
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [ms] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param static_min_pressure [Pa] Apogee pressure - Static ports
- * @param digital_min_pressure [Pa] Apogee pressure - Digital barometer
- * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered
- * @param baro_max_altitutde [m] Apogee altitude - Digital barometer
- * @param gps_max_altitude [m] Apogee altitude - GPS
- * @param drogue_dpl_ts [ms] System clock at drouge deployment
- * @param drogue_dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param dpl_vane_max_pressure [Pa] Max pressure in the deployment bay during drogue deployment
- * @param main_dpl_altitude_ts [ms] System clock at main chute deployment
- * @param main_dpl_altitude [m] Altittude at main deployment (m.s.l)
- * @param main_dpl_zspeed [m/s] Vertical speed at main deployment (sensor z axis)
- * @param main_dpl_acc [m/s2] Max measured vertical acceleration (sensor z axis) after main parachute deployment
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_lr_tm_send(mavlink_channel_t chan, uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float static_min_pressure, float digital_min_pressure, float ada_min_pressure, float baro_max_altitutde, float gps_max_altitude, uint64_t drogue_dpl_ts, float drogue_dpl_max_acc, float dpl_vane_max_pressure, uint64_t main_dpl_altitude_ts, float main_dpl_altitude, float main_dpl_zspeed, float main_dpl_acc, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LR_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_ts);
- _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 16, max_z_speed_ts);
- _mav_put_uint64_t(buf, 24, apogee_ts);
- _mav_put_uint64_t(buf, 32, drogue_dpl_ts);
- _mav_put_uint64_t(buf, 40, main_dpl_altitude_ts);
- _mav_put_float(buf, 48, liftoff_max_acc);
- _mav_put_float(buf, 52, max_z_speed);
- _mav_put_float(buf, 56, max_airspeed_pitot);
- _mav_put_float(buf, 60, max_speed_altitude);
- _mav_put_float(buf, 64, apogee_lat);
- _mav_put_float(buf, 68, apogee_lon);
- _mav_put_float(buf, 72, static_min_pressure);
- _mav_put_float(buf, 76, digital_min_pressure);
- _mav_put_float(buf, 80, ada_min_pressure);
- _mav_put_float(buf, 84, baro_max_altitutde);
- _mav_put_float(buf, 88, gps_max_altitude);
- _mav_put_float(buf, 92, drogue_dpl_max_acc);
- _mav_put_float(buf, 96, dpl_vane_max_pressure);
- _mav_put_float(buf, 100, main_dpl_altitude);
- _mav_put_float(buf, 104, main_dpl_zspeed);
- _mav_put_float(buf, 108, main_dpl_acc);
- _mav_put_float(buf, 112, cpu_load);
- _mav_put_uint32_t(buf, 116, free_heap);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LR_TM, buf, MAVLINK_MSG_ID_LR_TM_MIN_LEN, MAVLINK_MSG_ID_LR_TM_LEN, MAVLINK_MSG_ID_LR_TM_CRC);
-#else
- mavlink_lr_tm_t packet;
- packet.liftoff_ts = liftoff_ts;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.drogue_dpl_ts = drogue_dpl_ts;
- packet.main_dpl_altitude_ts = main_dpl_altitude_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.static_min_pressure = static_min_pressure;
- packet.digital_min_pressure = digital_min_pressure;
- packet.ada_min_pressure = ada_min_pressure;
- packet.baro_max_altitutde = baro_max_altitutde;
- packet.gps_max_altitude = gps_max_altitude;
- packet.drogue_dpl_max_acc = drogue_dpl_max_acc;
- packet.dpl_vane_max_pressure = dpl_vane_max_pressure;
- packet.main_dpl_altitude = main_dpl_altitude;
- packet.main_dpl_zspeed = main_dpl_zspeed;
- packet.main_dpl_acc = main_dpl_acc;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LR_TM, (const char *)&packet, MAVLINK_MSG_ID_LR_TM_MIN_LEN, MAVLINK_MSG_ID_LR_TM_LEN, MAVLINK_MSG_ID_LR_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a lr_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_lr_tm_send_struct(mavlink_channel_t chan, const mavlink_lr_tm_t* lr_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_lr_tm_send(chan, lr_tm->liftoff_ts, lr_tm->liftoff_max_acc_ts, lr_tm->liftoff_max_acc, lr_tm->max_z_speed_ts, lr_tm->max_z_speed, lr_tm->max_airspeed_pitot, lr_tm->max_speed_altitude, lr_tm->apogee_ts, lr_tm->apogee_lat, lr_tm->apogee_lon, lr_tm->static_min_pressure, lr_tm->digital_min_pressure, lr_tm->ada_min_pressure, lr_tm->baro_max_altitutde, lr_tm->gps_max_altitude, lr_tm->drogue_dpl_ts, lr_tm->drogue_dpl_max_acc, lr_tm->dpl_vane_max_pressure, lr_tm->main_dpl_altitude_ts, lr_tm->main_dpl_altitude, lr_tm->main_dpl_zspeed, lr_tm->main_dpl_acc, lr_tm->cpu_load, lr_tm->free_heap);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LR_TM, (const char *)lr_tm, MAVLINK_MSG_ID_LR_TM_MIN_LEN, MAVLINK_MSG_ID_LR_TM_LEN, MAVLINK_MSG_ID_LR_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_LR_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_lr_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float static_min_pressure, float digital_min_pressure, float ada_min_pressure, float baro_max_altitutde, float gps_max_altitude, uint64_t drogue_dpl_ts, float drogue_dpl_max_acc, float dpl_vane_max_pressure, uint64_t main_dpl_altitude_ts, float main_dpl_altitude, float main_dpl_zspeed, float main_dpl_acc, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, liftoff_ts);
- _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 16, max_z_speed_ts);
- _mav_put_uint64_t(buf, 24, apogee_ts);
- _mav_put_uint64_t(buf, 32, drogue_dpl_ts);
- _mav_put_uint64_t(buf, 40, main_dpl_altitude_ts);
- _mav_put_float(buf, 48, liftoff_max_acc);
- _mav_put_float(buf, 52, max_z_speed);
- _mav_put_float(buf, 56, max_airspeed_pitot);
- _mav_put_float(buf, 60, max_speed_altitude);
- _mav_put_float(buf, 64, apogee_lat);
- _mav_put_float(buf, 68, apogee_lon);
- _mav_put_float(buf, 72, static_min_pressure);
- _mav_put_float(buf, 76, digital_min_pressure);
- _mav_put_float(buf, 80, ada_min_pressure);
- _mav_put_float(buf, 84, baro_max_altitutde);
- _mav_put_float(buf, 88, gps_max_altitude);
- _mav_put_float(buf, 92, drogue_dpl_max_acc);
- _mav_put_float(buf, 96, dpl_vane_max_pressure);
- _mav_put_float(buf, 100, main_dpl_altitude);
- _mav_put_float(buf, 104, main_dpl_zspeed);
- _mav_put_float(buf, 108, main_dpl_acc);
- _mav_put_float(buf, 112, cpu_load);
- _mav_put_uint32_t(buf, 116, free_heap);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LR_TM, buf, MAVLINK_MSG_ID_LR_TM_MIN_LEN, MAVLINK_MSG_ID_LR_TM_LEN, MAVLINK_MSG_ID_LR_TM_CRC);
-#else
- mavlink_lr_tm_t *packet = (mavlink_lr_tm_t *)msgbuf;
- packet->liftoff_ts = liftoff_ts;
- packet->liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet->max_z_speed_ts = max_z_speed_ts;
- packet->apogee_ts = apogee_ts;
- packet->drogue_dpl_ts = drogue_dpl_ts;
- packet->main_dpl_altitude_ts = main_dpl_altitude_ts;
- packet->liftoff_max_acc = liftoff_max_acc;
- packet->max_z_speed = max_z_speed;
- packet->max_airspeed_pitot = max_airspeed_pitot;
- packet->max_speed_altitude = max_speed_altitude;
- packet->apogee_lat = apogee_lat;
- packet->apogee_lon = apogee_lon;
- packet->static_min_pressure = static_min_pressure;
- packet->digital_min_pressure = digital_min_pressure;
- packet->ada_min_pressure = ada_min_pressure;
- packet->baro_max_altitutde = baro_max_altitutde;
- packet->gps_max_altitude = gps_max_altitude;
- packet->drogue_dpl_max_acc = drogue_dpl_max_acc;
- packet->dpl_vane_max_pressure = dpl_vane_max_pressure;
- packet->main_dpl_altitude = main_dpl_altitude;
- packet->main_dpl_zspeed = main_dpl_zspeed;
- packet->main_dpl_acc = main_dpl_acc;
- packet->cpu_load = cpu_load;
- packet->free_heap = free_heap;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LR_TM, (const char *)packet, MAVLINK_MSG_ID_LR_TM_MIN_LEN, MAVLINK_MSG_ID_LR_TM_LEN, MAVLINK_MSG_ID_LR_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE LR_TM UNPACKING
-
-
-/**
- * @brief Get field liftoff_ts from lr_tm message
- *
- * @return [ms] System clock at liftoff
- */
-static inline uint64_t mavlink_msg_lr_tm_get_liftoff_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field liftoff_max_acc_ts from lr_tm message
- *
- * @return [ms] System clock at the maximum liftoff acceleration
- */
-static inline uint64_t mavlink_msg_lr_tm_get_liftoff_max_acc_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 8);
-}
-
-/**
- * @brief Get field liftoff_max_acc from lr_tm message
- *
- * @return [m/s2] Maximum liftoff acceleration
- */
-static inline float mavlink_msg_lr_tm_get_liftoff_max_acc(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field max_z_speed_ts from lr_tm message
- *
- * @return [ms] System clock at ADA max vertical speed
- */
-static inline uint64_t mavlink_msg_lr_tm_get_max_z_speed_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 16);
-}
-
-/**
- * @brief Get field max_z_speed from lr_tm message
- *
- * @return [m/s] Max measured vertical speed - ADA
- */
-static inline float mavlink_msg_lr_tm_get_max_z_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field max_airspeed_pitot from lr_tm message
- *
- * @return [m/s] Max speed read by the pitot tube
- */
-static inline float mavlink_msg_lr_tm_get_max_airspeed_pitot(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field max_speed_altitude from lr_tm message
- *
- * @return [m] Altitude at max speed
- */
-static inline float mavlink_msg_lr_tm_get_max_speed_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field apogee_ts from lr_tm message
- *
- * @return [ms] System clock at apogee
- */
-static inline uint64_t mavlink_msg_lr_tm_get_apogee_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 24);
-}
-
-/**
- * @brief Get field apogee_lat from lr_tm message
- *
- * @return [deg] Apogee latitude
- */
-static inline float mavlink_msg_lr_tm_get_apogee_lat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field apogee_lon from lr_tm message
- *
- * @return [deg] Apogee longitude
- */
-static inline float mavlink_msg_lr_tm_get_apogee_lon(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field static_min_pressure from lr_tm message
- *
- * @return [Pa] Apogee pressure - Static ports
- */
-static inline float mavlink_msg_lr_tm_get_static_min_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 72);
-}
-
-/**
- * @brief Get field digital_min_pressure from lr_tm message
- *
- * @return [Pa] Apogee pressure - Digital barometer
- */
-static inline float mavlink_msg_lr_tm_get_digital_min_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 76);
-}
-
-/**
- * @brief Get field ada_min_pressure from lr_tm message
- *
- * @return [Pa] Apogee pressure - ADA filtered
- */
-static inline float mavlink_msg_lr_tm_get_ada_min_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 80);
-}
-
-/**
- * @brief Get field baro_max_altitutde from lr_tm message
- *
- * @return [m] Apogee altitude - Digital barometer
- */
-static inline float mavlink_msg_lr_tm_get_baro_max_altitutde(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 84);
-}
-
-/**
- * @brief Get field gps_max_altitude from lr_tm message
- *
- * @return [m] Apogee altitude - GPS
- */
-static inline float mavlink_msg_lr_tm_get_gps_max_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 88);
-}
-
-/**
- * @brief Get field drogue_dpl_ts from lr_tm message
- *
- * @return [ms] System clock at drouge deployment
- */
-static inline uint64_t mavlink_msg_lr_tm_get_drogue_dpl_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 32);
-}
-
-/**
- * @brief Get field drogue_dpl_max_acc from lr_tm message
- *
- * @return [m/s2] Max acceleration during drouge deployment
- */
-static inline float mavlink_msg_lr_tm_get_drogue_dpl_max_acc(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 92);
-}
-
-/**
- * @brief Get field dpl_vane_max_pressure from lr_tm message
- *
- * @return [Pa] Max pressure in the deployment bay during drogue deployment
- */
-static inline float mavlink_msg_lr_tm_get_dpl_vane_max_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 96);
-}
-
-/**
- * @brief Get field main_dpl_altitude_ts from lr_tm message
- *
- * @return [ms] System clock at main chute deployment
- */
-static inline uint64_t mavlink_msg_lr_tm_get_main_dpl_altitude_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 40);
-}
-
-/**
- * @brief Get field main_dpl_altitude from lr_tm message
- *
- * @return [m] Altittude at main deployment (m.s.l)
- */
-static inline float mavlink_msg_lr_tm_get_main_dpl_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 100);
-}
-
-/**
- * @brief Get field main_dpl_zspeed from lr_tm message
- *
- * @return [m/s] Vertical speed at main deployment (sensor z axis)
- */
-static inline float mavlink_msg_lr_tm_get_main_dpl_zspeed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 104);
-}
-
-/**
- * @brief Get field main_dpl_acc from lr_tm message
- *
- * @return [m/s2] Max measured vertical acceleration (sensor z axis) after main parachute deployment
- */
-static inline float mavlink_msg_lr_tm_get_main_dpl_acc(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 108);
-}
-
-/**
- * @brief Get field cpu_load from lr_tm message
- *
- * @return CPU load in percentage
- */
-static inline float mavlink_msg_lr_tm_get_cpu_load(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 112);
-}
-
-/**
- * @brief Get field free_heap from lr_tm message
- *
- * @return Amount of available heap in memory
- */
-static inline uint32_t mavlink_msg_lr_tm_get_free_heap(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 116);
-}
-
-/**
- * @brief Decode a lr_tm message into a struct
- *
- * @param msg The message to decode
- * @param lr_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_lr_tm_decode(const mavlink_message_t* msg, mavlink_lr_tm_t* lr_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- lr_tm->liftoff_ts = mavlink_msg_lr_tm_get_liftoff_ts(msg);
- lr_tm->liftoff_max_acc_ts = mavlink_msg_lr_tm_get_liftoff_max_acc_ts(msg);
- lr_tm->max_z_speed_ts = mavlink_msg_lr_tm_get_max_z_speed_ts(msg);
- lr_tm->apogee_ts = mavlink_msg_lr_tm_get_apogee_ts(msg);
- lr_tm->drogue_dpl_ts = mavlink_msg_lr_tm_get_drogue_dpl_ts(msg);
- lr_tm->main_dpl_altitude_ts = mavlink_msg_lr_tm_get_main_dpl_altitude_ts(msg);
- lr_tm->liftoff_max_acc = mavlink_msg_lr_tm_get_liftoff_max_acc(msg);
- lr_tm->max_z_speed = mavlink_msg_lr_tm_get_max_z_speed(msg);
- lr_tm->max_airspeed_pitot = mavlink_msg_lr_tm_get_max_airspeed_pitot(msg);
- lr_tm->max_speed_altitude = mavlink_msg_lr_tm_get_max_speed_altitude(msg);
- lr_tm->apogee_lat = mavlink_msg_lr_tm_get_apogee_lat(msg);
- lr_tm->apogee_lon = mavlink_msg_lr_tm_get_apogee_lon(msg);
- lr_tm->static_min_pressure = mavlink_msg_lr_tm_get_static_min_pressure(msg);
- lr_tm->digital_min_pressure = mavlink_msg_lr_tm_get_digital_min_pressure(msg);
- lr_tm->ada_min_pressure = mavlink_msg_lr_tm_get_ada_min_pressure(msg);
- lr_tm->baro_max_altitutde = mavlink_msg_lr_tm_get_baro_max_altitutde(msg);
- lr_tm->gps_max_altitude = mavlink_msg_lr_tm_get_gps_max_altitude(msg);
- lr_tm->drogue_dpl_max_acc = mavlink_msg_lr_tm_get_drogue_dpl_max_acc(msg);
- lr_tm->dpl_vane_max_pressure = mavlink_msg_lr_tm_get_dpl_vane_max_pressure(msg);
- lr_tm->main_dpl_altitude = mavlink_msg_lr_tm_get_main_dpl_altitude(msg);
- lr_tm->main_dpl_zspeed = mavlink_msg_lr_tm_get_main_dpl_zspeed(msg);
- lr_tm->main_dpl_acc = mavlink_msg_lr_tm_get_main_dpl_acc(msg);
- lr_tm->cpu_load = mavlink_msg_lr_tm_get_cpu_load(msg);
- lr_tm->free_heap = mavlink_msg_lr_tm_get_free_heap(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_LR_TM_LEN? msg->len : MAVLINK_MSG_ID_LR_TM_LEN;
- memset(lr_tm, 0, MAVLINK_MSG_ID_LR_TM_LEN);
- memcpy(lr_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_ms5803_tm.h b/mavlink_lib/lynx/mavlink_msg_ms5803_tm.h
deleted file mode 100644
index 91c1143bab23b43891a416b37f518c0e57bef319..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_ms5803_tm.h
+++ /dev/null
@@ -1,263 +0,0 @@
-#pragma once
-// MESSAGE MS5803_TM PACKING
-
-#define MAVLINK_MSG_ID_MS5803_TM 172
-
-MAVPACKED(
-typedef struct __mavlink_ms5803_tm_t {
- uint64_t timestamp; /*< [ms] When was this logged*/
- float pressure; /*< [Pa] Pressure of the digital barometer*/
- float temperature; /*< [deg] Temperature of the digital barometer*/
-}) mavlink_ms5803_tm_t;
-
-#define MAVLINK_MSG_ID_MS5803_TM_LEN 16
-#define MAVLINK_MSG_ID_MS5803_TM_MIN_LEN 16
-#define MAVLINK_MSG_ID_172_LEN 16
-#define MAVLINK_MSG_ID_172_MIN_LEN 16
-
-#define MAVLINK_MSG_ID_MS5803_TM_CRC 56
-#define MAVLINK_MSG_ID_172_CRC 56
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_MS5803_TM { \
- 172, \
- "MS5803_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ms5803_tm_t, timestamp) }, \
- { "pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ms5803_tm_t, pressure) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ms5803_tm_t, temperature) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_MS5803_TM { \
- "MS5803_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ms5803_tm_t, timestamp) }, \
- { "pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ms5803_tm_t, pressure) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ms5803_tm_t, temperature) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ms5803_tm 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] When was this logged
- * @param pressure [Pa] Pressure of the digital barometer
- * @param temperature [deg] Temperature of the digital barometer
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ms5803_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, float pressure, float temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MS5803_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure);
- _mav_put_float(buf, 12, temperature);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MS5803_TM_LEN);
-#else
- mavlink_ms5803_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure = pressure;
- packet.temperature = temperature;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MS5803_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_MS5803_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MS5803_TM_MIN_LEN, MAVLINK_MSG_ID_MS5803_TM_LEN, MAVLINK_MSG_ID_MS5803_TM_CRC);
-}
-
-/**
- * @brief Pack a ms5803_tm 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] When was this logged
- * @param pressure [Pa] Pressure of the digital barometer
- * @param temperature [deg] Temperature of the digital barometer
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ms5803_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,float pressure,float temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MS5803_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure);
- _mav_put_float(buf, 12, temperature);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MS5803_TM_LEN);
-#else
- mavlink_ms5803_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure = pressure;
- packet.temperature = temperature;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MS5803_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_MS5803_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MS5803_TM_MIN_LEN, MAVLINK_MSG_ID_MS5803_TM_LEN, MAVLINK_MSG_ID_MS5803_TM_CRC);
-}
-
-/**
- * @brief Encode a ms5803_tm 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 ms5803_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ms5803_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ms5803_tm_t* ms5803_tm)
-{
- return mavlink_msg_ms5803_tm_pack(system_id, component_id, msg, ms5803_tm->timestamp, ms5803_tm->pressure, ms5803_tm->temperature);
-}
-
-/**
- * @brief Encode a ms5803_tm 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 ms5803_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ms5803_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ms5803_tm_t* ms5803_tm)
-{
- return mavlink_msg_ms5803_tm_pack_chan(system_id, component_id, chan, msg, ms5803_tm->timestamp, ms5803_tm->pressure, ms5803_tm->temperature);
-}
-
-/**
- * @brief Send a ms5803_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [ms] When was this logged
- * @param pressure [Pa] Pressure of the digital barometer
- * @param temperature [deg] Temperature of the digital barometer
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ms5803_tm_send(mavlink_channel_t chan, uint64_t timestamp, float pressure, float temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MS5803_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure);
- _mav_put_float(buf, 12, temperature);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MS5803_TM, buf, MAVLINK_MSG_ID_MS5803_TM_MIN_LEN, MAVLINK_MSG_ID_MS5803_TM_LEN, MAVLINK_MSG_ID_MS5803_TM_CRC);
-#else
- mavlink_ms5803_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure = pressure;
- packet.temperature = temperature;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MS5803_TM, (const char *)&packet, MAVLINK_MSG_ID_MS5803_TM_MIN_LEN, MAVLINK_MSG_ID_MS5803_TM_LEN, MAVLINK_MSG_ID_MS5803_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a ms5803_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ms5803_tm_send_struct(mavlink_channel_t chan, const mavlink_ms5803_tm_t* ms5803_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ms5803_tm_send(chan, ms5803_tm->timestamp, ms5803_tm->pressure, ms5803_tm->temperature);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MS5803_TM, (const char *)ms5803_tm, MAVLINK_MSG_ID_MS5803_TM_MIN_LEN, MAVLINK_MSG_ID_MS5803_TM_LEN, MAVLINK_MSG_ID_MS5803_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_MS5803_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_ms5803_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float pressure, float temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure);
- _mav_put_float(buf, 12, temperature);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MS5803_TM, buf, MAVLINK_MSG_ID_MS5803_TM_MIN_LEN, MAVLINK_MSG_ID_MS5803_TM_LEN, MAVLINK_MSG_ID_MS5803_TM_CRC);
-#else
- mavlink_ms5803_tm_t *packet = (mavlink_ms5803_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->pressure = pressure;
- packet->temperature = temperature;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MS5803_TM, (const char *)packet, MAVLINK_MSG_ID_MS5803_TM_MIN_LEN, MAVLINK_MSG_ID_MS5803_TM_LEN, MAVLINK_MSG_ID_MS5803_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE MS5803_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from ms5803_tm message
- *
- * @return [ms] When was this logged
- */
-static inline uint64_t mavlink_msg_ms5803_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field pressure from ms5803_tm message
- *
- * @return [Pa] Pressure of the digital barometer
- */
-static inline float mavlink_msg_ms5803_tm_get_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field temperature from ms5803_tm message
- *
- * @return [deg] Temperature of the digital barometer
- */
-static inline float mavlink_msg_ms5803_tm_get_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Decode a ms5803_tm message into a struct
- *
- * @param msg The message to decode
- * @param ms5803_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ms5803_tm_decode(const mavlink_message_t* msg, mavlink_ms5803_tm_t* ms5803_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ms5803_tm->timestamp = mavlink_msg_ms5803_tm_get_timestamp(msg);
- ms5803_tm->pressure = mavlink_msg_ms5803_tm_get_pressure(msg);
- ms5803_tm->temperature = mavlink_msg_ms5803_tm_get_temperature(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_MS5803_TM_LEN? msg->len : MAVLINK_MSG_ID_MS5803_TM_LEN;
- memset(ms5803_tm, 0, MAVLINK_MSG_ID_MS5803_TM_LEN);
- memcpy(ms5803_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_nack_tm.h b/mavlink_lib/lynx/mavlink_msg_nack_tm.h
deleted file mode 100644
index 55451259046d4d2b5458aae948a2070d2a7e05a0..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_nack_tm.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE NACK_TM PACKING
-
-#define MAVLINK_MSG_ID_NACK_TM 131
-
-MAVPACKED(
-typedef struct __mavlink_nack_tm_t {
- uint8_t recv_msgid; /*< Message id of the received message.*/
- uint8_t seq_ack; /*< Sequence number of the received message.*/
-}) mavlink_nack_tm_t;
-
-#define MAVLINK_MSG_ID_NACK_TM_LEN 2
-#define MAVLINK_MSG_ID_NACK_TM_MIN_LEN 2
-#define MAVLINK_MSG_ID_131_LEN 2
-#define MAVLINK_MSG_ID_131_MIN_LEN 2
-
-#define MAVLINK_MSG_ID_NACK_TM_CRC 146
-#define MAVLINK_MSG_ID_131_CRC 146
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_NACK_TM { \
- 131, \
- "NACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_nack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_nack_tm_t, seq_ack) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_NACK_TM { \
- "NACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_nack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_nack_tm_t, seq_ack) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a nack_tm 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 recv_msgid Message id of the received message.
- * @param seq_ack Sequence number of the received message.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_nack_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NACK_TM_LEN);
-#else
- mavlink_nack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NACK_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-}
-
-/**
- * @brief Pack a nack_tm 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 recv_msgid Message id of the received message.
- * @param seq_ack Sequence number of the received message.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_nack_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t recv_msgid,uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NACK_TM_LEN);
-#else
- mavlink_nack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NACK_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-}
-
-/**
- * @brief Encode a nack_tm 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 nack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_nack_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nack_tm_t* nack_tm)
-{
- return mavlink_msg_nack_tm_pack(system_id, component_id, msg, nack_tm->recv_msgid, nack_tm->seq_ack);
-}
-
-/**
- * @brief Encode a nack_tm 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 nack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_nack_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nack_tm_t* nack_tm)
-{
- return mavlink_msg_nack_tm_pack_chan(system_id, component_id, chan, msg, nack_tm->recv_msgid, nack_tm->seq_ack);
-}
-
-/**
- * @brief Send a nack_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param recv_msgid Message id of the received message.
- * @param seq_ack Sequence number of the received message.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_nack_tm_send(mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, buf, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#else
- mavlink_nack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, (const char *)&packet, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a nack_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_nack_tm_send_struct(mavlink_channel_t chan, const mavlink_nack_tm_t* nack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_nack_tm_send(chan, nack_tm->recv_msgid, nack_tm->seq_ack);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, (const char *)nack_tm, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_NACK_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_nack_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, buf, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#else
- mavlink_nack_tm_t *packet = (mavlink_nack_tm_t *)msgbuf;
- packet->recv_msgid = recv_msgid;
- packet->seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, (const char *)packet, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE NACK_TM UNPACKING
-
-
-/**
- * @brief Get field recv_msgid from nack_tm message
- *
- * @return Message id of the received message.
- */
-static inline uint8_t mavlink_msg_nack_tm_get_recv_msgid(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field seq_ack from nack_tm message
- *
- * @return Sequence number of the received message.
- */
-static inline uint8_t mavlink_msg_nack_tm_get_seq_ack(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Decode a nack_tm message into a struct
- *
- * @param msg The message to decode
- * @param nack_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_nack_tm_decode(const mavlink_message_t* msg, mavlink_nack_tm_t* nack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- nack_tm->recv_msgid = mavlink_msg_nack_tm_get_recv_msgid(msg);
- nack_tm->seq_ack = mavlink_msg_nack_tm_get_seq_ack(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_NACK_TM_LEN? msg->len : MAVLINK_MSG_ID_NACK_TM_LEN;
- memset(nack_tm, 0, MAVLINK_MSG_ID_NACK_TM_LEN);
- memcpy(nack_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_nas_tm.h b/mavlink_lib/lynx/mavlink_msg_nas_tm.h
deleted file mode 100644
index 7015c1d0dcdaf1f8385f79b5b13e3646883ce194..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_nas_tm.h
+++ /dev/null
@@ -1,963 +0,0 @@
-#pragma once
-// MESSAGE NAS_TM PACKING
-
-#define MAVLINK_MSG_ID_NAS_TM 169
-
-MAVPACKED(
-typedef struct __mavlink_nas_tm_t {
- uint64_t timestamp; /*< [ms] When was this logged*/
- float x0; /*< [m] Kalman state variable 0 (position x)*/
- float x1; /*< [m] Kalman state variable 1 (position y)*/
- float x2; /*< [m] >Kalman state variable 2 (position z)*/
- float x3; /*< [m/s] >Kalman state variable 3 (velocity x)*/
- float x4; /*< [m/s] >Kalman state variable 4 (velocity y)*/
- float x5; /*< [m/s] >Kalman state variable 5 (velocity z)*/
- float x6; /*< Kalman state variable 6 (q0)*/
- float x7; /*< Kalman state variable 7 (q1)*/
- float x8; /*< Kalman state variable 8 (q2)*/
- float x9; /*< Kalman state variable 9 (q3)*/
- float x10; /*< Kalman state variable 10 (bias)*/
- float x11; /*< Kalman state variable 11 (bias)*/
- float x12; /*< Kalman state variable 12 (bias)*/
- float ref_pressure; /*< [Pa] Calibration pressure*/
- float ref_temperature; /*< [degC] Calibration temperature*/
- float ref_latitude; /*< [deg] Calibration latitude*/
- float ref_longitude; /*< [deg] Calibration longitude*/
- float ref_accel_x; /*< [m/s2] Calibration acceleration on x axis*/
- float ref_accel_y; /*< [m/s2] Calibration acceleration on y axis*/
- float ref_accel_z; /*< [m/s2] Calibration acceleration on z axis*/
- float ref_mag_x; /*< [uT] Calibration compass on x axis*/
- float ref_mag_y; /*< [uT] Calibration compass on y axis*/
- float ref_mag_z; /*< [uT] Calibration compass on z axis*/
- float triad_roll; /*< Orientation on roll estimated by TRIAD initialization*/
- float triad_pitch; /*< Orientation on pitch estimated by TRIAD initialization*/
- float triad_yaw; /*< Orientation on yaw estimated by TRIAD initialization*/
- float roll; /*< [deg] Orientation on roll*/
- float pitch; /*< [deg] Orientation on pitch*/
- float yaw; /*< [deg] Orientation on yaw*/
- uint8_t state; /*< NAS current state*/
-}) mavlink_nas_tm_t;
-
-#define MAVLINK_MSG_ID_NAS_TM_LEN 125
-#define MAVLINK_MSG_ID_NAS_TM_MIN_LEN 125
-#define MAVLINK_MSG_ID_169_LEN 125
-#define MAVLINK_MSG_ID_169_MIN_LEN 125
-
-#define MAVLINK_MSG_ID_NAS_TM_CRC 14
-#define MAVLINK_MSG_ID_169_CRC 14
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_NAS_TM { \
- 169, \
- "NAS_TM", \
- 31, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_nas_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 124, offsetof(mavlink_nas_tm_t, state) }, \
- { "x0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nas_tm_t, x0) }, \
- { "x1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nas_tm_t, x1) }, \
- { "x2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nas_tm_t, x2) }, \
- { "x3", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_nas_tm_t, x3) }, \
- { "x4", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_nas_tm_t, x4) }, \
- { "x5", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_nas_tm_t, x5) }, \
- { "x6", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_nas_tm_t, x6) }, \
- { "x7", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_nas_tm_t, x7) }, \
- { "x8", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_nas_tm_t, x8) }, \
- { "x9", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_nas_tm_t, x9) }, \
- { "x10", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_nas_tm_t, x10) }, \
- { "x11", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_nas_tm_t, x11) }, \
- { "x12", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_nas_tm_t, x12) }, \
- { "ref_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_nas_tm_t, ref_pressure) }, \
- { "ref_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_nas_tm_t, ref_temperature) }, \
- { "ref_latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_nas_tm_t, ref_latitude) }, \
- { "ref_longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_nas_tm_t, ref_longitude) }, \
- { "ref_accel_x", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_nas_tm_t, ref_accel_x) }, \
- { "ref_accel_y", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_nas_tm_t, ref_accel_y) }, \
- { "ref_accel_z", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_nas_tm_t, ref_accel_z) }, \
- { "ref_mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_nas_tm_t, ref_mag_x) }, \
- { "ref_mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_nas_tm_t, ref_mag_y) }, \
- { "ref_mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_nas_tm_t, ref_mag_z) }, \
- { "triad_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_nas_tm_t, triad_roll) }, \
- { "triad_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_nas_tm_t, triad_pitch) }, \
- { "triad_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_nas_tm_t, triad_yaw) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_nas_tm_t, roll) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_nas_tm_t, pitch) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_nas_tm_t, yaw) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_NAS_TM { \
- "NAS_TM", \
- 31, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_nas_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 124, offsetof(mavlink_nas_tm_t, state) }, \
- { "x0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nas_tm_t, x0) }, \
- { "x1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nas_tm_t, x1) }, \
- { "x2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nas_tm_t, x2) }, \
- { "x3", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_nas_tm_t, x3) }, \
- { "x4", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_nas_tm_t, x4) }, \
- { "x5", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_nas_tm_t, x5) }, \
- { "x6", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_nas_tm_t, x6) }, \
- { "x7", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_nas_tm_t, x7) }, \
- { "x8", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_nas_tm_t, x8) }, \
- { "x9", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_nas_tm_t, x9) }, \
- { "x10", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_nas_tm_t, x10) }, \
- { "x11", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_nas_tm_t, x11) }, \
- { "x12", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_nas_tm_t, x12) }, \
- { "ref_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_nas_tm_t, ref_pressure) }, \
- { "ref_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_nas_tm_t, ref_temperature) }, \
- { "ref_latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_nas_tm_t, ref_latitude) }, \
- { "ref_longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_nas_tm_t, ref_longitude) }, \
- { "ref_accel_x", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_nas_tm_t, ref_accel_x) }, \
- { "ref_accel_y", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_nas_tm_t, ref_accel_y) }, \
- { "ref_accel_z", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_nas_tm_t, ref_accel_z) }, \
- { "ref_mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_nas_tm_t, ref_mag_x) }, \
- { "ref_mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_nas_tm_t, ref_mag_y) }, \
- { "ref_mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_nas_tm_t, ref_mag_z) }, \
- { "triad_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_nas_tm_t, triad_roll) }, \
- { "triad_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_nas_tm_t, triad_pitch) }, \
- { "triad_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_nas_tm_t, triad_yaw) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_nas_tm_t, roll) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_nas_tm_t, pitch) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_nas_tm_t, yaw) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a nas_tm 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] When was this logged
- * @param state NAS current state
- * @param x0 [m] Kalman state variable 0 (position x)
- * @param x1 [m] Kalman state variable 1 (position y)
- * @param x2 [m] >Kalman state variable 2 (position z)
- * @param x3 [m/s] >Kalman state variable 3 (velocity x)
- * @param x4 [m/s] >Kalman state variable 4 (velocity y)
- * @param x5 [m/s] >Kalman state variable 5 (velocity z)
- * @param x6 Kalman state variable 6 (q0)
- * @param x7 Kalman state variable 7 (q1)
- * @param x8 Kalman state variable 8 (q2)
- * @param x9 Kalman state variable 9 (q3)
- * @param x10 Kalman state variable 10 (bias)
- * @param x11 Kalman state variable 11 (bias)
- * @param x12 Kalman state variable 12 (bias)
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_temperature [degC] Calibration temperature
- * @param ref_latitude [deg] Calibration latitude
- * @param ref_longitude [deg] Calibration longitude
- * @param ref_accel_x [m/s2] Calibration acceleration on x axis
- * @param ref_accel_y [m/s2] Calibration acceleration on y axis
- * @param ref_accel_z [m/s2] Calibration acceleration on z axis
- * @param ref_mag_x [uT] Calibration compass on x axis
- * @param ref_mag_y [uT] Calibration compass on y axis
- * @param ref_mag_z [uT] Calibration compass on z axis
- * @param triad_roll Orientation on roll estimated by TRIAD initialization
- * @param triad_pitch Orientation on pitch estimated by TRIAD initialization
- * @param triad_yaw Orientation on yaw estimated by TRIAD initialization
- * @param roll [deg] Orientation on roll
- * @param pitch [deg] Orientation on pitch
- * @param yaw [deg] Orientation on yaw
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_nas_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t state, float x0, float x1, float x2, float x3, float x4, float x5, float x6, float x7, float x8, float x9, float x10, float x11, float x12, float ref_pressure, float ref_temperature, float ref_latitude, float ref_longitude, float ref_accel_x, float ref_accel_y, float ref_accel_z, float ref_mag_x, float ref_mag_y, float ref_mag_z, float triad_roll, float triad_pitch, float triad_yaw, float roll, float pitch, float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NAS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, x0);
- _mav_put_float(buf, 12, x1);
- _mav_put_float(buf, 16, x2);
- _mav_put_float(buf, 20, x3);
- _mav_put_float(buf, 24, x4);
- _mav_put_float(buf, 28, x5);
- _mav_put_float(buf, 32, x6);
- _mav_put_float(buf, 36, x7);
- _mav_put_float(buf, 40, x8);
- _mav_put_float(buf, 44, x9);
- _mav_put_float(buf, 48, x10);
- _mav_put_float(buf, 52, x11);
- _mav_put_float(buf, 56, x12);
- _mav_put_float(buf, 60, ref_pressure);
- _mav_put_float(buf, 64, ref_temperature);
- _mav_put_float(buf, 68, ref_latitude);
- _mav_put_float(buf, 72, ref_longitude);
- _mav_put_float(buf, 76, ref_accel_x);
- _mav_put_float(buf, 80, ref_accel_y);
- _mav_put_float(buf, 84, ref_accel_z);
- _mav_put_float(buf, 88, ref_mag_x);
- _mav_put_float(buf, 92, ref_mag_y);
- _mav_put_float(buf, 96, ref_mag_z);
- _mav_put_float(buf, 100, triad_roll);
- _mav_put_float(buf, 104, triad_pitch);
- _mav_put_float(buf, 108, triad_yaw);
- _mav_put_float(buf, 112, roll);
- _mav_put_float(buf, 116, pitch);
- _mav_put_float(buf, 120, yaw);
- _mav_put_uint8_t(buf, 124, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAS_TM_LEN);
-#else
- mavlink_nas_tm_t packet;
- packet.timestamp = timestamp;
- packet.x0 = x0;
- packet.x1 = x1;
- packet.x2 = x2;
- packet.x3 = x3;
- packet.x4 = x4;
- packet.x5 = x5;
- packet.x6 = x6;
- packet.x7 = x7;
- packet.x8 = x8;
- packet.x9 = x9;
- packet.x10 = x10;
- packet.x11 = x11;
- packet.x12 = x12;
- packet.ref_pressure = ref_pressure;
- packet.ref_temperature = ref_temperature;
- packet.ref_latitude = ref_latitude;
- packet.ref_longitude = ref_longitude;
- packet.ref_accel_x = ref_accel_x;
- packet.ref_accel_y = ref_accel_y;
- packet.ref_accel_z = ref_accel_z;
- packet.ref_mag_x = ref_mag_x;
- packet.ref_mag_y = ref_mag_y;
- packet.ref_mag_z = ref_mag_z;
- packet.triad_roll = triad_roll;
- packet.triad_pitch = triad_pitch;
- packet.triad_yaw = triad_yaw;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NAS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-}
-
-/**
- * @brief Pack a nas_tm 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] When was this logged
- * @param state NAS current state
- * @param x0 [m] Kalman state variable 0 (position x)
- * @param x1 [m] Kalman state variable 1 (position y)
- * @param x2 [m] >Kalman state variable 2 (position z)
- * @param x3 [m/s] >Kalman state variable 3 (velocity x)
- * @param x4 [m/s] >Kalman state variable 4 (velocity y)
- * @param x5 [m/s] >Kalman state variable 5 (velocity z)
- * @param x6 Kalman state variable 6 (q0)
- * @param x7 Kalman state variable 7 (q1)
- * @param x8 Kalman state variable 8 (q2)
- * @param x9 Kalman state variable 9 (q3)
- * @param x10 Kalman state variable 10 (bias)
- * @param x11 Kalman state variable 11 (bias)
- * @param x12 Kalman state variable 12 (bias)
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_temperature [degC] Calibration temperature
- * @param ref_latitude [deg] Calibration latitude
- * @param ref_longitude [deg] Calibration longitude
- * @param ref_accel_x [m/s2] Calibration acceleration on x axis
- * @param ref_accel_y [m/s2] Calibration acceleration on y axis
- * @param ref_accel_z [m/s2] Calibration acceleration on z axis
- * @param ref_mag_x [uT] Calibration compass on x axis
- * @param ref_mag_y [uT] Calibration compass on y axis
- * @param ref_mag_z [uT] Calibration compass on z axis
- * @param triad_roll Orientation on roll estimated by TRIAD initialization
- * @param triad_pitch Orientation on pitch estimated by TRIAD initialization
- * @param triad_yaw Orientation on yaw estimated by TRIAD initialization
- * @param roll [deg] Orientation on roll
- * @param pitch [deg] Orientation on pitch
- * @param yaw [deg] Orientation on yaw
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_nas_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t state,float x0,float x1,float x2,float x3,float x4,float x5,float x6,float x7,float x8,float x9,float x10,float x11,float x12,float ref_pressure,float ref_temperature,float ref_latitude,float ref_longitude,float ref_accel_x,float ref_accel_y,float ref_accel_z,float ref_mag_x,float ref_mag_y,float ref_mag_z,float triad_roll,float triad_pitch,float triad_yaw,float roll,float pitch,float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NAS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, x0);
- _mav_put_float(buf, 12, x1);
- _mav_put_float(buf, 16, x2);
- _mav_put_float(buf, 20, x3);
- _mav_put_float(buf, 24, x4);
- _mav_put_float(buf, 28, x5);
- _mav_put_float(buf, 32, x6);
- _mav_put_float(buf, 36, x7);
- _mav_put_float(buf, 40, x8);
- _mav_put_float(buf, 44, x9);
- _mav_put_float(buf, 48, x10);
- _mav_put_float(buf, 52, x11);
- _mav_put_float(buf, 56, x12);
- _mav_put_float(buf, 60, ref_pressure);
- _mav_put_float(buf, 64, ref_temperature);
- _mav_put_float(buf, 68, ref_latitude);
- _mav_put_float(buf, 72, ref_longitude);
- _mav_put_float(buf, 76, ref_accel_x);
- _mav_put_float(buf, 80, ref_accel_y);
- _mav_put_float(buf, 84, ref_accel_z);
- _mav_put_float(buf, 88, ref_mag_x);
- _mav_put_float(buf, 92, ref_mag_y);
- _mav_put_float(buf, 96, ref_mag_z);
- _mav_put_float(buf, 100, triad_roll);
- _mav_put_float(buf, 104, triad_pitch);
- _mav_put_float(buf, 108, triad_yaw);
- _mav_put_float(buf, 112, roll);
- _mav_put_float(buf, 116, pitch);
- _mav_put_float(buf, 120, yaw);
- _mav_put_uint8_t(buf, 124, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAS_TM_LEN);
-#else
- mavlink_nas_tm_t packet;
- packet.timestamp = timestamp;
- packet.x0 = x0;
- packet.x1 = x1;
- packet.x2 = x2;
- packet.x3 = x3;
- packet.x4 = x4;
- packet.x5 = x5;
- packet.x6 = x6;
- packet.x7 = x7;
- packet.x8 = x8;
- packet.x9 = x9;
- packet.x10 = x10;
- packet.x11 = x11;
- packet.x12 = x12;
- packet.ref_pressure = ref_pressure;
- packet.ref_temperature = ref_temperature;
- packet.ref_latitude = ref_latitude;
- packet.ref_longitude = ref_longitude;
- packet.ref_accel_x = ref_accel_x;
- packet.ref_accel_y = ref_accel_y;
- packet.ref_accel_z = ref_accel_z;
- packet.ref_mag_x = ref_mag_x;
- packet.ref_mag_y = ref_mag_y;
- packet.ref_mag_z = ref_mag_z;
- packet.triad_roll = triad_roll;
- packet.triad_pitch = triad_pitch;
- packet.triad_yaw = triad_yaw;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NAS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-}
-
-/**
- * @brief Encode a nas_tm 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 nas_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_nas_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nas_tm_t* nas_tm)
-{
- return mavlink_msg_nas_tm_pack(system_id, component_id, msg, nas_tm->timestamp, nas_tm->state, nas_tm->x0, nas_tm->x1, nas_tm->x2, nas_tm->x3, nas_tm->x4, nas_tm->x5, nas_tm->x6, nas_tm->x7, nas_tm->x8, nas_tm->x9, nas_tm->x10, nas_tm->x11, nas_tm->x12, nas_tm->ref_pressure, nas_tm->ref_temperature, nas_tm->ref_latitude, nas_tm->ref_longitude, nas_tm->ref_accel_x, nas_tm->ref_accel_y, nas_tm->ref_accel_z, nas_tm->ref_mag_x, nas_tm->ref_mag_y, nas_tm->ref_mag_z, nas_tm->triad_roll, nas_tm->triad_pitch, nas_tm->triad_yaw, nas_tm->roll, nas_tm->pitch, nas_tm->yaw);
-}
-
-/**
- * @brief Encode a nas_tm 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 nas_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_nas_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nas_tm_t* nas_tm)
-{
- return mavlink_msg_nas_tm_pack_chan(system_id, component_id, chan, msg, nas_tm->timestamp, nas_tm->state, nas_tm->x0, nas_tm->x1, nas_tm->x2, nas_tm->x3, nas_tm->x4, nas_tm->x5, nas_tm->x6, nas_tm->x7, nas_tm->x8, nas_tm->x9, nas_tm->x10, nas_tm->x11, nas_tm->x12, nas_tm->ref_pressure, nas_tm->ref_temperature, nas_tm->ref_latitude, nas_tm->ref_longitude, nas_tm->ref_accel_x, nas_tm->ref_accel_y, nas_tm->ref_accel_z, nas_tm->ref_mag_x, nas_tm->ref_mag_y, nas_tm->ref_mag_z, nas_tm->triad_roll, nas_tm->triad_pitch, nas_tm->triad_yaw, nas_tm->roll, nas_tm->pitch, nas_tm->yaw);
-}
-
-/**
- * @brief Send a nas_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [ms] When was this logged
- * @param state NAS current state
- * @param x0 [m] Kalman state variable 0 (position x)
- * @param x1 [m] Kalman state variable 1 (position y)
- * @param x2 [m] >Kalman state variable 2 (position z)
- * @param x3 [m/s] >Kalman state variable 3 (velocity x)
- * @param x4 [m/s] >Kalman state variable 4 (velocity y)
- * @param x5 [m/s] >Kalman state variable 5 (velocity z)
- * @param x6 Kalman state variable 6 (q0)
- * @param x7 Kalman state variable 7 (q1)
- * @param x8 Kalman state variable 8 (q2)
- * @param x9 Kalman state variable 9 (q3)
- * @param x10 Kalman state variable 10 (bias)
- * @param x11 Kalman state variable 11 (bias)
- * @param x12 Kalman state variable 12 (bias)
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_temperature [degC] Calibration temperature
- * @param ref_latitude [deg] Calibration latitude
- * @param ref_longitude [deg] Calibration longitude
- * @param ref_accel_x [m/s2] Calibration acceleration on x axis
- * @param ref_accel_y [m/s2] Calibration acceleration on y axis
- * @param ref_accel_z [m/s2] Calibration acceleration on z axis
- * @param ref_mag_x [uT] Calibration compass on x axis
- * @param ref_mag_y [uT] Calibration compass on y axis
- * @param ref_mag_z [uT] Calibration compass on z axis
- * @param triad_roll Orientation on roll estimated by TRIAD initialization
- * @param triad_pitch Orientation on pitch estimated by TRIAD initialization
- * @param triad_yaw Orientation on yaw estimated by TRIAD initialization
- * @param roll [deg] Orientation on roll
- * @param pitch [deg] Orientation on pitch
- * @param yaw [deg] Orientation on yaw
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_nas_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float x0, float x1, float x2, float x3, float x4, float x5, float x6, float x7, float x8, float x9, float x10, float x11, float x12, float ref_pressure, float ref_temperature, float ref_latitude, float ref_longitude, float ref_accel_x, float ref_accel_y, float ref_accel_z, float ref_mag_x, float ref_mag_y, float ref_mag_z, float triad_roll, float triad_pitch, float triad_yaw, float roll, float pitch, float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NAS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, x0);
- _mav_put_float(buf, 12, x1);
- _mav_put_float(buf, 16, x2);
- _mav_put_float(buf, 20, x3);
- _mav_put_float(buf, 24, x4);
- _mav_put_float(buf, 28, x5);
- _mav_put_float(buf, 32, x6);
- _mav_put_float(buf, 36, x7);
- _mav_put_float(buf, 40, x8);
- _mav_put_float(buf, 44, x9);
- _mav_put_float(buf, 48, x10);
- _mav_put_float(buf, 52, x11);
- _mav_put_float(buf, 56, x12);
- _mav_put_float(buf, 60, ref_pressure);
- _mav_put_float(buf, 64, ref_temperature);
- _mav_put_float(buf, 68, ref_latitude);
- _mav_put_float(buf, 72, ref_longitude);
- _mav_put_float(buf, 76, ref_accel_x);
- _mav_put_float(buf, 80, ref_accel_y);
- _mav_put_float(buf, 84, ref_accel_z);
- _mav_put_float(buf, 88, ref_mag_x);
- _mav_put_float(buf, 92, ref_mag_y);
- _mav_put_float(buf, 96, ref_mag_z);
- _mav_put_float(buf, 100, triad_roll);
- _mav_put_float(buf, 104, triad_pitch);
- _mav_put_float(buf, 108, triad_yaw);
- _mav_put_float(buf, 112, roll);
- _mav_put_float(buf, 116, pitch);
- _mav_put_float(buf, 120, yaw);
- _mav_put_uint8_t(buf, 124, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAS_TM, buf, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-#else
- mavlink_nas_tm_t packet;
- packet.timestamp = timestamp;
- packet.x0 = x0;
- packet.x1 = x1;
- packet.x2 = x2;
- packet.x3 = x3;
- packet.x4 = x4;
- packet.x5 = x5;
- packet.x6 = x6;
- packet.x7 = x7;
- packet.x8 = x8;
- packet.x9 = x9;
- packet.x10 = x10;
- packet.x11 = x11;
- packet.x12 = x12;
- packet.ref_pressure = ref_pressure;
- packet.ref_temperature = ref_temperature;
- packet.ref_latitude = ref_latitude;
- packet.ref_longitude = ref_longitude;
- packet.ref_accel_x = ref_accel_x;
- packet.ref_accel_y = ref_accel_y;
- packet.ref_accel_z = ref_accel_z;
- packet.ref_mag_x = ref_mag_x;
- packet.ref_mag_y = ref_mag_y;
- packet.ref_mag_z = ref_mag_z;
- packet.triad_roll = triad_roll;
- packet.triad_pitch = triad_pitch;
- packet.triad_yaw = triad_yaw;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAS_TM, (const char *)&packet, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a nas_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_nas_tm_send_struct(mavlink_channel_t chan, const mavlink_nas_tm_t* nas_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_nas_tm_send(chan, nas_tm->timestamp, nas_tm->state, nas_tm->x0, nas_tm->x1, nas_tm->x2, nas_tm->x3, nas_tm->x4, nas_tm->x5, nas_tm->x6, nas_tm->x7, nas_tm->x8, nas_tm->x9, nas_tm->x10, nas_tm->x11, nas_tm->x12, nas_tm->ref_pressure, nas_tm->ref_temperature, nas_tm->ref_latitude, nas_tm->ref_longitude, nas_tm->ref_accel_x, nas_tm->ref_accel_y, nas_tm->ref_accel_z, nas_tm->ref_mag_x, nas_tm->ref_mag_y, nas_tm->ref_mag_z, nas_tm->triad_roll, nas_tm->triad_pitch, nas_tm->triad_yaw, nas_tm->roll, nas_tm->pitch, nas_tm->yaw);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAS_TM, (const char *)nas_tm, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_NAS_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_nas_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float x0, float x1, float x2, float x3, float x4, float x5, float x6, float x7, float x8, float x9, float x10, float x11, float x12, float ref_pressure, float ref_temperature, float ref_latitude, float ref_longitude, float ref_accel_x, float ref_accel_y, float ref_accel_z, float ref_mag_x, float ref_mag_y, float ref_mag_z, float triad_roll, float triad_pitch, float triad_yaw, float roll, float pitch, float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, x0);
- _mav_put_float(buf, 12, x1);
- _mav_put_float(buf, 16, x2);
- _mav_put_float(buf, 20, x3);
- _mav_put_float(buf, 24, x4);
- _mav_put_float(buf, 28, x5);
- _mav_put_float(buf, 32, x6);
- _mav_put_float(buf, 36, x7);
- _mav_put_float(buf, 40, x8);
- _mav_put_float(buf, 44, x9);
- _mav_put_float(buf, 48, x10);
- _mav_put_float(buf, 52, x11);
- _mav_put_float(buf, 56, x12);
- _mav_put_float(buf, 60, ref_pressure);
- _mav_put_float(buf, 64, ref_temperature);
- _mav_put_float(buf, 68, ref_latitude);
- _mav_put_float(buf, 72, ref_longitude);
- _mav_put_float(buf, 76, ref_accel_x);
- _mav_put_float(buf, 80, ref_accel_y);
- _mav_put_float(buf, 84, ref_accel_z);
- _mav_put_float(buf, 88, ref_mag_x);
- _mav_put_float(buf, 92, ref_mag_y);
- _mav_put_float(buf, 96, ref_mag_z);
- _mav_put_float(buf, 100, triad_roll);
- _mav_put_float(buf, 104, triad_pitch);
- _mav_put_float(buf, 108, triad_yaw);
- _mav_put_float(buf, 112, roll);
- _mav_put_float(buf, 116, pitch);
- _mav_put_float(buf, 120, yaw);
- _mav_put_uint8_t(buf, 124, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAS_TM, buf, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-#else
- mavlink_nas_tm_t *packet = (mavlink_nas_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->x0 = x0;
- packet->x1 = x1;
- packet->x2 = x2;
- packet->x3 = x3;
- packet->x4 = x4;
- packet->x5 = x5;
- packet->x6 = x6;
- packet->x7 = x7;
- packet->x8 = x8;
- packet->x9 = x9;
- packet->x10 = x10;
- packet->x11 = x11;
- packet->x12 = x12;
- packet->ref_pressure = ref_pressure;
- packet->ref_temperature = ref_temperature;
- packet->ref_latitude = ref_latitude;
- packet->ref_longitude = ref_longitude;
- packet->ref_accel_x = ref_accel_x;
- packet->ref_accel_y = ref_accel_y;
- packet->ref_accel_z = ref_accel_z;
- packet->ref_mag_x = ref_mag_x;
- packet->ref_mag_y = ref_mag_y;
- packet->ref_mag_z = ref_mag_z;
- packet->triad_roll = triad_roll;
- packet->triad_pitch = triad_pitch;
- packet->triad_yaw = triad_yaw;
- packet->roll = roll;
- packet->pitch = pitch;
- packet->yaw = yaw;
- packet->state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAS_TM, (const char *)packet, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE NAS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from nas_tm message
- *
- * @return [ms] When was this logged
- */
-static inline uint64_t mavlink_msg_nas_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field state from nas_tm message
- *
- * @return NAS current state
- */
-static inline uint8_t mavlink_msg_nas_tm_get_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 124);
-}
-
-/**
- * @brief Get field x0 from nas_tm message
- *
- * @return [m] Kalman state variable 0 (position x)
- */
-static inline float mavlink_msg_nas_tm_get_x0(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field x1 from nas_tm message
- *
- * @return [m] Kalman state variable 1 (position y)
- */
-static inline float mavlink_msg_nas_tm_get_x1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field x2 from nas_tm message
- *
- * @return [m] >Kalman state variable 2 (position z)
- */
-static inline float mavlink_msg_nas_tm_get_x2(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field x3 from nas_tm message
- *
- * @return [m/s] >Kalman state variable 3 (velocity x)
- */
-static inline float mavlink_msg_nas_tm_get_x3(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field x4 from nas_tm message
- *
- * @return [m/s] >Kalman state variable 4 (velocity y)
- */
-static inline float mavlink_msg_nas_tm_get_x4(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field x5 from nas_tm message
- *
- * @return [m/s] >Kalman state variable 5 (velocity z)
- */
-static inline float mavlink_msg_nas_tm_get_x5(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field x6 from nas_tm message
- *
- * @return Kalman state variable 6 (q0)
- */
-static inline float mavlink_msg_nas_tm_get_x6(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field x7 from nas_tm message
- *
- * @return Kalman state variable 7 (q1)
- */
-static inline float mavlink_msg_nas_tm_get_x7(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field x8 from nas_tm message
- *
- * @return Kalman state variable 8 (q2)
- */
-static inline float mavlink_msg_nas_tm_get_x8(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field x9 from nas_tm message
- *
- * @return Kalman state variable 9 (q3)
- */
-static inline float mavlink_msg_nas_tm_get_x9(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field x10 from nas_tm message
- *
- * @return Kalman state variable 10 (bias)
- */
-static inline float mavlink_msg_nas_tm_get_x10(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field x11 from nas_tm message
- *
- * @return Kalman state variable 11 (bias)
- */
-static inline float mavlink_msg_nas_tm_get_x11(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field x12 from nas_tm message
- *
- * @return Kalman state variable 12 (bias)
- */
-static inline float mavlink_msg_nas_tm_get_x12(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field ref_pressure from nas_tm message
- *
- * @return [Pa] Calibration pressure
- */
-static inline float mavlink_msg_nas_tm_get_ref_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field ref_temperature from nas_tm message
- *
- * @return [degC] Calibration temperature
- */
-static inline float mavlink_msg_nas_tm_get_ref_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field ref_latitude from nas_tm message
- *
- * @return [deg] Calibration latitude
- */
-static inline float mavlink_msg_nas_tm_get_ref_latitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field ref_longitude from nas_tm message
- *
- * @return [deg] Calibration longitude
- */
-static inline float mavlink_msg_nas_tm_get_ref_longitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 72);
-}
-
-/**
- * @brief Get field ref_accel_x from nas_tm message
- *
- * @return [m/s2] Calibration acceleration on x axis
- */
-static inline float mavlink_msg_nas_tm_get_ref_accel_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 76);
-}
-
-/**
- * @brief Get field ref_accel_y from nas_tm message
- *
- * @return [m/s2] Calibration acceleration on y axis
- */
-static inline float mavlink_msg_nas_tm_get_ref_accel_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 80);
-}
-
-/**
- * @brief Get field ref_accel_z from nas_tm message
- *
- * @return [m/s2] Calibration acceleration on z axis
- */
-static inline float mavlink_msg_nas_tm_get_ref_accel_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 84);
-}
-
-/**
- * @brief Get field ref_mag_x from nas_tm message
- *
- * @return [uT] Calibration compass on x axis
- */
-static inline float mavlink_msg_nas_tm_get_ref_mag_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 88);
-}
-
-/**
- * @brief Get field ref_mag_y from nas_tm message
- *
- * @return [uT] Calibration compass on y axis
- */
-static inline float mavlink_msg_nas_tm_get_ref_mag_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 92);
-}
-
-/**
- * @brief Get field ref_mag_z from nas_tm message
- *
- * @return [uT] Calibration compass on z axis
- */
-static inline float mavlink_msg_nas_tm_get_ref_mag_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 96);
-}
-
-/**
- * @brief Get field triad_roll from nas_tm message
- *
- * @return Orientation on roll estimated by TRIAD initialization
- */
-static inline float mavlink_msg_nas_tm_get_triad_roll(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 100);
-}
-
-/**
- * @brief Get field triad_pitch from nas_tm message
- *
- * @return Orientation on pitch estimated by TRIAD initialization
- */
-static inline float mavlink_msg_nas_tm_get_triad_pitch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 104);
-}
-
-/**
- * @brief Get field triad_yaw from nas_tm message
- *
- * @return Orientation on yaw estimated by TRIAD initialization
- */
-static inline float mavlink_msg_nas_tm_get_triad_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 108);
-}
-
-/**
- * @brief Get field roll from nas_tm message
- *
- * @return [deg] Orientation on roll
- */
-static inline float mavlink_msg_nas_tm_get_roll(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 112);
-}
-
-/**
- * @brief Get field pitch from nas_tm message
- *
- * @return [deg] Orientation on pitch
- */
-static inline float mavlink_msg_nas_tm_get_pitch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 116);
-}
-
-/**
- * @brief Get field yaw from nas_tm message
- *
- * @return [deg] Orientation on yaw
- */
-static inline float mavlink_msg_nas_tm_get_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 120);
-}
-
-/**
- * @brief Decode a nas_tm message into a struct
- *
- * @param msg The message to decode
- * @param nas_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_nas_tm_decode(const mavlink_message_t* msg, mavlink_nas_tm_t* nas_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- nas_tm->timestamp = mavlink_msg_nas_tm_get_timestamp(msg);
- nas_tm->x0 = mavlink_msg_nas_tm_get_x0(msg);
- nas_tm->x1 = mavlink_msg_nas_tm_get_x1(msg);
- nas_tm->x2 = mavlink_msg_nas_tm_get_x2(msg);
- nas_tm->x3 = mavlink_msg_nas_tm_get_x3(msg);
- nas_tm->x4 = mavlink_msg_nas_tm_get_x4(msg);
- nas_tm->x5 = mavlink_msg_nas_tm_get_x5(msg);
- nas_tm->x6 = mavlink_msg_nas_tm_get_x6(msg);
- nas_tm->x7 = mavlink_msg_nas_tm_get_x7(msg);
- nas_tm->x8 = mavlink_msg_nas_tm_get_x8(msg);
- nas_tm->x9 = mavlink_msg_nas_tm_get_x9(msg);
- nas_tm->x10 = mavlink_msg_nas_tm_get_x10(msg);
- nas_tm->x11 = mavlink_msg_nas_tm_get_x11(msg);
- nas_tm->x12 = mavlink_msg_nas_tm_get_x12(msg);
- nas_tm->ref_pressure = mavlink_msg_nas_tm_get_ref_pressure(msg);
- nas_tm->ref_temperature = mavlink_msg_nas_tm_get_ref_temperature(msg);
- nas_tm->ref_latitude = mavlink_msg_nas_tm_get_ref_latitude(msg);
- nas_tm->ref_longitude = mavlink_msg_nas_tm_get_ref_longitude(msg);
- nas_tm->ref_accel_x = mavlink_msg_nas_tm_get_ref_accel_x(msg);
- nas_tm->ref_accel_y = mavlink_msg_nas_tm_get_ref_accel_y(msg);
- nas_tm->ref_accel_z = mavlink_msg_nas_tm_get_ref_accel_z(msg);
- nas_tm->ref_mag_x = mavlink_msg_nas_tm_get_ref_mag_x(msg);
- nas_tm->ref_mag_y = mavlink_msg_nas_tm_get_ref_mag_y(msg);
- nas_tm->ref_mag_z = mavlink_msg_nas_tm_get_ref_mag_z(msg);
- nas_tm->triad_roll = mavlink_msg_nas_tm_get_triad_roll(msg);
- nas_tm->triad_pitch = mavlink_msg_nas_tm_get_triad_pitch(msg);
- nas_tm->triad_yaw = mavlink_msg_nas_tm_get_triad_yaw(msg);
- nas_tm->roll = mavlink_msg_nas_tm_get_roll(msg);
- nas_tm->pitch = mavlink_msg_nas_tm_get_pitch(msg);
- nas_tm->yaw = mavlink_msg_nas_tm_get_yaw(msg);
- nas_tm->state = mavlink_msg_nas_tm_get_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_NAS_TM_LEN? msg->len : MAVLINK_MSG_ID_NAS_TM_LEN;
- memset(nas_tm, 0, MAVLINK_MSG_ID_NAS_TM_LEN);
- memcpy(nas_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_noarg_tc.h b/mavlink_lib/lynx/mavlink_msg_noarg_tc.h
deleted file mode 100644
index 7de53c9223ff12524224dede49dcfee4c45f38c1..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_noarg_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE NOARG_TC PACKING
-
-#define MAVLINK_MSG_ID_NOARG_TC 10
-
-MAVPACKED(
-typedef struct __mavlink_noarg_tc_t {
- uint8_t command_id; /*< A member of the MavCommandList enum.*/
-}) mavlink_noarg_tc_t;
-
-#define MAVLINK_MSG_ID_NOARG_TC_LEN 1
-#define MAVLINK_MSG_ID_NOARG_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_10_LEN 1
-#define MAVLINK_MSG_ID_10_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_NOARG_TC_CRC 77
-#define MAVLINK_MSG_ID_10_CRC 77
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_NOARG_TC { \
- 10, \
- "NOARG_TC", \
- 1, \
- { { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_noarg_tc_t, command_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_NOARG_TC { \
- "NOARG_TC", \
- 1, \
- { { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_noarg_tc_t, command_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a noarg_tc 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_id A member of the MavCommandList enum.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_noarg_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NOARG_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NOARG_TC_LEN);
-#else
- mavlink_noarg_tc_t packet;
- packet.command_id = command_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NOARG_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NOARG_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-}
-
-/**
- * @brief Pack a noarg_tc 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_id A member of the MavCommandList enum.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_noarg_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NOARG_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NOARG_TC_LEN);
-#else
- mavlink_noarg_tc_t packet;
- packet.command_id = command_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NOARG_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NOARG_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-}
-
-/**
- * @brief Encode a noarg_tc 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 noarg_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_noarg_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_noarg_tc_t* noarg_tc)
-{
- return mavlink_msg_noarg_tc_pack(system_id, component_id, msg, noarg_tc->command_id);
-}
-
-/**
- * @brief Encode a noarg_tc 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 noarg_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_noarg_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_noarg_tc_t* noarg_tc)
-{
- return mavlink_msg_noarg_tc_pack_chan(system_id, component_id, chan, msg, noarg_tc->command_id);
-}
-
-/**
- * @brief Send a noarg_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param command_id A member of the MavCommandList enum.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_noarg_tc_send(mavlink_channel_t chan, uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NOARG_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOARG_TC, buf, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-#else
- mavlink_noarg_tc_t packet;
- packet.command_id = command_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOARG_TC, (const char *)&packet, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a noarg_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_noarg_tc_send_struct(mavlink_channel_t chan, const mavlink_noarg_tc_t* noarg_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_noarg_tc_send(chan, noarg_tc->command_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOARG_TC, (const char *)noarg_tc, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_NOARG_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_noarg_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, command_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOARG_TC, buf, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-#else
- mavlink_noarg_tc_t *packet = (mavlink_noarg_tc_t *)msgbuf;
- packet->command_id = command_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOARG_TC, (const char *)packet, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE NOARG_TC UNPACKING
-
-
-/**
- * @brief Get field command_id from noarg_tc message
- *
- * @return A member of the MavCommandList enum.
- */
-static inline uint8_t mavlink_msg_noarg_tc_get_command_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a noarg_tc message into a struct
- *
- * @param msg The message to decode
- * @param noarg_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_noarg_tc_decode(const mavlink_message_t* msg, mavlink_noarg_tc_t* noarg_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- noarg_tc->command_id = mavlink_msg_noarg_tc_get_command_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_NOARG_TC_LEN? msg->len : MAVLINK_MSG_ID_NOARG_TC_LEN;
- memset(noarg_tc, 0, MAVLINK_MSG_ID_NOARG_TC_LEN);
- memcpy(noarg_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_pin_obs_tm.h b/mavlink_lib/lynx/mavlink_msg_pin_obs_tm.h
deleted file mode 100644
index a76d36f10d8f3e45ddf0881bb89861f7144bd471..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_pin_obs_tm.h
+++ /dev/null
@@ -1,438 +0,0 @@
-#pragma once
-// MESSAGE PIN_OBS_TM PACKING
-
-#define MAVLINK_MSG_ID_PIN_OBS_TM 162
-
-MAVPACKED(
-typedef struct __mavlink_pin_obs_tm_t {
- uint64_t timestamp; /*< [ms] Timestamp*/
- uint64_t pin_launch_last_change; /*< Last change of the launch pin*/
- uint64_t pin_nosecone_last_change; /*< Last change of the nosecone pin*/
- uint64_t pin_dpl_servo_last_change; /*< Last change of the dpl servo optical sensor*/
- uint8_t pin_launch_num_changes; /*< Number of changes of the launch pin*/
- uint8_t pin_launch_state; /*< Current state of the launch pin*/
- uint8_t pin_nosecone_num_changes; /*< Number of changes of the nosecone pin*/
- uint8_t pin_nosecone_state; /*< Current state of the nosecone pin*/
- uint8_t pin_dpl_servo_num_changes; /*< Number of changes of the dpl servo optical sensor*/
- uint8_t pin_dpl_servo_state; /*< Current state of the dpl servo optical sensor*/
-}) mavlink_pin_obs_tm_t;
-
-#define MAVLINK_MSG_ID_PIN_OBS_TM_LEN 38
-#define MAVLINK_MSG_ID_PIN_OBS_TM_MIN_LEN 38
-#define MAVLINK_MSG_ID_162_LEN 38
-#define MAVLINK_MSG_ID_162_MIN_LEN 38
-
-#define MAVLINK_MSG_ID_PIN_OBS_TM_CRC 66
-#define MAVLINK_MSG_ID_162_CRC 66
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_PIN_OBS_TM { \
- 162, \
- "PIN_OBS_TM", \
- 10, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_pin_obs_tm_t, timestamp) }, \
- { "pin_launch_last_change", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_pin_obs_tm_t, pin_launch_last_change) }, \
- { "pin_launch_num_changes", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_pin_obs_tm_t, pin_launch_num_changes) }, \
- { "pin_launch_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_pin_obs_tm_t, pin_launch_state) }, \
- { "pin_nosecone_last_change", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_pin_obs_tm_t, pin_nosecone_last_change) }, \
- { "pin_nosecone_num_changes", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_pin_obs_tm_t, pin_nosecone_num_changes) }, \
- { "pin_nosecone_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_pin_obs_tm_t, pin_nosecone_state) }, \
- { "pin_dpl_servo_last_change", NULL, MAVLINK_TYPE_UINT64_T, 0, 24, offsetof(mavlink_pin_obs_tm_t, pin_dpl_servo_last_change) }, \
- { "pin_dpl_servo_num_changes", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_pin_obs_tm_t, pin_dpl_servo_num_changes) }, \
- { "pin_dpl_servo_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_pin_obs_tm_t, pin_dpl_servo_state) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_PIN_OBS_TM { \
- "PIN_OBS_TM", \
- 10, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_pin_obs_tm_t, timestamp) }, \
- { "pin_launch_last_change", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_pin_obs_tm_t, pin_launch_last_change) }, \
- { "pin_launch_num_changes", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_pin_obs_tm_t, pin_launch_num_changes) }, \
- { "pin_launch_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_pin_obs_tm_t, pin_launch_state) }, \
- { "pin_nosecone_last_change", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_pin_obs_tm_t, pin_nosecone_last_change) }, \
- { "pin_nosecone_num_changes", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_pin_obs_tm_t, pin_nosecone_num_changes) }, \
- { "pin_nosecone_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_pin_obs_tm_t, pin_nosecone_state) }, \
- { "pin_dpl_servo_last_change", NULL, MAVLINK_TYPE_UINT64_T, 0, 24, offsetof(mavlink_pin_obs_tm_t, pin_dpl_servo_last_change) }, \
- { "pin_dpl_servo_num_changes", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_pin_obs_tm_t, pin_dpl_servo_num_changes) }, \
- { "pin_dpl_servo_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_pin_obs_tm_t, pin_dpl_servo_state) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a pin_obs_tm 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
- * @param pin_launch_last_change Last change of the launch pin
- * @param pin_launch_num_changes Number of changes of the launch pin
- * @param pin_launch_state Current state of the launch pin
- * @param pin_nosecone_last_change Last change of the nosecone pin
- * @param pin_nosecone_num_changes Number of changes of the nosecone pin
- * @param pin_nosecone_state Current state of the nosecone pin
- * @param pin_dpl_servo_last_change Last change of the dpl servo optical sensor
- * @param pin_dpl_servo_num_changes Number of changes of the dpl servo optical sensor
- * @param pin_dpl_servo_state Current state of the dpl servo optical sensor
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_pin_obs_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint64_t pin_launch_last_change, uint8_t pin_launch_num_changes, uint8_t pin_launch_state, uint64_t pin_nosecone_last_change, uint8_t pin_nosecone_num_changes, uint8_t pin_nosecone_state, uint64_t pin_dpl_servo_last_change, uint8_t pin_dpl_servo_num_changes, uint8_t pin_dpl_servo_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PIN_OBS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, pin_launch_last_change);
- _mav_put_uint64_t(buf, 16, pin_nosecone_last_change);
- _mav_put_uint64_t(buf, 24, pin_dpl_servo_last_change);
- _mav_put_uint8_t(buf, 32, pin_launch_num_changes);
- _mav_put_uint8_t(buf, 33, pin_launch_state);
- _mav_put_uint8_t(buf, 34, pin_nosecone_num_changes);
- _mav_put_uint8_t(buf, 35, pin_nosecone_state);
- _mav_put_uint8_t(buf, 36, pin_dpl_servo_num_changes);
- _mav_put_uint8_t(buf, 37, pin_dpl_servo_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PIN_OBS_TM_LEN);
-#else
- mavlink_pin_obs_tm_t packet;
- packet.timestamp = timestamp;
- packet.pin_launch_last_change = pin_launch_last_change;
- packet.pin_nosecone_last_change = pin_nosecone_last_change;
- packet.pin_dpl_servo_last_change = pin_dpl_servo_last_change;
- packet.pin_launch_num_changes = pin_launch_num_changes;
- packet.pin_launch_state = pin_launch_state;
- packet.pin_nosecone_num_changes = pin_nosecone_num_changes;
- packet.pin_nosecone_state = pin_nosecone_state;
- packet.pin_dpl_servo_num_changes = pin_dpl_servo_num_changes;
- packet.pin_dpl_servo_state = pin_dpl_servo_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PIN_OBS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PIN_OBS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PIN_OBS_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_OBS_TM_LEN, MAVLINK_MSG_ID_PIN_OBS_TM_CRC);
-}
-
-/**
- * @brief Pack a pin_obs_tm 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
- * @param pin_launch_last_change Last change of the launch pin
- * @param pin_launch_num_changes Number of changes of the launch pin
- * @param pin_launch_state Current state of the launch pin
- * @param pin_nosecone_last_change Last change of the nosecone pin
- * @param pin_nosecone_num_changes Number of changes of the nosecone pin
- * @param pin_nosecone_state Current state of the nosecone pin
- * @param pin_dpl_servo_last_change Last change of the dpl servo optical sensor
- * @param pin_dpl_servo_num_changes Number of changes of the dpl servo optical sensor
- * @param pin_dpl_servo_state Current state of the dpl servo optical sensor
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_pin_obs_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint64_t pin_launch_last_change,uint8_t pin_launch_num_changes,uint8_t pin_launch_state,uint64_t pin_nosecone_last_change,uint8_t pin_nosecone_num_changes,uint8_t pin_nosecone_state,uint64_t pin_dpl_servo_last_change,uint8_t pin_dpl_servo_num_changes,uint8_t pin_dpl_servo_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PIN_OBS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, pin_launch_last_change);
- _mav_put_uint64_t(buf, 16, pin_nosecone_last_change);
- _mav_put_uint64_t(buf, 24, pin_dpl_servo_last_change);
- _mav_put_uint8_t(buf, 32, pin_launch_num_changes);
- _mav_put_uint8_t(buf, 33, pin_launch_state);
- _mav_put_uint8_t(buf, 34, pin_nosecone_num_changes);
- _mav_put_uint8_t(buf, 35, pin_nosecone_state);
- _mav_put_uint8_t(buf, 36, pin_dpl_servo_num_changes);
- _mav_put_uint8_t(buf, 37, pin_dpl_servo_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PIN_OBS_TM_LEN);
-#else
- mavlink_pin_obs_tm_t packet;
- packet.timestamp = timestamp;
- packet.pin_launch_last_change = pin_launch_last_change;
- packet.pin_nosecone_last_change = pin_nosecone_last_change;
- packet.pin_dpl_servo_last_change = pin_dpl_servo_last_change;
- packet.pin_launch_num_changes = pin_launch_num_changes;
- packet.pin_launch_state = pin_launch_state;
- packet.pin_nosecone_num_changes = pin_nosecone_num_changes;
- packet.pin_nosecone_state = pin_nosecone_state;
- packet.pin_dpl_servo_num_changes = pin_dpl_servo_num_changes;
- packet.pin_dpl_servo_state = pin_dpl_servo_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PIN_OBS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PIN_OBS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PIN_OBS_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_OBS_TM_LEN, MAVLINK_MSG_ID_PIN_OBS_TM_CRC);
-}
-
-/**
- * @brief Encode a pin_obs_tm 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 pin_obs_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_pin_obs_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pin_obs_tm_t* pin_obs_tm)
-{
- return mavlink_msg_pin_obs_tm_pack(system_id, component_id, msg, pin_obs_tm->timestamp, pin_obs_tm->pin_launch_last_change, pin_obs_tm->pin_launch_num_changes, pin_obs_tm->pin_launch_state, pin_obs_tm->pin_nosecone_last_change, pin_obs_tm->pin_nosecone_num_changes, pin_obs_tm->pin_nosecone_state, pin_obs_tm->pin_dpl_servo_last_change, pin_obs_tm->pin_dpl_servo_num_changes, pin_obs_tm->pin_dpl_servo_state);
-}
-
-/**
- * @brief Encode a pin_obs_tm 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 pin_obs_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_pin_obs_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_pin_obs_tm_t* pin_obs_tm)
-{
- return mavlink_msg_pin_obs_tm_pack_chan(system_id, component_id, chan, msg, pin_obs_tm->timestamp, pin_obs_tm->pin_launch_last_change, pin_obs_tm->pin_launch_num_changes, pin_obs_tm->pin_launch_state, pin_obs_tm->pin_nosecone_last_change, pin_obs_tm->pin_nosecone_num_changes, pin_obs_tm->pin_nosecone_state, pin_obs_tm->pin_dpl_servo_last_change, pin_obs_tm->pin_dpl_servo_num_changes, pin_obs_tm->pin_dpl_servo_state);
-}
-
-/**
- * @brief Send a pin_obs_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [ms] Timestamp
- * @param pin_launch_last_change Last change of the launch pin
- * @param pin_launch_num_changes Number of changes of the launch pin
- * @param pin_launch_state Current state of the launch pin
- * @param pin_nosecone_last_change Last change of the nosecone pin
- * @param pin_nosecone_num_changes Number of changes of the nosecone pin
- * @param pin_nosecone_state Current state of the nosecone pin
- * @param pin_dpl_servo_last_change Last change of the dpl servo optical sensor
- * @param pin_dpl_servo_num_changes Number of changes of the dpl servo optical sensor
- * @param pin_dpl_servo_state Current state of the dpl servo optical sensor
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_pin_obs_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint64_t pin_launch_last_change, uint8_t pin_launch_num_changes, uint8_t pin_launch_state, uint64_t pin_nosecone_last_change, uint8_t pin_nosecone_num_changes, uint8_t pin_nosecone_state, uint64_t pin_dpl_servo_last_change, uint8_t pin_dpl_servo_num_changes, uint8_t pin_dpl_servo_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PIN_OBS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, pin_launch_last_change);
- _mav_put_uint64_t(buf, 16, pin_nosecone_last_change);
- _mav_put_uint64_t(buf, 24, pin_dpl_servo_last_change);
- _mav_put_uint8_t(buf, 32, pin_launch_num_changes);
- _mav_put_uint8_t(buf, 33, pin_launch_state);
- _mav_put_uint8_t(buf, 34, pin_nosecone_num_changes);
- _mav_put_uint8_t(buf, 35, pin_nosecone_state);
- _mav_put_uint8_t(buf, 36, pin_dpl_servo_num_changes);
- _mav_put_uint8_t(buf, 37, pin_dpl_servo_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PIN_OBS_TM, buf, MAVLINK_MSG_ID_PIN_OBS_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_OBS_TM_LEN, MAVLINK_MSG_ID_PIN_OBS_TM_CRC);
-#else
- mavlink_pin_obs_tm_t packet;
- packet.timestamp = timestamp;
- packet.pin_launch_last_change = pin_launch_last_change;
- packet.pin_nosecone_last_change = pin_nosecone_last_change;
- packet.pin_dpl_servo_last_change = pin_dpl_servo_last_change;
- packet.pin_launch_num_changes = pin_launch_num_changes;
- packet.pin_launch_state = pin_launch_state;
- packet.pin_nosecone_num_changes = pin_nosecone_num_changes;
- packet.pin_nosecone_state = pin_nosecone_state;
- packet.pin_dpl_servo_num_changes = pin_dpl_servo_num_changes;
- packet.pin_dpl_servo_state = pin_dpl_servo_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PIN_OBS_TM, (const char *)&packet, MAVLINK_MSG_ID_PIN_OBS_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_OBS_TM_LEN, MAVLINK_MSG_ID_PIN_OBS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a pin_obs_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_pin_obs_tm_send_struct(mavlink_channel_t chan, const mavlink_pin_obs_tm_t* pin_obs_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_pin_obs_tm_send(chan, pin_obs_tm->timestamp, pin_obs_tm->pin_launch_last_change, pin_obs_tm->pin_launch_num_changes, pin_obs_tm->pin_launch_state, pin_obs_tm->pin_nosecone_last_change, pin_obs_tm->pin_nosecone_num_changes, pin_obs_tm->pin_nosecone_state, pin_obs_tm->pin_dpl_servo_last_change, pin_obs_tm->pin_dpl_servo_num_changes, pin_obs_tm->pin_dpl_servo_state);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PIN_OBS_TM, (const char *)pin_obs_tm, MAVLINK_MSG_ID_PIN_OBS_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_OBS_TM_LEN, MAVLINK_MSG_ID_PIN_OBS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_PIN_OBS_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_pin_obs_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint64_t pin_launch_last_change, uint8_t pin_launch_num_changes, uint8_t pin_launch_state, uint64_t pin_nosecone_last_change, uint8_t pin_nosecone_num_changes, uint8_t pin_nosecone_state, uint64_t pin_dpl_servo_last_change, uint8_t pin_dpl_servo_num_changes, uint8_t pin_dpl_servo_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, pin_launch_last_change);
- _mav_put_uint64_t(buf, 16, pin_nosecone_last_change);
- _mav_put_uint64_t(buf, 24, pin_dpl_servo_last_change);
- _mav_put_uint8_t(buf, 32, pin_launch_num_changes);
- _mav_put_uint8_t(buf, 33, pin_launch_state);
- _mav_put_uint8_t(buf, 34, pin_nosecone_num_changes);
- _mav_put_uint8_t(buf, 35, pin_nosecone_state);
- _mav_put_uint8_t(buf, 36, pin_dpl_servo_num_changes);
- _mav_put_uint8_t(buf, 37, pin_dpl_servo_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PIN_OBS_TM, buf, MAVLINK_MSG_ID_PIN_OBS_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_OBS_TM_LEN, MAVLINK_MSG_ID_PIN_OBS_TM_CRC);
-#else
- mavlink_pin_obs_tm_t *packet = (mavlink_pin_obs_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->pin_launch_last_change = pin_launch_last_change;
- packet->pin_nosecone_last_change = pin_nosecone_last_change;
- packet->pin_dpl_servo_last_change = pin_dpl_servo_last_change;
- packet->pin_launch_num_changes = pin_launch_num_changes;
- packet->pin_launch_state = pin_launch_state;
- packet->pin_nosecone_num_changes = pin_nosecone_num_changes;
- packet->pin_nosecone_state = pin_nosecone_state;
- packet->pin_dpl_servo_num_changes = pin_dpl_servo_num_changes;
- packet->pin_dpl_servo_state = pin_dpl_servo_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PIN_OBS_TM, (const char *)packet, MAVLINK_MSG_ID_PIN_OBS_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_OBS_TM_LEN, MAVLINK_MSG_ID_PIN_OBS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE PIN_OBS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from pin_obs_tm message
- *
- * @return [ms] Timestamp
- */
-static inline uint64_t mavlink_msg_pin_obs_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field pin_launch_last_change from pin_obs_tm message
- *
- * @return Last change of the launch pin
- */
-static inline uint64_t mavlink_msg_pin_obs_tm_get_pin_launch_last_change(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 8);
-}
-
-/**
- * @brief Get field pin_launch_num_changes from pin_obs_tm message
- *
- * @return Number of changes of the launch pin
- */
-static inline uint8_t mavlink_msg_pin_obs_tm_get_pin_launch_num_changes(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 32);
-}
-
-/**
- * @brief Get field pin_launch_state from pin_obs_tm message
- *
- * @return Current state of the launch pin
- */
-static inline uint8_t mavlink_msg_pin_obs_tm_get_pin_launch_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 33);
-}
-
-/**
- * @brief Get field pin_nosecone_last_change from pin_obs_tm message
- *
- * @return Last change of the nosecone pin
- */
-static inline uint64_t mavlink_msg_pin_obs_tm_get_pin_nosecone_last_change(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 16);
-}
-
-/**
- * @brief Get field pin_nosecone_num_changes from pin_obs_tm message
- *
- * @return Number of changes of the nosecone pin
- */
-static inline uint8_t mavlink_msg_pin_obs_tm_get_pin_nosecone_num_changes(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 34);
-}
-
-/**
- * @brief Get field pin_nosecone_state from pin_obs_tm message
- *
- * @return Current state of the nosecone pin
- */
-static inline uint8_t mavlink_msg_pin_obs_tm_get_pin_nosecone_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 35);
-}
-
-/**
- * @brief Get field pin_dpl_servo_last_change from pin_obs_tm message
- *
- * @return Last change of the dpl servo optical sensor
- */
-static inline uint64_t mavlink_msg_pin_obs_tm_get_pin_dpl_servo_last_change(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 24);
-}
-
-/**
- * @brief Get field pin_dpl_servo_num_changes from pin_obs_tm message
- *
- * @return Number of changes of the dpl servo optical sensor
- */
-static inline uint8_t mavlink_msg_pin_obs_tm_get_pin_dpl_servo_num_changes(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 36);
-}
-
-/**
- * @brief Get field pin_dpl_servo_state from pin_obs_tm message
- *
- * @return Current state of the dpl servo optical sensor
- */
-static inline uint8_t mavlink_msg_pin_obs_tm_get_pin_dpl_servo_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 37);
-}
-
-/**
- * @brief Decode a pin_obs_tm message into a struct
- *
- * @param msg The message to decode
- * @param pin_obs_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_pin_obs_tm_decode(const mavlink_message_t* msg, mavlink_pin_obs_tm_t* pin_obs_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- pin_obs_tm->timestamp = mavlink_msg_pin_obs_tm_get_timestamp(msg);
- pin_obs_tm->pin_launch_last_change = mavlink_msg_pin_obs_tm_get_pin_launch_last_change(msg);
- pin_obs_tm->pin_nosecone_last_change = mavlink_msg_pin_obs_tm_get_pin_nosecone_last_change(msg);
- pin_obs_tm->pin_dpl_servo_last_change = mavlink_msg_pin_obs_tm_get_pin_dpl_servo_last_change(msg);
- pin_obs_tm->pin_launch_num_changes = mavlink_msg_pin_obs_tm_get_pin_launch_num_changes(msg);
- pin_obs_tm->pin_launch_state = mavlink_msg_pin_obs_tm_get_pin_launch_state(msg);
- pin_obs_tm->pin_nosecone_num_changes = mavlink_msg_pin_obs_tm_get_pin_nosecone_num_changes(msg);
- pin_obs_tm->pin_nosecone_state = mavlink_msg_pin_obs_tm_get_pin_nosecone_state(msg);
- pin_obs_tm->pin_dpl_servo_num_changes = mavlink_msg_pin_obs_tm_get_pin_dpl_servo_num_changes(msg);
- pin_obs_tm->pin_dpl_servo_state = mavlink_msg_pin_obs_tm_get_pin_dpl_servo_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_PIN_OBS_TM_LEN? msg->len : MAVLINK_MSG_ID_PIN_OBS_TM_LEN;
- memset(pin_obs_tm, 0, MAVLINK_MSG_ID_PIN_OBS_TM_LEN);
- memcpy(pin_obs_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_ping_tc.h b/mavlink_lib/lynx/mavlink_msg_ping_tc.h
deleted file mode 100644
index cb1575a0f48705e36177dc8186d3ae85bbd41391..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_ping_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE PING_TC PACKING
-
-#define MAVLINK_MSG_ID_PING_TC 1
-
-MAVPACKED(
-typedef struct __mavlink_ping_tc_t {
- uint64_t timestamp; /*< Timestamp to identify when it was sent.*/
-}) mavlink_ping_tc_t;
-
-#define MAVLINK_MSG_ID_PING_TC_LEN 8
-#define MAVLINK_MSG_ID_PING_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_1_LEN 8
-#define MAVLINK_MSG_ID_1_MIN_LEN 8
-
-#define MAVLINK_MSG_ID_PING_TC_CRC 136
-#define MAVLINK_MSG_ID_1_CRC 136
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_PING_TC { \
- 1, \
- "PING_TC", \
- 1, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_tc_t, timestamp) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_PING_TC { \
- "PING_TC", \
- 1, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_tc_t, timestamp) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ping_tc 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 Timestamp to identify when it was sent.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ping_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_TC_LEN);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PING_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-}
-
-/**
- * @brief Pack a ping_tc 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 Timestamp to identify when it was sent.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ping_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_TC_LEN);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PING_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-}
-
-/**
- * @brief Encode a ping_tc 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_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ping_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_tc_t* ping_tc)
-{
- return mavlink_msg_ping_tc_pack(system_id, component_id, msg, ping_tc->timestamp);
-}
-
-/**
- * @brief Encode a ping_tc 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_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ping_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ping_tc_t* ping_tc)
-{
- return mavlink_msg_ping_tc_pack_chan(system_id, component_id, chan, msg, ping_tc->timestamp);
-}
-
-/**
- * @brief Send a ping_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp Timestamp to identify when it was sent.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ping_tc_send(mavlink_channel_t chan, uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, buf, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)&packet, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a ping_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ping_tc_send_struct(mavlink_channel_t chan, const mavlink_ping_tc_t* ping_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ping_tc_send(chan, ping_tc->timestamp);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)ping_tc, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_PING_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, buf, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#else
- mavlink_ping_tc_t *packet = (mavlink_ping_tc_t *)msgbuf;
- packet->timestamp = timestamp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)packet, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE PING_TC UNPACKING
-
-
-/**
- * @brief Get field timestamp from ping_tc message
- *
- * @return Timestamp to identify when it was sent.
- */
-static inline uint64_t mavlink_msg_ping_tc_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Decode a ping_tc message into a struct
- *
- * @param msg The message to decode
- * @param ping_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ping_tc_decode(const mavlink_message_t* msg, mavlink_ping_tc_t* ping_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ping_tc->timestamp = mavlink_msg_ping_tc_get_timestamp(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_PING_TC_LEN? msg->len : MAVLINK_MSG_ID_PING_TC_LEN;
- memset(ping_tc, 0, MAVLINK_MSG_ID_PING_TC_LEN);
- memcpy(ping_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_raw_event_tc.h b/mavlink_lib/lynx/mavlink_msg_raw_event_tc.h
deleted file mode 100644
index 7b95415ba088d3fd4527319f3ee22c84c5754eb9..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_raw_event_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE RAW_EVENT_TC PACKING
-
-#define MAVLINK_MSG_ID_RAW_EVENT_TC 80
-
-MAVPACKED(
-typedef struct __mavlink_raw_event_tc_t {
- uint8_t Event_id; /*< Id of the event to be posted.*/
- uint8_t Topic_id; /*< Id of the topic to which the event should be posted.*/
-}) mavlink_raw_event_tc_t;
-
-#define MAVLINK_MSG_ID_RAW_EVENT_TC_LEN 2
-#define MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN 2
-#define MAVLINK_MSG_ID_80_LEN 2
-#define MAVLINK_MSG_ID_80_MIN_LEN 2
-
-#define MAVLINK_MSG_ID_RAW_EVENT_TC_CRC 134
-#define MAVLINK_MSG_ID_80_CRC 134
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_RAW_EVENT_TC { \
- 80, \
- "RAW_EVENT_TC", \
- 2, \
- { { "Event_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_raw_event_tc_t, Event_id) }, \
- { "Topic_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_raw_event_tc_t, Topic_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_RAW_EVENT_TC { \
- "RAW_EVENT_TC", \
- 2, \
- { { "Event_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_raw_event_tc_t, Event_id) }, \
- { "Topic_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_raw_event_tc_t, Topic_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a raw_event_tc 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 Event_id Id of the event to be posted.
- * @param Topic_id Id of the topic to which the event should be posted.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_raw_event_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t Event_id, uint8_t Topic_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_EVENT_TC_LEN];
- _mav_put_uint8_t(buf, 0, Event_id);
- _mav_put_uint8_t(buf, 1, Topic_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#else
- mavlink_raw_event_tc_t packet;
- packet.Event_id = Event_id;
- packet.Topic_id = Topic_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RAW_EVENT_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-}
-
-/**
- * @brief Pack a raw_event_tc 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 Event_id Id of the event to be posted.
- * @param Topic_id Id of the topic to which the event should be posted.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_raw_event_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t Event_id,uint8_t Topic_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_EVENT_TC_LEN];
- _mav_put_uint8_t(buf, 0, Event_id);
- _mav_put_uint8_t(buf, 1, Topic_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#else
- mavlink_raw_event_tc_t packet;
- packet.Event_id = Event_id;
- packet.Topic_id = Topic_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RAW_EVENT_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-}
-
-/**
- * @brief Encode a raw_event_tc 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_event_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_raw_event_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_event_tc_t* raw_event_tc)
-{
- return mavlink_msg_raw_event_tc_pack(system_id, component_id, msg, raw_event_tc->Event_id, raw_event_tc->Topic_id);
-}
-
-/**
- * @brief Encode a raw_event_tc 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_event_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_raw_event_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_event_tc_t* raw_event_tc)
-{
- return mavlink_msg_raw_event_tc_pack_chan(system_id, component_id, chan, msg, raw_event_tc->Event_id, raw_event_tc->Topic_id);
-}
-
-/**
- * @brief Send a raw_event_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param Event_id Id of the event to be posted.
- * @param Topic_id Id of the topic to which the event should be posted.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_raw_event_tc_send(mavlink_channel_t chan, uint8_t Event_id, uint8_t Topic_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_EVENT_TC_LEN];
- _mav_put_uint8_t(buf, 0, Event_id);
- _mav_put_uint8_t(buf, 1, Topic_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, buf, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#else
- mavlink_raw_event_tc_t packet;
- packet.Event_id = Event_id;
- packet.Topic_id = Topic_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, (const char *)&packet, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a raw_event_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_raw_event_tc_send_struct(mavlink_channel_t chan, const mavlink_raw_event_tc_t* raw_event_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_raw_event_tc_send(chan, raw_event_tc->Event_id, raw_event_tc->Topic_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, (const char *)raw_event_tc, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_RAW_EVENT_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_event_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t Event_id, uint8_t Topic_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, Event_id);
- _mav_put_uint8_t(buf, 1, Topic_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, buf, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#else
- mavlink_raw_event_tc_t *packet = (mavlink_raw_event_tc_t *)msgbuf;
- packet->Event_id = Event_id;
- packet->Topic_id = Topic_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, (const char *)packet, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE RAW_EVENT_TC UNPACKING
-
-
-/**
- * @brief Get field Event_id from raw_event_tc message
- *
- * @return Id of the event to be posted.
- */
-static inline uint8_t mavlink_msg_raw_event_tc_get_Event_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field Topic_id from raw_event_tc message
- *
- * @return Id of the topic to which the event should be posted.
- */
-static inline uint8_t mavlink_msg_raw_event_tc_get_Topic_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Decode a raw_event_tc message into a struct
- *
- * @param msg The message to decode
- * @param raw_event_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_raw_event_tc_decode(const mavlink_message_t* msg, mavlink_raw_event_tc_t* raw_event_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- raw_event_tc->Event_id = mavlink_msg_raw_event_tc_get_Event_id(msg);
- raw_event_tc->Topic_id = mavlink_msg_raw_event_tc_get_Topic_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_RAW_EVENT_TC_LEN? msg->len : MAVLINK_MSG_ID_RAW_EVENT_TC_LEN;
- memset(raw_event_tc, 0, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
- memcpy(raw_event_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_sensors_tm.h b/mavlink_lib/lynx/mavlink_msg_sensors_tm.h
deleted file mode 100644
index 2017e9e5c3b5e73cce8fd2ca119ede32fcf02e35..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_sensors_tm.h
+++ /dev/null
@@ -1,838 +0,0 @@
-#pragma once
-// MESSAGE SENSORS_TM PACKING
-
-#define MAVLINK_MSG_ID_SENSORS_TM 184
-
-MAVPACKED(
-typedef struct __mavlink_sensors_tm_t {
- uint64_t timestamp; /*< [ms] */
- float bmx160_acc_x; /*< [m/s^2] */
- float bmx160_acc_y; /*< [m/s^2] */
- float bmx160_acc_z; /*< [m/s^2] */
- float bmx160_gyro_x; /*< [rad/s] */
- float bmx160_gyro_y; /*< [rad/s] */
- float bmx160_gyro_z; /*< [rad/s] */
- float bmx160_mag_x; /*< [uT] */
- float bmx160_mag_y; /*< [uT] */
- float bmx160_mag_z; /*< [uT] */
- float bmx160_temp; /*< [deg C] */
- float ms5803_press; /*< [Pa] */
- float ms5803_temp; /*< [deg C] */
- float dpl_press; /*< [Pa] */
- float pitot_press; /*< [Pa] */
- float static_press; /*< [Pa] */
- float lis3mdl_mag_x; /*< [uT] */
- float lis3mdl_mag_y; /*< [uT] */
- float lis3mdl_mag_z; /*< [uT] */
- float lis3mdl_temp; /*< [uT] */
- float gps_lat; /*< [deg] */
- float gps_lon; /*< [deg] */
- float gps_alt; /*< [m] */
- float vbat; /*< [V] */
- float vsupply_5v; /*< [V] */
- uint8_t gps_fix; /*< */
-}) mavlink_sensors_tm_t;
-
-#define MAVLINK_MSG_ID_SENSORS_TM_LEN 105
-#define MAVLINK_MSG_ID_SENSORS_TM_MIN_LEN 105
-#define MAVLINK_MSG_ID_184_LEN 105
-#define MAVLINK_MSG_ID_184_MIN_LEN 105
-
-#define MAVLINK_MSG_ID_SENSORS_TM_CRC 230
-#define MAVLINK_MSG_ID_184_CRC 230
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SENSORS_TM { \
- 184, \
- "SENSORS_TM", \
- 26, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_sensors_tm_t, timestamp) }, \
- { "bmx160_acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sensors_tm_t, bmx160_acc_x) }, \
- { "bmx160_acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sensors_tm_t, bmx160_acc_y) }, \
- { "bmx160_acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sensors_tm_t, bmx160_acc_z) }, \
- { "bmx160_gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sensors_tm_t, bmx160_gyro_x) }, \
- { "bmx160_gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sensors_tm_t, bmx160_gyro_y) }, \
- { "bmx160_gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sensors_tm_t, bmx160_gyro_z) }, \
- { "bmx160_mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sensors_tm_t, bmx160_mag_x) }, \
- { "bmx160_mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sensors_tm_t, bmx160_mag_y) }, \
- { "bmx160_mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sensors_tm_t, bmx160_mag_z) }, \
- { "bmx160_temp", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_sensors_tm_t, bmx160_temp) }, \
- { "ms5803_press", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_sensors_tm_t, ms5803_press) }, \
- { "ms5803_temp", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_sensors_tm_t, ms5803_temp) }, \
- { "dpl_press", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_sensors_tm_t, dpl_press) }, \
- { "pitot_press", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_sensors_tm_t, pitot_press) }, \
- { "static_press", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_sensors_tm_t, static_press) }, \
- { "lis3mdl_mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_sensors_tm_t, lis3mdl_mag_x) }, \
- { "lis3mdl_mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_sensors_tm_t, lis3mdl_mag_y) }, \
- { "lis3mdl_mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_sensors_tm_t, lis3mdl_mag_z) }, \
- { "lis3mdl_temp", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_sensors_tm_t, lis3mdl_temp) }, \
- { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_sensors_tm_t, gps_lat) }, \
- { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_sensors_tm_t, gps_lon) }, \
- { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_sensors_tm_t, gps_alt) }, \
- { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 104, offsetof(mavlink_sensors_tm_t, gps_fix) }, \
- { "vbat", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_sensors_tm_t, vbat) }, \
- { "vsupply_5v", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_sensors_tm_t, vsupply_5v) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SENSORS_TM { \
- "SENSORS_TM", \
- 26, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_sensors_tm_t, timestamp) }, \
- { "bmx160_acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sensors_tm_t, bmx160_acc_x) }, \
- { "bmx160_acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sensors_tm_t, bmx160_acc_y) }, \
- { "bmx160_acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sensors_tm_t, bmx160_acc_z) }, \
- { "bmx160_gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sensors_tm_t, bmx160_gyro_x) }, \
- { "bmx160_gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sensors_tm_t, bmx160_gyro_y) }, \
- { "bmx160_gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sensors_tm_t, bmx160_gyro_z) }, \
- { "bmx160_mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sensors_tm_t, bmx160_mag_x) }, \
- { "bmx160_mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sensors_tm_t, bmx160_mag_y) }, \
- { "bmx160_mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sensors_tm_t, bmx160_mag_z) }, \
- { "bmx160_temp", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_sensors_tm_t, bmx160_temp) }, \
- { "ms5803_press", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_sensors_tm_t, ms5803_press) }, \
- { "ms5803_temp", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_sensors_tm_t, ms5803_temp) }, \
- { "dpl_press", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_sensors_tm_t, dpl_press) }, \
- { "pitot_press", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_sensors_tm_t, pitot_press) }, \
- { "static_press", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_sensors_tm_t, static_press) }, \
- { "lis3mdl_mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_sensors_tm_t, lis3mdl_mag_x) }, \
- { "lis3mdl_mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_sensors_tm_t, lis3mdl_mag_y) }, \
- { "lis3mdl_mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_sensors_tm_t, lis3mdl_mag_z) }, \
- { "lis3mdl_temp", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_sensors_tm_t, lis3mdl_temp) }, \
- { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_sensors_tm_t, gps_lat) }, \
- { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_sensors_tm_t, gps_lon) }, \
- { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_sensors_tm_t, gps_alt) }, \
- { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 104, offsetof(mavlink_sensors_tm_t, gps_fix) }, \
- { "vbat", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_sensors_tm_t, vbat) }, \
- { "vsupply_5v", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_sensors_tm_t, vsupply_5v) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a sensors_tm 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]
- * @param bmx160_acc_x [m/s^2]
- * @param bmx160_acc_y [m/s^2]
- * @param bmx160_acc_z [m/s^2]
- * @param bmx160_gyro_x [rad/s]
- * @param bmx160_gyro_y [rad/s]
- * @param bmx160_gyro_z [rad/s]
- * @param bmx160_mag_x [uT]
- * @param bmx160_mag_y [uT]
- * @param bmx160_mag_z [uT]
- * @param bmx160_temp [deg C]
- * @param ms5803_press [Pa]
- * @param ms5803_temp [deg C]
- * @param dpl_press [Pa]
- * @param pitot_press [Pa]
- * @param static_press [Pa]
- * @param lis3mdl_mag_x [uT]
- * @param lis3mdl_mag_y [uT]
- * @param lis3mdl_mag_z [uT]
- * @param lis3mdl_temp [uT]
- * @param gps_lat [deg]
- * @param gps_lon [deg]
- * @param gps_alt [m]
- * @param gps_fix
- * @param vbat [V]
- * @param vsupply_5v [V]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sensors_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, float bmx160_acc_x, float bmx160_acc_y, float bmx160_acc_z, float bmx160_gyro_x, float bmx160_gyro_y, float bmx160_gyro_z, float bmx160_mag_x, float bmx160_mag_y, float bmx160_mag_z, float bmx160_temp, float ms5803_press, float ms5803_temp, float dpl_press, float pitot_press, float static_press, float lis3mdl_mag_x, float lis3mdl_mag_y, float lis3mdl_mag_z, float lis3mdl_temp, float gps_lat, float gps_lon, float gps_alt, uint8_t gps_fix, float vbat, float vsupply_5v)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSORS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, bmx160_acc_x);
- _mav_put_float(buf, 12, bmx160_acc_y);
- _mav_put_float(buf, 16, bmx160_acc_z);
- _mav_put_float(buf, 20, bmx160_gyro_x);
- _mav_put_float(buf, 24, bmx160_gyro_y);
- _mav_put_float(buf, 28, bmx160_gyro_z);
- _mav_put_float(buf, 32, bmx160_mag_x);
- _mav_put_float(buf, 36, bmx160_mag_y);
- _mav_put_float(buf, 40, bmx160_mag_z);
- _mav_put_float(buf, 44, bmx160_temp);
- _mav_put_float(buf, 48, ms5803_press);
- _mav_put_float(buf, 52, ms5803_temp);
- _mav_put_float(buf, 56, dpl_press);
- _mav_put_float(buf, 60, pitot_press);
- _mav_put_float(buf, 64, static_press);
- _mav_put_float(buf, 68, lis3mdl_mag_x);
- _mav_put_float(buf, 72, lis3mdl_mag_y);
- _mav_put_float(buf, 76, lis3mdl_mag_z);
- _mav_put_float(buf, 80, lis3mdl_temp);
- _mav_put_float(buf, 84, gps_lat);
- _mav_put_float(buf, 88, gps_lon);
- _mav_put_float(buf, 92, gps_alt);
- _mav_put_float(buf, 96, vbat);
- _mav_put_float(buf, 100, vsupply_5v);
- _mav_put_uint8_t(buf, 104, gps_fix);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSORS_TM_LEN);
-#else
- mavlink_sensors_tm_t packet;
- packet.timestamp = timestamp;
- packet.bmx160_acc_x = bmx160_acc_x;
- packet.bmx160_acc_y = bmx160_acc_y;
- packet.bmx160_acc_z = bmx160_acc_z;
- packet.bmx160_gyro_x = bmx160_gyro_x;
- packet.bmx160_gyro_y = bmx160_gyro_y;
- packet.bmx160_gyro_z = bmx160_gyro_z;
- packet.bmx160_mag_x = bmx160_mag_x;
- packet.bmx160_mag_y = bmx160_mag_y;
- packet.bmx160_mag_z = bmx160_mag_z;
- packet.bmx160_temp = bmx160_temp;
- packet.ms5803_press = ms5803_press;
- packet.ms5803_temp = ms5803_temp;
- packet.dpl_press = dpl_press;
- packet.pitot_press = pitot_press;
- packet.static_press = static_press;
- packet.lis3mdl_mag_x = lis3mdl_mag_x;
- packet.lis3mdl_mag_y = lis3mdl_mag_y;
- packet.lis3mdl_mag_z = lis3mdl_mag_z;
- packet.lis3mdl_temp = lis3mdl_temp;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.vbat = vbat;
- packet.vsupply_5v = vsupply_5v;
- packet.gps_fix = gps_fix;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSORS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SENSORS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SENSORS_TM_MIN_LEN, MAVLINK_MSG_ID_SENSORS_TM_LEN, MAVLINK_MSG_ID_SENSORS_TM_CRC);
-}
-
-/**
- * @brief Pack a sensors_tm 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]
- * @param bmx160_acc_x [m/s^2]
- * @param bmx160_acc_y [m/s^2]
- * @param bmx160_acc_z [m/s^2]
- * @param bmx160_gyro_x [rad/s]
- * @param bmx160_gyro_y [rad/s]
- * @param bmx160_gyro_z [rad/s]
- * @param bmx160_mag_x [uT]
- * @param bmx160_mag_y [uT]
- * @param bmx160_mag_z [uT]
- * @param bmx160_temp [deg C]
- * @param ms5803_press [Pa]
- * @param ms5803_temp [deg C]
- * @param dpl_press [Pa]
- * @param pitot_press [Pa]
- * @param static_press [Pa]
- * @param lis3mdl_mag_x [uT]
- * @param lis3mdl_mag_y [uT]
- * @param lis3mdl_mag_z [uT]
- * @param lis3mdl_temp [uT]
- * @param gps_lat [deg]
- * @param gps_lon [deg]
- * @param gps_alt [m]
- * @param gps_fix
- * @param vbat [V]
- * @param vsupply_5v [V]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sensors_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,float bmx160_acc_x,float bmx160_acc_y,float bmx160_acc_z,float bmx160_gyro_x,float bmx160_gyro_y,float bmx160_gyro_z,float bmx160_mag_x,float bmx160_mag_y,float bmx160_mag_z,float bmx160_temp,float ms5803_press,float ms5803_temp,float dpl_press,float pitot_press,float static_press,float lis3mdl_mag_x,float lis3mdl_mag_y,float lis3mdl_mag_z,float lis3mdl_temp,float gps_lat,float gps_lon,float gps_alt,uint8_t gps_fix,float vbat,float vsupply_5v)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSORS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, bmx160_acc_x);
- _mav_put_float(buf, 12, bmx160_acc_y);
- _mav_put_float(buf, 16, bmx160_acc_z);
- _mav_put_float(buf, 20, bmx160_gyro_x);
- _mav_put_float(buf, 24, bmx160_gyro_y);
- _mav_put_float(buf, 28, bmx160_gyro_z);
- _mav_put_float(buf, 32, bmx160_mag_x);
- _mav_put_float(buf, 36, bmx160_mag_y);
- _mav_put_float(buf, 40, bmx160_mag_z);
- _mav_put_float(buf, 44, bmx160_temp);
- _mav_put_float(buf, 48, ms5803_press);
- _mav_put_float(buf, 52, ms5803_temp);
- _mav_put_float(buf, 56, dpl_press);
- _mav_put_float(buf, 60, pitot_press);
- _mav_put_float(buf, 64, static_press);
- _mav_put_float(buf, 68, lis3mdl_mag_x);
- _mav_put_float(buf, 72, lis3mdl_mag_y);
- _mav_put_float(buf, 76, lis3mdl_mag_z);
- _mav_put_float(buf, 80, lis3mdl_temp);
- _mav_put_float(buf, 84, gps_lat);
- _mav_put_float(buf, 88, gps_lon);
- _mav_put_float(buf, 92, gps_alt);
- _mav_put_float(buf, 96, vbat);
- _mav_put_float(buf, 100, vsupply_5v);
- _mav_put_uint8_t(buf, 104, gps_fix);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSORS_TM_LEN);
-#else
- mavlink_sensors_tm_t packet;
- packet.timestamp = timestamp;
- packet.bmx160_acc_x = bmx160_acc_x;
- packet.bmx160_acc_y = bmx160_acc_y;
- packet.bmx160_acc_z = bmx160_acc_z;
- packet.bmx160_gyro_x = bmx160_gyro_x;
- packet.bmx160_gyro_y = bmx160_gyro_y;
- packet.bmx160_gyro_z = bmx160_gyro_z;
- packet.bmx160_mag_x = bmx160_mag_x;
- packet.bmx160_mag_y = bmx160_mag_y;
- packet.bmx160_mag_z = bmx160_mag_z;
- packet.bmx160_temp = bmx160_temp;
- packet.ms5803_press = ms5803_press;
- packet.ms5803_temp = ms5803_temp;
- packet.dpl_press = dpl_press;
- packet.pitot_press = pitot_press;
- packet.static_press = static_press;
- packet.lis3mdl_mag_x = lis3mdl_mag_x;
- packet.lis3mdl_mag_y = lis3mdl_mag_y;
- packet.lis3mdl_mag_z = lis3mdl_mag_z;
- packet.lis3mdl_temp = lis3mdl_temp;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.vbat = vbat;
- packet.vsupply_5v = vsupply_5v;
- packet.gps_fix = gps_fix;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSORS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SENSORS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SENSORS_TM_MIN_LEN, MAVLINK_MSG_ID_SENSORS_TM_LEN, MAVLINK_MSG_ID_SENSORS_TM_CRC);
-}
-
-/**
- * @brief Encode a sensors_tm 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 sensors_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sensors_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensors_tm_t* sensors_tm)
-{
- return mavlink_msg_sensors_tm_pack(system_id, component_id, msg, sensors_tm->timestamp, sensors_tm->bmx160_acc_x, sensors_tm->bmx160_acc_y, sensors_tm->bmx160_acc_z, sensors_tm->bmx160_gyro_x, sensors_tm->bmx160_gyro_y, sensors_tm->bmx160_gyro_z, sensors_tm->bmx160_mag_x, sensors_tm->bmx160_mag_y, sensors_tm->bmx160_mag_z, sensors_tm->bmx160_temp, sensors_tm->ms5803_press, sensors_tm->ms5803_temp, sensors_tm->dpl_press, sensors_tm->pitot_press, sensors_tm->static_press, sensors_tm->lis3mdl_mag_x, sensors_tm->lis3mdl_mag_y, sensors_tm->lis3mdl_mag_z, sensors_tm->lis3mdl_temp, sensors_tm->gps_lat, sensors_tm->gps_lon, sensors_tm->gps_alt, sensors_tm->gps_fix, sensors_tm->vbat, sensors_tm->vsupply_5v);
-}
-
-/**
- * @brief Encode a sensors_tm 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 sensors_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sensors_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sensors_tm_t* sensors_tm)
-{
- return mavlink_msg_sensors_tm_pack_chan(system_id, component_id, chan, msg, sensors_tm->timestamp, sensors_tm->bmx160_acc_x, sensors_tm->bmx160_acc_y, sensors_tm->bmx160_acc_z, sensors_tm->bmx160_gyro_x, sensors_tm->bmx160_gyro_y, sensors_tm->bmx160_gyro_z, sensors_tm->bmx160_mag_x, sensors_tm->bmx160_mag_y, sensors_tm->bmx160_mag_z, sensors_tm->bmx160_temp, sensors_tm->ms5803_press, sensors_tm->ms5803_temp, sensors_tm->dpl_press, sensors_tm->pitot_press, sensors_tm->static_press, sensors_tm->lis3mdl_mag_x, sensors_tm->lis3mdl_mag_y, sensors_tm->lis3mdl_mag_z, sensors_tm->lis3mdl_temp, sensors_tm->gps_lat, sensors_tm->gps_lon, sensors_tm->gps_alt, sensors_tm->gps_fix, sensors_tm->vbat, sensors_tm->vsupply_5v);
-}
-
-/**
- * @brief Send a sensors_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [ms]
- * @param bmx160_acc_x [m/s^2]
- * @param bmx160_acc_y [m/s^2]
- * @param bmx160_acc_z [m/s^2]
- * @param bmx160_gyro_x [rad/s]
- * @param bmx160_gyro_y [rad/s]
- * @param bmx160_gyro_z [rad/s]
- * @param bmx160_mag_x [uT]
- * @param bmx160_mag_y [uT]
- * @param bmx160_mag_z [uT]
- * @param bmx160_temp [deg C]
- * @param ms5803_press [Pa]
- * @param ms5803_temp [deg C]
- * @param dpl_press [Pa]
- * @param pitot_press [Pa]
- * @param static_press [Pa]
- * @param lis3mdl_mag_x [uT]
- * @param lis3mdl_mag_y [uT]
- * @param lis3mdl_mag_z [uT]
- * @param lis3mdl_temp [uT]
- * @param gps_lat [deg]
- * @param gps_lon [deg]
- * @param gps_alt [m]
- * @param gps_fix
- * @param vbat [V]
- * @param vsupply_5v [V]
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_sensors_tm_send(mavlink_channel_t chan, uint64_t timestamp, float bmx160_acc_x, float bmx160_acc_y, float bmx160_acc_z, float bmx160_gyro_x, float bmx160_gyro_y, float bmx160_gyro_z, float bmx160_mag_x, float bmx160_mag_y, float bmx160_mag_z, float bmx160_temp, float ms5803_press, float ms5803_temp, float dpl_press, float pitot_press, float static_press, float lis3mdl_mag_x, float lis3mdl_mag_y, float lis3mdl_mag_z, float lis3mdl_temp, float gps_lat, float gps_lon, float gps_alt, uint8_t gps_fix, float vbat, float vsupply_5v)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSORS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, bmx160_acc_x);
- _mav_put_float(buf, 12, bmx160_acc_y);
- _mav_put_float(buf, 16, bmx160_acc_z);
- _mav_put_float(buf, 20, bmx160_gyro_x);
- _mav_put_float(buf, 24, bmx160_gyro_y);
- _mav_put_float(buf, 28, bmx160_gyro_z);
- _mav_put_float(buf, 32, bmx160_mag_x);
- _mav_put_float(buf, 36, bmx160_mag_y);
- _mav_put_float(buf, 40, bmx160_mag_z);
- _mav_put_float(buf, 44, bmx160_temp);
- _mav_put_float(buf, 48, ms5803_press);
- _mav_put_float(buf, 52, ms5803_temp);
- _mav_put_float(buf, 56, dpl_press);
- _mav_put_float(buf, 60, pitot_press);
- _mav_put_float(buf, 64, static_press);
- _mav_put_float(buf, 68, lis3mdl_mag_x);
- _mav_put_float(buf, 72, lis3mdl_mag_y);
- _mav_put_float(buf, 76, lis3mdl_mag_z);
- _mav_put_float(buf, 80, lis3mdl_temp);
- _mav_put_float(buf, 84, gps_lat);
- _mav_put_float(buf, 88, gps_lon);
- _mav_put_float(buf, 92, gps_alt);
- _mav_put_float(buf, 96, vbat);
- _mav_put_float(buf, 100, vsupply_5v);
- _mav_put_uint8_t(buf, 104, gps_fix);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSORS_TM, buf, MAVLINK_MSG_ID_SENSORS_TM_MIN_LEN, MAVLINK_MSG_ID_SENSORS_TM_LEN, MAVLINK_MSG_ID_SENSORS_TM_CRC);
-#else
- mavlink_sensors_tm_t packet;
- packet.timestamp = timestamp;
- packet.bmx160_acc_x = bmx160_acc_x;
- packet.bmx160_acc_y = bmx160_acc_y;
- packet.bmx160_acc_z = bmx160_acc_z;
- packet.bmx160_gyro_x = bmx160_gyro_x;
- packet.bmx160_gyro_y = bmx160_gyro_y;
- packet.bmx160_gyro_z = bmx160_gyro_z;
- packet.bmx160_mag_x = bmx160_mag_x;
- packet.bmx160_mag_y = bmx160_mag_y;
- packet.bmx160_mag_z = bmx160_mag_z;
- packet.bmx160_temp = bmx160_temp;
- packet.ms5803_press = ms5803_press;
- packet.ms5803_temp = ms5803_temp;
- packet.dpl_press = dpl_press;
- packet.pitot_press = pitot_press;
- packet.static_press = static_press;
- packet.lis3mdl_mag_x = lis3mdl_mag_x;
- packet.lis3mdl_mag_y = lis3mdl_mag_y;
- packet.lis3mdl_mag_z = lis3mdl_mag_z;
- packet.lis3mdl_temp = lis3mdl_temp;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.vbat = vbat;
- packet.vsupply_5v = vsupply_5v;
- packet.gps_fix = gps_fix;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSORS_TM, (const char *)&packet, MAVLINK_MSG_ID_SENSORS_TM_MIN_LEN, MAVLINK_MSG_ID_SENSORS_TM_LEN, MAVLINK_MSG_ID_SENSORS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a sensors_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_sensors_tm_send_struct(mavlink_channel_t chan, const mavlink_sensors_tm_t* sensors_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_sensors_tm_send(chan, sensors_tm->timestamp, sensors_tm->bmx160_acc_x, sensors_tm->bmx160_acc_y, sensors_tm->bmx160_acc_z, sensors_tm->bmx160_gyro_x, sensors_tm->bmx160_gyro_y, sensors_tm->bmx160_gyro_z, sensors_tm->bmx160_mag_x, sensors_tm->bmx160_mag_y, sensors_tm->bmx160_mag_z, sensors_tm->bmx160_temp, sensors_tm->ms5803_press, sensors_tm->ms5803_temp, sensors_tm->dpl_press, sensors_tm->pitot_press, sensors_tm->static_press, sensors_tm->lis3mdl_mag_x, sensors_tm->lis3mdl_mag_y, sensors_tm->lis3mdl_mag_z, sensors_tm->lis3mdl_temp, sensors_tm->gps_lat, sensors_tm->gps_lon, sensors_tm->gps_alt, sensors_tm->gps_fix, sensors_tm->vbat, sensors_tm->vsupply_5v);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSORS_TM, (const char *)sensors_tm, MAVLINK_MSG_ID_SENSORS_TM_MIN_LEN, MAVLINK_MSG_ID_SENSORS_TM_LEN, MAVLINK_MSG_ID_SENSORS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SENSORS_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_sensors_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float bmx160_acc_x, float bmx160_acc_y, float bmx160_acc_z, float bmx160_gyro_x, float bmx160_gyro_y, float bmx160_gyro_z, float bmx160_mag_x, float bmx160_mag_y, float bmx160_mag_z, float bmx160_temp, float ms5803_press, float ms5803_temp, float dpl_press, float pitot_press, float static_press, float lis3mdl_mag_x, float lis3mdl_mag_y, float lis3mdl_mag_z, float lis3mdl_temp, float gps_lat, float gps_lon, float gps_alt, uint8_t gps_fix, float vbat, float vsupply_5v)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, bmx160_acc_x);
- _mav_put_float(buf, 12, bmx160_acc_y);
- _mav_put_float(buf, 16, bmx160_acc_z);
- _mav_put_float(buf, 20, bmx160_gyro_x);
- _mav_put_float(buf, 24, bmx160_gyro_y);
- _mav_put_float(buf, 28, bmx160_gyro_z);
- _mav_put_float(buf, 32, bmx160_mag_x);
- _mav_put_float(buf, 36, bmx160_mag_y);
- _mav_put_float(buf, 40, bmx160_mag_z);
- _mav_put_float(buf, 44, bmx160_temp);
- _mav_put_float(buf, 48, ms5803_press);
- _mav_put_float(buf, 52, ms5803_temp);
- _mav_put_float(buf, 56, dpl_press);
- _mav_put_float(buf, 60, pitot_press);
- _mav_put_float(buf, 64, static_press);
- _mav_put_float(buf, 68, lis3mdl_mag_x);
- _mav_put_float(buf, 72, lis3mdl_mag_y);
- _mav_put_float(buf, 76, lis3mdl_mag_z);
- _mav_put_float(buf, 80, lis3mdl_temp);
- _mav_put_float(buf, 84, gps_lat);
- _mav_put_float(buf, 88, gps_lon);
- _mav_put_float(buf, 92, gps_alt);
- _mav_put_float(buf, 96, vbat);
- _mav_put_float(buf, 100, vsupply_5v);
- _mav_put_uint8_t(buf, 104, gps_fix);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSORS_TM, buf, MAVLINK_MSG_ID_SENSORS_TM_MIN_LEN, MAVLINK_MSG_ID_SENSORS_TM_LEN, MAVLINK_MSG_ID_SENSORS_TM_CRC);
-#else
- mavlink_sensors_tm_t *packet = (mavlink_sensors_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->bmx160_acc_x = bmx160_acc_x;
- packet->bmx160_acc_y = bmx160_acc_y;
- packet->bmx160_acc_z = bmx160_acc_z;
- packet->bmx160_gyro_x = bmx160_gyro_x;
- packet->bmx160_gyro_y = bmx160_gyro_y;
- packet->bmx160_gyro_z = bmx160_gyro_z;
- packet->bmx160_mag_x = bmx160_mag_x;
- packet->bmx160_mag_y = bmx160_mag_y;
- packet->bmx160_mag_z = bmx160_mag_z;
- packet->bmx160_temp = bmx160_temp;
- packet->ms5803_press = ms5803_press;
- packet->ms5803_temp = ms5803_temp;
- packet->dpl_press = dpl_press;
- packet->pitot_press = pitot_press;
- packet->static_press = static_press;
- packet->lis3mdl_mag_x = lis3mdl_mag_x;
- packet->lis3mdl_mag_y = lis3mdl_mag_y;
- packet->lis3mdl_mag_z = lis3mdl_mag_z;
- packet->lis3mdl_temp = lis3mdl_temp;
- packet->gps_lat = gps_lat;
- packet->gps_lon = gps_lon;
- packet->gps_alt = gps_alt;
- packet->vbat = vbat;
- packet->vsupply_5v = vsupply_5v;
- packet->gps_fix = gps_fix;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSORS_TM, (const char *)packet, MAVLINK_MSG_ID_SENSORS_TM_MIN_LEN, MAVLINK_MSG_ID_SENSORS_TM_LEN, MAVLINK_MSG_ID_SENSORS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SENSORS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from sensors_tm message
- *
- * @return [ms]
- */
-static inline uint64_t mavlink_msg_sensors_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field bmx160_acc_x from sensors_tm message
- *
- * @return [m/s^2]
- */
-static inline float mavlink_msg_sensors_tm_get_bmx160_acc_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field bmx160_acc_y from sensors_tm message
- *
- * @return [m/s^2]
- */
-static inline float mavlink_msg_sensors_tm_get_bmx160_acc_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field bmx160_acc_z from sensors_tm message
- *
- * @return [m/s^2]
- */
-static inline float mavlink_msg_sensors_tm_get_bmx160_acc_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field bmx160_gyro_x from sensors_tm message
- *
- * @return [rad/s]
- */
-static inline float mavlink_msg_sensors_tm_get_bmx160_gyro_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field bmx160_gyro_y from sensors_tm message
- *
- * @return [rad/s]
- */
-static inline float mavlink_msg_sensors_tm_get_bmx160_gyro_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field bmx160_gyro_z from sensors_tm message
- *
- * @return [rad/s]
- */
-static inline float mavlink_msg_sensors_tm_get_bmx160_gyro_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field bmx160_mag_x from sensors_tm message
- *
- * @return [uT]
- */
-static inline float mavlink_msg_sensors_tm_get_bmx160_mag_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field bmx160_mag_y from sensors_tm message
- *
- * @return [uT]
- */
-static inline float mavlink_msg_sensors_tm_get_bmx160_mag_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field bmx160_mag_z from sensors_tm message
- *
- * @return [uT]
- */
-static inline float mavlink_msg_sensors_tm_get_bmx160_mag_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field bmx160_temp from sensors_tm message
- *
- * @return [deg C]
- */
-static inline float mavlink_msg_sensors_tm_get_bmx160_temp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field ms5803_press from sensors_tm message
- *
- * @return [Pa]
- */
-static inline float mavlink_msg_sensors_tm_get_ms5803_press(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field ms5803_temp from sensors_tm message
- *
- * @return [deg C]
- */
-static inline float mavlink_msg_sensors_tm_get_ms5803_temp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field dpl_press from sensors_tm message
- *
- * @return [Pa]
- */
-static inline float mavlink_msg_sensors_tm_get_dpl_press(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field pitot_press from sensors_tm message
- *
- * @return [Pa]
- */
-static inline float mavlink_msg_sensors_tm_get_pitot_press(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field static_press from sensors_tm message
- *
- * @return [Pa]
- */
-static inline float mavlink_msg_sensors_tm_get_static_press(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field lis3mdl_mag_x from sensors_tm message
- *
- * @return [uT]
- */
-static inline float mavlink_msg_sensors_tm_get_lis3mdl_mag_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field lis3mdl_mag_y from sensors_tm message
- *
- * @return [uT]
- */
-static inline float mavlink_msg_sensors_tm_get_lis3mdl_mag_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 72);
-}
-
-/**
- * @brief Get field lis3mdl_mag_z from sensors_tm message
- *
- * @return [uT]
- */
-static inline float mavlink_msg_sensors_tm_get_lis3mdl_mag_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 76);
-}
-
-/**
- * @brief Get field lis3mdl_temp from sensors_tm message
- *
- * @return [uT]
- */
-static inline float mavlink_msg_sensors_tm_get_lis3mdl_temp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 80);
-}
-
-/**
- * @brief Get field gps_lat from sensors_tm message
- *
- * @return [deg]
- */
-static inline float mavlink_msg_sensors_tm_get_gps_lat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 84);
-}
-
-/**
- * @brief Get field gps_lon from sensors_tm message
- *
- * @return [deg]
- */
-static inline float mavlink_msg_sensors_tm_get_gps_lon(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 88);
-}
-
-/**
- * @brief Get field gps_alt from sensors_tm message
- *
- * @return [m]
- */
-static inline float mavlink_msg_sensors_tm_get_gps_alt(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 92);
-}
-
-/**
- * @brief Get field gps_fix from sensors_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sensors_tm_get_gps_fix(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 104);
-}
-
-/**
- * @brief Get field vbat from sensors_tm message
- *
- * @return [V]
- */
-static inline float mavlink_msg_sensors_tm_get_vbat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 96);
-}
-
-/**
- * @brief Get field vsupply_5v from sensors_tm message
- *
- * @return [V]
- */
-static inline float mavlink_msg_sensors_tm_get_vsupply_5v(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 100);
-}
-
-/**
- * @brief Decode a sensors_tm message into a struct
- *
- * @param msg The message to decode
- * @param sensors_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_sensors_tm_decode(const mavlink_message_t* msg, mavlink_sensors_tm_t* sensors_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- sensors_tm->timestamp = mavlink_msg_sensors_tm_get_timestamp(msg);
- sensors_tm->bmx160_acc_x = mavlink_msg_sensors_tm_get_bmx160_acc_x(msg);
- sensors_tm->bmx160_acc_y = mavlink_msg_sensors_tm_get_bmx160_acc_y(msg);
- sensors_tm->bmx160_acc_z = mavlink_msg_sensors_tm_get_bmx160_acc_z(msg);
- sensors_tm->bmx160_gyro_x = mavlink_msg_sensors_tm_get_bmx160_gyro_x(msg);
- sensors_tm->bmx160_gyro_y = mavlink_msg_sensors_tm_get_bmx160_gyro_y(msg);
- sensors_tm->bmx160_gyro_z = mavlink_msg_sensors_tm_get_bmx160_gyro_z(msg);
- sensors_tm->bmx160_mag_x = mavlink_msg_sensors_tm_get_bmx160_mag_x(msg);
- sensors_tm->bmx160_mag_y = mavlink_msg_sensors_tm_get_bmx160_mag_y(msg);
- sensors_tm->bmx160_mag_z = mavlink_msg_sensors_tm_get_bmx160_mag_z(msg);
- sensors_tm->bmx160_temp = mavlink_msg_sensors_tm_get_bmx160_temp(msg);
- sensors_tm->ms5803_press = mavlink_msg_sensors_tm_get_ms5803_press(msg);
- sensors_tm->ms5803_temp = mavlink_msg_sensors_tm_get_ms5803_temp(msg);
- sensors_tm->dpl_press = mavlink_msg_sensors_tm_get_dpl_press(msg);
- sensors_tm->pitot_press = mavlink_msg_sensors_tm_get_pitot_press(msg);
- sensors_tm->static_press = mavlink_msg_sensors_tm_get_static_press(msg);
- sensors_tm->lis3mdl_mag_x = mavlink_msg_sensors_tm_get_lis3mdl_mag_x(msg);
- sensors_tm->lis3mdl_mag_y = mavlink_msg_sensors_tm_get_lis3mdl_mag_y(msg);
- sensors_tm->lis3mdl_mag_z = mavlink_msg_sensors_tm_get_lis3mdl_mag_z(msg);
- sensors_tm->lis3mdl_temp = mavlink_msg_sensors_tm_get_lis3mdl_temp(msg);
- sensors_tm->gps_lat = mavlink_msg_sensors_tm_get_gps_lat(msg);
- sensors_tm->gps_lon = mavlink_msg_sensors_tm_get_gps_lon(msg);
- sensors_tm->gps_alt = mavlink_msg_sensors_tm_get_gps_alt(msg);
- sensors_tm->vbat = mavlink_msg_sensors_tm_get_vbat(msg);
- sensors_tm->vsupply_5v = mavlink_msg_sensors_tm_get_vsupply_5v(msg);
- sensors_tm->gps_fix = mavlink_msg_sensors_tm_get_gps_fix(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SENSORS_TM_LEN? msg->len : MAVLINK_MSG_ID_SENSORS_TM_LEN;
- memset(sensors_tm, 0, MAVLINK_MSG_ID_SENSORS_TM_LEN);
- memcpy(sensors_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_set_aerobrake_angle_tc.h b/mavlink_lib/lynx/mavlink_msg_set_aerobrake_angle_tc.h
deleted file mode 100644
index db53e22c6f1ef4ba6faf8da2eaad5472250220e3..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_set_aerobrake_angle_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SET_AEROBRAKE_ANGLE_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC 22
-
-MAVPACKED(
-typedef struct __mavlink_set_aerobrake_angle_tc_t {
- float angle; /*< [deg] Aerobrake angle*/
-}) mavlink_set_aerobrake_angle_tc_t;
-
-#define MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_LEN 4
-#define MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_MIN_LEN 4
-#define MAVLINK_MSG_ID_22_LEN 4
-#define MAVLINK_MSG_ID_22_MIN_LEN 4
-
-#define MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_CRC 183
-#define MAVLINK_MSG_ID_22_CRC 183
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_AEROBRAKE_ANGLE_TC { \
- 22, \
- "SET_AEROBRAKE_ANGLE_TC", \
- 1, \
- { { "angle", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_aerobrake_angle_tc_t, angle) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_AEROBRAKE_ANGLE_TC { \
- "SET_AEROBRAKE_ANGLE_TC", \
- 1, \
- { { "angle", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_aerobrake_angle_tc_t, angle) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_aerobrake_angle_tc 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 angle [deg] Aerobrake angle
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_aerobrake_angle_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float angle)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_LEN];
- _mav_put_float(buf, 0, angle);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_LEN);
-#else
- mavlink_set_aerobrake_angle_tc_t packet;
- packet.angle = angle;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_CRC);
-}
-
-/**
- * @brief Pack a set_aerobrake_angle_tc 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 angle [deg] Aerobrake angle
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_aerobrake_angle_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float angle)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_LEN];
- _mav_put_float(buf, 0, angle);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_LEN);
-#else
- mavlink_set_aerobrake_angle_tc_t packet;
- packet.angle = angle;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_CRC);
-}
-
-/**
- * @brief Encode a set_aerobrake_angle_tc 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_aerobrake_angle_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_aerobrake_angle_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_aerobrake_angle_tc_t* set_aerobrake_angle_tc)
-{
- return mavlink_msg_set_aerobrake_angle_tc_pack(system_id, component_id, msg, set_aerobrake_angle_tc->angle);
-}
-
-/**
- * @brief Encode a set_aerobrake_angle_tc 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_aerobrake_angle_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_aerobrake_angle_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_aerobrake_angle_tc_t* set_aerobrake_angle_tc)
-{
- return mavlink_msg_set_aerobrake_angle_tc_pack_chan(system_id, component_id, chan, msg, set_aerobrake_angle_tc->angle);
-}
-
-/**
- * @brief Send a set_aerobrake_angle_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param angle [deg] Aerobrake angle
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_aerobrake_angle_tc_send(mavlink_channel_t chan, float angle)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_LEN];
- _mav_put_float(buf, 0, angle);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC, buf, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_CRC);
-#else
- mavlink_set_aerobrake_angle_tc_t packet;
- packet.angle = angle;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_aerobrake_angle_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_aerobrake_angle_tc_send_struct(mavlink_channel_t chan, const mavlink_set_aerobrake_angle_tc_t* set_aerobrake_angle_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_aerobrake_angle_tc_send(chan, set_aerobrake_angle_tc->angle);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC, (const char *)set_aerobrake_angle_tc, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_aerobrake_angle_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float angle)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, angle);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC, buf, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_CRC);
-#else
- mavlink_set_aerobrake_angle_tc_t *packet = (mavlink_set_aerobrake_angle_tc_t *)msgbuf;
- packet->angle = angle;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC, (const char *)packet, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_AEROBRAKE_ANGLE_TC UNPACKING
-
-
-/**
- * @brief Get field angle from set_aerobrake_angle_tc message
- *
- * @return [deg] Aerobrake angle
- */
-static inline float mavlink_msg_set_aerobrake_angle_tc_get_angle(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a set_aerobrake_angle_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_aerobrake_angle_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_aerobrake_angle_tc_decode(const mavlink_message_t* msg, mavlink_set_aerobrake_angle_tc_t* set_aerobrake_angle_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_aerobrake_angle_tc->angle = mavlink_msg_set_aerobrake_angle_tc_get_angle(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_LEN;
- memset(set_aerobrake_angle_tc, 0, MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_LEN);
- memcpy(set_aerobrake_angle_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_set_deployment_altitude_tc.h b/mavlink_lib/lynx/mavlink_msg_set_deployment_altitude_tc.h
deleted file mode 100644
index bd320a4ee104917287c8800b1d6053789e72a0da..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_set_deployment_altitude_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SET_DEPLOYMENT_ALTITUDE_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC 25
-
-MAVPACKED(
-typedef struct __mavlink_set_deployment_altitude_tc_t {
- float dpl_altitude; /*< [m] Deployment altitude*/
-}) mavlink_set_deployment_altitude_tc_t;
-
-#define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN 4
-#define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN 4
-#define MAVLINK_MSG_ID_25_LEN 4
-#define MAVLINK_MSG_ID_25_MIN_LEN 4
-
-#define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC 44
-#define MAVLINK_MSG_ID_25_CRC 44
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC { \
- 25, \
- "SET_DEPLOYMENT_ALTITUDE_TC", \
- 1, \
- { { "dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_deployment_altitude_tc_t, dpl_altitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC { \
- "SET_DEPLOYMENT_ALTITUDE_TC", \
- 1, \
- { { "dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_deployment_altitude_tc_t, dpl_altitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_deployment_altitude_tc 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 dpl_altitude [m] Deployment altitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_deployment_altitude_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, dpl_altitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
-#else
- mavlink_set_deployment_altitude_tc_t packet;
- packet.dpl_altitude = dpl_altitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-}
-
-/**
- * @brief Pack a set_deployment_altitude_tc 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 dpl_altitude [m] Deployment altitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_deployment_altitude_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, dpl_altitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
-#else
- mavlink_set_deployment_altitude_tc_t packet;
- packet.dpl_altitude = dpl_altitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-}
-
-/**
- * @brief Encode a set_deployment_altitude_tc 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_deployment_altitude_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_deployment_altitude_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_deployment_altitude_tc_t* set_deployment_altitude_tc)
-{
- return mavlink_msg_set_deployment_altitude_tc_pack(system_id, component_id, msg, set_deployment_altitude_tc->dpl_altitude);
-}
-
-/**
- * @brief Encode a set_deployment_altitude_tc 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_deployment_altitude_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_deployment_altitude_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_deployment_altitude_tc_t* set_deployment_altitude_tc)
-{
- return mavlink_msg_set_deployment_altitude_tc_pack_chan(system_id, component_id, chan, msg, set_deployment_altitude_tc->dpl_altitude);
-}
-
-/**
- * @brief Send a set_deployment_altitude_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param dpl_altitude [m] Deployment altitude
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_deployment_altitude_tc_send(mavlink_channel_t chan, float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, dpl_altitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC, buf, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-#else
- mavlink_set_deployment_altitude_tc_t packet;
- packet.dpl_altitude = dpl_altitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_deployment_altitude_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_deployment_altitude_tc_send_struct(mavlink_channel_t chan, const mavlink_set_deployment_altitude_tc_t* set_deployment_altitude_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_deployment_altitude_tc_send(chan, set_deployment_altitude_tc->dpl_altitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC, (const char *)set_deployment_altitude_tc, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_deployment_altitude_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, dpl_altitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC, buf, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-#else
- mavlink_set_deployment_altitude_tc_t *packet = (mavlink_set_deployment_altitude_tc_t *)msgbuf;
- packet->dpl_altitude = dpl_altitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC, (const char *)packet, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_DEPLOYMENT_ALTITUDE_TC UNPACKING
-
-
-/**
- * @brief Get field dpl_altitude from set_deployment_altitude_tc message
- *
- * @return [m] Deployment altitude
- */
-static inline float mavlink_msg_set_deployment_altitude_tc_get_dpl_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a set_deployment_altitude_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_deployment_altitude_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_deployment_altitude_tc_decode(const mavlink_message_t* msg, mavlink_set_deployment_altitude_tc_t* set_deployment_altitude_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_deployment_altitude_tc->dpl_altitude = mavlink_msg_set_deployment_altitude_tc_get_dpl_altitude(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN;
- memset(set_deployment_altitude_tc, 0, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
- memcpy(set_deployment_altitude_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_set_initial_coordinates_tc.h b/mavlink_lib/lynx/mavlink_msg_set_initial_coordinates_tc.h
deleted file mode 100644
index fa153ac7f03467c80634ac4186e3acc4fd85c752..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_set_initial_coordinates_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SET_INITIAL_COORDINATES_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC 51
-
-MAVPACKED(
-typedef struct __mavlink_set_initial_coordinates_tc_t {
- float latitude; /*< [deg] Launchpad latitude*/
- float longitude; /*< [deg] Launchpad longitude*/
-}) mavlink_set_initial_coordinates_tc_t;
-
-#define MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_LEN 8
-#define MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_51_LEN 8
-#define MAVLINK_MSG_ID_51_MIN_LEN 8
-
-#define MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_CRC 63
-#define MAVLINK_MSG_ID_51_CRC 63
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_INITIAL_COORDINATES_TC { \
- 51, \
- "SET_INITIAL_COORDINATES_TC", \
- 2, \
- { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_initial_coordinates_tc_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_initial_coordinates_tc_t, longitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_INITIAL_COORDINATES_TC { \
- "SET_INITIAL_COORDINATES_TC", \
- 2, \
- { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_initial_coordinates_tc_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_initial_coordinates_tc_t, longitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_initial_coordinates_tc 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 [deg] Launchpad latitude
- * @param longitude [deg] Launchpad longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_initial_coordinates_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_LEN);
-#else
- mavlink_set_initial_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_CRC);
-}
-
-/**
- * @brief Pack a set_initial_coordinates_tc 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 [deg] Launchpad latitude
- * @param longitude [deg] Launchpad longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_initial_coordinates_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float latitude,float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_LEN);
-#else
- mavlink_set_initial_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_CRC);
-}
-
-/**
- * @brief Encode a set_initial_coordinates_tc 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_initial_coordinates_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_initial_coordinates_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_initial_coordinates_tc_t* set_initial_coordinates_tc)
-{
- return mavlink_msg_set_initial_coordinates_tc_pack(system_id, component_id, msg, set_initial_coordinates_tc->latitude, set_initial_coordinates_tc->longitude);
-}
-
-/**
- * @brief Encode a set_initial_coordinates_tc 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_initial_coordinates_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_initial_coordinates_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_initial_coordinates_tc_t* set_initial_coordinates_tc)
-{
- return mavlink_msg_set_initial_coordinates_tc_pack_chan(system_id, component_id, chan, msg, set_initial_coordinates_tc->latitude, set_initial_coordinates_tc->longitude);
-}
-
-/**
- * @brief Send a set_initial_coordinates_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param latitude [deg] Launchpad latitude
- * @param longitude [deg] Launchpad longitude
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_initial_coordinates_tc_send(mavlink_channel_t chan, float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC, buf, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_CRC);
-#else
- mavlink_set_initial_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_initial_coordinates_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_initial_coordinates_tc_send_struct(mavlink_channel_t chan, const mavlink_set_initial_coordinates_tc_t* set_initial_coordinates_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_initial_coordinates_tc_send(chan, set_initial_coordinates_tc->latitude, set_initial_coordinates_tc->longitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC, (const char *)set_initial_coordinates_tc, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_initial_coordinates_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC, buf, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_CRC);
-#else
- mavlink_set_initial_coordinates_tc_t *packet = (mavlink_set_initial_coordinates_tc_t *)msgbuf;
- packet->latitude = latitude;
- packet->longitude = longitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC, (const char *)packet, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_INITIAL_COORDINATES_TC UNPACKING
-
-
-/**
- * @brief Get field latitude from set_initial_coordinates_tc message
- *
- * @return [deg] Launchpad latitude
- */
-static inline float mavlink_msg_set_initial_coordinates_tc_get_latitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Get field longitude from set_initial_coordinates_tc message
- *
- * @return [deg] Launchpad longitude
- */
-static inline float mavlink_msg_set_initial_coordinates_tc_get_longitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 4);
-}
-
-/**
- * @brief Decode a set_initial_coordinates_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_initial_coordinates_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_initial_coordinates_tc_decode(const mavlink_message_t* msg, mavlink_set_initial_coordinates_tc_t* set_initial_coordinates_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_initial_coordinates_tc->latitude = mavlink_msg_set_initial_coordinates_tc_get_latitude(msg);
- set_initial_coordinates_tc->longitude = mavlink_msg_set_initial_coordinates_tc_get_longitude(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_LEN;
- memset(set_initial_coordinates_tc, 0, MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_LEN);
- memcpy(set_initial_coordinates_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_set_initial_orientation_tc.h b/mavlink_lib/lynx/mavlink_msg_set_initial_orientation_tc.h
deleted file mode 100644
index 3cdd53fbd12433bad41b94096fc61931e71eaa05..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_set_initial_orientation_tc.h
+++ /dev/null
@@ -1,263 +0,0 @@
-#pragma once
-// MESSAGE SET_INITIAL_ORIENTATION_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC 26
-
-MAVPACKED(
-typedef struct __mavlink_set_initial_orientation_tc_t {
- float yaw; /*< [deg] Yaw angle*/
- float pitch; /*< [deg] Pitch angle*/
- float roll; /*< [deg] Roll angle*/
-}) mavlink_set_initial_orientation_tc_t;
-
-#define MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_LEN 12
-#define MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_MIN_LEN 12
-#define MAVLINK_MSG_ID_26_LEN 12
-#define MAVLINK_MSG_ID_26_MIN_LEN 12
-
-#define MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_CRC 138
-#define MAVLINK_MSG_ID_26_CRC 138
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_INITIAL_ORIENTATION_TC { \
- 26, \
- "SET_INITIAL_ORIENTATION_TC", \
- 3, \
- { { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_initial_orientation_tc_t, yaw) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_initial_orientation_tc_t, pitch) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_initial_orientation_tc_t, roll) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_INITIAL_ORIENTATION_TC { \
- "SET_INITIAL_ORIENTATION_TC", \
- 3, \
- { { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_initial_orientation_tc_t, yaw) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_initial_orientation_tc_t, pitch) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_initial_orientation_tc_t, roll) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_initial_orientation_tc 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 yaw [deg] Yaw angle
- * @param pitch [deg] Pitch angle
- * @param roll [deg] Roll angle
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_initial_orientation_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float yaw, float pitch, float roll)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_LEN];
- _mav_put_float(buf, 0, yaw);
- _mav_put_float(buf, 4, pitch);
- _mav_put_float(buf, 8, roll);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_LEN);
-#else
- mavlink_set_initial_orientation_tc_t packet;
- packet.yaw = yaw;
- packet.pitch = pitch;
- packet.roll = roll;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_CRC);
-}
-
-/**
- * @brief Pack a set_initial_orientation_tc 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 yaw [deg] Yaw angle
- * @param pitch [deg] Pitch angle
- * @param roll [deg] Roll angle
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_initial_orientation_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float yaw,float pitch,float roll)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_LEN];
- _mav_put_float(buf, 0, yaw);
- _mav_put_float(buf, 4, pitch);
- _mav_put_float(buf, 8, roll);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_LEN);
-#else
- mavlink_set_initial_orientation_tc_t packet;
- packet.yaw = yaw;
- packet.pitch = pitch;
- packet.roll = roll;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_CRC);
-}
-
-/**
- * @brief Encode a set_initial_orientation_tc 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_initial_orientation_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_initial_orientation_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_initial_orientation_tc_t* set_initial_orientation_tc)
-{
- return mavlink_msg_set_initial_orientation_tc_pack(system_id, component_id, msg, set_initial_orientation_tc->yaw, set_initial_orientation_tc->pitch, set_initial_orientation_tc->roll);
-}
-
-/**
- * @brief Encode a set_initial_orientation_tc 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_initial_orientation_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_initial_orientation_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_initial_orientation_tc_t* set_initial_orientation_tc)
-{
- return mavlink_msg_set_initial_orientation_tc_pack_chan(system_id, component_id, chan, msg, set_initial_orientation_tc->yaw, set_initial_orientation_tc->pitch, set_initial_orientation_tc->roll);
-}
-
-/**
- * @brief Send a set_initial_orientation_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param yaw [deg] Yaw angle
- * @param pitch [deg] Pitch angle
- * @param roll [deg] Roll angle
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_initial_orientation_tc_send(mavlink_channel_t chan, float yaw, float pitch, float roll)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_LEN];
- _mav_put_float(buf, 0, yaw);
- _mav_put_float(buf, 4, pitch);
- _mav_put_float(buf, 8, roll);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC, buf, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_CRC);
-#else
- mavlink_set_initial_orientation_tc_t packet;
- packet.yaw = yaw;
- packet.pitch = pitch;
- packet.roll = roll;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_initial_orientation_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_initial_orientation_tc_send_struct(mavlink_channel_t chan, const mavlink_set_initial_orientation_tc_t* set_initial_orientation_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_initial_orientation_tc_send(chan, set_initial_orientation_tc->yaw, set_initial_orientation_tc->pitch, set_initial_orientation_tc->roll);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC, (const char *)set_initial_orientation_tc, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_initial_orientation_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float yaw, float pitch, float roll)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, yaw);
- _mav_put_float(buf, 4, pitch);
- _mav_put_float(buf, 8, roll);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC, buf, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_CRC);
-#else
- mavlink_set_initial_orientation_tc_t *packet = (mavlink_set_initial_orientation_tc_t *)msgbuf;
- packet->yaw = yaw;
- packet->pitch = pitch;
- packet->roll = roll;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC, (const char *)packet, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_INITIAL_ORIENTATION_TC UNPACKING
-
-
-/**
- * @brief Get field yaw from set_initial_orientation_tc message
- *
- * @return [deg] Yaw angle
- */
-static inline float mavlink_msg_set_initial_orientation_tc_get_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Get field pitch from set_initial_orientation_tc message
- *
- * @return [deg] Pitch angle
- */
-static inline float mavlink_msg_set_initial_orientation_tc_get_pitch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 4);
-}
-
-/**
- * @brief Get field roll from set_initial_orientation_tc message
- *
- * @return [deg] Roll angle
- */
-static inline float mavlink_msg_set_initial_orientation_tc_get_roll(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Decode a set_initial_orientation_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_initial_orientation_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_initial_orientation_tc_decode(const mavlink_message_t* msg, mavlink_set_initial_orientation_tc_t* set_initial_orientation_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_initial_orientation_tc->yaw = mavlink_msg_set_initial_orientation_tc_get_yaw(msg);
- set_initial_orientation_tc->pitch = mavlink_msg_set_initial_orientation_tc_get_pitch(msg);
- set_initial_orientation_tc->roll = mavlink_msg_set_initial_orientation_tc_get_roll(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_LEN;
- memset(set_initial_orientation_tc, 0, MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_LEN);
- memcpy(set_initial_orientation_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_set_reference_altitude.h b/mavlink_lib/lynx/mavlink_msg_set_reference_altitude.h
deleted file mode 100644
index 0fafe5522dffa93ebbe5219a114d0fc862a56756..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_set_reference_altitude.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SET_REFERENCE_ALTITUDE PACKING
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE 23
-
-MAVPACKED(
-typedef struct __mavlink_set_reference_altitude_t {
- float ref_altitude; /*< [m] Reference altitude*/
-}) mavlink_set_reference_altitude_t;
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_LEN 4
-#define MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_MIN_LEN 4
-#define MAVLINK_MSG_ID_23_LEN 4
-#define MAVLINK_MSG_ID_23_MIN_LEN 4
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_CRC 95
-#define MAVLINK_MSG_ID_23_CRC 95
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE { \
- 23, \
- "SET_REFERENCE_ALTITUDE", \
- 1, \
- { { "ref_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_reference_altitude_t, ref_altitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE { \
- "SET_REFERENCE_ALTITUDE", \
- 1, \
- { { "ref_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_reference_altitude_t, ref_altitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_reference_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 ref_altitude [m] Reference altitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_reference_altitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float ref_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_LEN];
- _mav_put_float(buf, 0, ref_altitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_LEN);
-#else
- mavlink_set_reference_altitude_t packet;
- packet.ref_altitude = ref_altitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_CRC);
-}
-
-/**
- * @brief Pack a set_reference_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 ref_altitude [m] Reference altitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_reference_altitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float ref_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_LEN];
- _mav_put_float(buf, 0, ref_altitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_LEN);
-#else
- mavlink_set_reference_altitude_t packet;
- packet.ref_altitude = ref_altitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_CRC);
-}
-
-/**
- * @brief Encode a set_reference_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 set_reference_altitude C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_reference_altitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_reference_altitude_t* set_reference_altitude)
-{
- return mavlink_msg_set_reference_altitude_pack(system_id, component_id, msg, set_reference_altitude->ref_altitude);
-}
-
-/**
- * @brief Encode a set_reference_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 set_reference_altitude C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_reference_altitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_reference_altitude_t* set_reference_altitude)
-{
- return mavlink_msg_set_reference_altitude_pack_chan(system_id, component_id, chan, msg, set_reference_altitude->ref_altitude);
-}
-
-/**
- * @brief Send a set_reference_altitude message
- * @param chan MAVLink channel to send the message
- *
- * @param ref_altitude [m] Reference altitude
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_reference_altitude_send(mavlink_channel_t chan, float ref_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_LEN];
- _mav_put_float(buf, 0, ref_altitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE, buf, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_CRC);
-#else
- mavlink_set_reference_altitude_t packet;
- packet.ref_altitude = ref_altitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE, (const char *)&packet, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_reference_altitude message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_reference_altitude_send_struct(mavlink_channel_t chan, const mavlink_set_reference_altitude_t* set_reference_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_reference_altitude_send(chan, set_reference_altitude->ref_altitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE, (const char *)set_reference_altitude, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_reference_altitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float ref_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, ref_altitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE, buf, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_CRC);
-#else
- mavlink_set_reference_altitude_t *packet = (mavlink_set_reference_altitude_t *)msgbuf;
- packet->ref_altitude = ref_altitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE, (const char *)packet, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_REFERENCE_ALTITUDE UNPACKING
-
-
-/**
- * @brief Get field ref_altitude from set_reference_altitude message
- *
- * @return [m] Reference altitude
- */
-static inline float mavlink_msg_set_reference_altitude_get_ref_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a set_reference_altitude message into a struct
- *
- * @param msg The message to decode
- * @param set_reference_altitude C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_reference_altitude_decode(const mavlink_message_t* msg, mavlink_set_reference_altitude_t* set_reference_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_reference_altitude->ref_altitude = mavlink_msg_set_reference_altitude_get_ref_altitude(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_LEN? msg->len : MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_LEN;
- memset(set_reference_altitude, 0, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_LEN);
- memcpy(set_reference_altitude, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_set_reference_temperature_tc.h b/mavlink_lib/lynx/mavlink_msg_set_reference_temperature_tc.h
deleted file mode 100644
index 477f193759974c3961213cd2d8f7279aef025d7b..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_set_reference_temperature_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SET_REFERENCE_TEMPERATURE_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC 24
-
-MAVPACKED(
-typedef struct __mavlink_set_reference_temperature_tc_t {
- float ref_temp; /*< [degC] Reference temperature*/
-}) mavlink_set_reference_temperature_tc_t;
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN 4
-#define MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN 4
-#define MAVLINK_MSG_ID_24_LEN 4
-#define MAVLINK_MSG_ID_24_MIN_LEN 4
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC 38
-#define MAVLINK_MSG_ID_24_CRC 38
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC { \
- 24, \
- "SET_REFERENCE_TEMPERATURE_TC", \
- 1, \
- { { "ref_temp", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_reference_temperature_tc_t, ref_temp) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC { \
- "SET_REFERENCE_TEMPERATURE_TC", \
- 1, \
- { { "ref_temp", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_reference_temperature_tc_t, ref_temp) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_reference_temperature_tc 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 ref_temp [degC] Reference temperature
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_reference_temperature_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float ref_temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN];
- _mav_put_float(buf, 0, ref_temp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
-#else
- mavlink_set_reference_temperature_tc_t packet;
- packet.ref_temp = ref_temp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-}
-
-/**
- * @brief Pack a set_reference_temperature_tc 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 ref_temp [degC] Reference temperature
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_reference_temperature_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float ref_temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN];
- _mav_put_float(buf, 0, ref_temp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
-#else
- mavlink_set_reference_temperature_tc_t packet;
- packet.ref_temp = ref_temp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-}
-
-/**
- * @brief Encode a set_reference_temperature_tc 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_reference_temperature_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_reference_temperature_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_reference_temperature_tc_t* set_reference_temperature_tc)
-{
- return mavlink_msg_set_reference_temperature_tc_pack(system_id, component_id, msg, set_reference_temperature_tc->ref_temp);
-}
-
-/**
- * @brief Encode a set_reference_temperature_tc 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_reference_temperature_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_reference_temperature_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_reference_temperature_tc_t* set_reference_temperature_tc)
-{
- return mavlink_msg_set_reference_temperature_tc_pack_chan(system_id, component_id, chan, msg, set_reference_temperature_tc->ref_temp);
-}
-
-/**
- * @brief Send a set_reference_temperature_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param ref_temp [degC] Reference temperature
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_reference_temperature_tc_send(mavlink_channel_t chan, float ref_temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN];
- _mav_put_float(buf, 0, ref_temp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC, buf, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-#else
- mavlink_set_reference_temperature_tc_t packet;
- packet.ref_temp = ref_temp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_reference_temperature_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_reference_temperature_tc_send_struct(mavlink_channel_t chan, const mavlink_set_reference_temperature_tc_t* set_reference_temperature_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_reference_temperature_tc_send(chan, set_reference_temperature_tc->ref_temp);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC, (const char *)set_reference_temperature_tc, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_reference_temperature_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float ref_temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, ref_temp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC, buf, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-#else
- mavlink_set_reference_temperature_tc_t *packet = (mavlink_set_reference_temperature_tc_t *)msgbuf;
- packet->ref_temp = ref_temp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC, (const char *)packet, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_REFERENCE_TEMPERATURE_TC UNPACKING
-
-
-/**
- * @brief Get field ref_temp from set_reference_temperature_tc message
- *
- * @return [degC] Reference temperature
- */
-static inline float mavlink_msg_set_reference_temperature_tc_get_ref_temp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a set_reference_temperature_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_reference_temperature_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_reference_temperature_tc_decode(const mavlink_message_t* msg, mavlink_set_reference_temperature_tc_t* set_reference_temperature_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_reference_temperature_tc->ref_temp = mavlink_msg_set_reference_temperature_tc_get_ref_temp(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN;
- memset(set_reference_temperature_tc, 0, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
- memcpy(set_reference_temperature_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_start_launch_tc.h b/mavlink_lib/lynx/mavlink_msg_start_launch_tc.h
deleted file mode 100644
index 34ab1599e2f08d41912e74034c260f5868631c55..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_start_launch_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE START_LAUNCH_TC PACKING
-
-#define MAVLINK_MSG_ID_START_LAUNCH_TC 20
-
-MAVPACKED(
-typedef struct __mavlink_start_launch_tc_t {
- uint64_t launch_code; /*< 64bit launch code.*/
-}) mavlink_start_launch_tc_t;
-
-#define MAVLINK_MSG_ID_START_LAUNCH_TC_LEN 8
-#define MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_20_LEN 8
-#define MAVLINK_MSG_ID_20_MIN_LEN 8
-
-#define MAVLINK_MSG_ID_START_LAUNCH_TC_CRC 43
-#define MAVLINK_MSG_ID_20_CRC 43
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_START_LAUNCH_TC { \
- 20, \
- "START_LAUNCH_TC", \
- 1, \
- { { "launch_code", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_start_launch_tc_t, launch_code) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_START_LAUNCH_TC { \
- "START_LAUNCH_TC", \
- 1, \
- { { "launch_code", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_start_launch_tc_t, launch_code) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a start_launch_tc 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 launch_code 64bit launch code.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_start_launch_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t launch_code)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_START_LAUNCH_TC_LEN];
- _mav_put_uint64_t(buf, 0, launch_code);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN);
-#else
- mavlink_start_launch_tc_t packet;
- packet.launch_code = launch_code;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_START_LAUNCH_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-}
-
-/**
- * @brief Pack a start_launch_tc 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 launch_code 64bit launch code.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_start_launch_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t launch_code)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_START_LAUNCH_TC_LEN];
- _mav_put_uint64_t(buf, 0, launch_code);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN);
-#else
- mavlink_start_launch_tc_t packet;
- packet.launch_code = launch_code;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_START_LAUNCH_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-}
-
-/**
- * @brief Encode a start_launch_tc 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 start_launch_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_start_launch_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_start_launch_tc_t* start_launch_tc)
-{
- return mavlink_msg_start_launch_tc_pack(system_id, component_id, msg, start_launch_tc->launch_code);
-}
-
-/**
- * @brief Encode a start_launch_tc 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 start_launch_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_start_launch_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_start_launch_tc_t* start_launch_tc)
-{
- return mavlink_msg_start_launch_tc_pack_chan(system_id, component_id, chan, msg, start_launch_tc->launch_code);
-}
-
-/**
- * @brief Send a start_launch_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param launch_code 64bit launch code.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_start_launch_tc_send(mavlink_channel_t chan, uint64_t launch_code)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_START_LAUNCH_TC_LEN];
- _mav_put_uint64_t(buf, 0, launch_code);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_START_LAUNCH_TC, buf, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-#else
- mavlink_start_launch_tc_t packet;
- packet.launch_code = launch_code;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_START_LAUNCH_TC, (const char *)&packet, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a start_launch_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_start_launch_tc_send_struct(mavlink_channel_t chan, const mavlink_start_launch_tc_t* start_launch_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_start_launch_tc_send(chan, start_launch_tc->launch_code);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_START_LAUNCH_TC, (const char *)start_launch_tc, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_START_LAUNCH_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_start_launch_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t launch_code)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, launch_code);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_START_LAUNCH_TC, buf, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-#else
- mavlink_start_launch_tc_t *packet = (mavlink_start_launch_tc_t *)msgbuf;
- packet->launch_code = launch_code;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_START_LAUNCH_TC, (const char *)packet, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE START_LAUNCH_TC UNPACKING
-
-
-/**
- * @brief Get field launch_code from start_launch_tc message
- *
- * @return 64bit launch code.
- */
-static inline uint64_t mavlink_msg_start_launch_tc_get_launch_code(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Decode a start_launch_tc message into a struct
- *
- * @param msg The message to decode
- * @param start_launch_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_start_launch_tc_decode(const mavlink_message_t* msg, mavlink_start_launch_tc_t* start_launch_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- start_launch_tc->launch_code = mavlink_msg_start_launch_tc_get_launch_code(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_START_LAUNCH_TC_LEN? msg->len : MAVLINK_MSG_ID_START_LAUNCH_TC_LEN;
- memset(start_launch_tc, 0, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN);
- memcpy(start_launch_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_sys_tm.h b/mavlink_lib/lynx/mavlink_msg_sys_tm.h
deleted file mode 100644
index 966a20fb1bc89564aa0052bf45a6991c3b0929a8..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_sys_tm.h
+++ /dev/null
@@ -1,538 +0,0 @@
-#pragma once
-// MESSAGE SYS_TM PACKING
-
-#define MAVLINK_MSG_ID_SYS_TM 160
-
-MAVPACKED(
-typedef struct __mavlink_sys_tm_t {
- uint64_t timestamp; /*< [ms] Timestamp*/
- uint8_t death_stack; /*< */
- uint8_t logger; /*< */
- uint8_t ev_broker; /*< */
- uint8_t pin_obs; /*< */
- uint8_t radio; /*< */
- uint8_t state_machines; /*< */
- uint8_t sensors; /*< */
- uint8_t bmx160_status; /*< */
- uint8_t ms5803_status; /*< */
- uint8_t lis3mdl_status; /*< */
- uint8_t gps_status; /*< */
- uint8_t internal_adc_status; /*< */
- uint8_t ads1118_status; /*< */
-}) mavlink_sys_tm_t;
-
-#define MAVLINK_MSG_ID_SYS_TM_LEN 21
-#define MAVLINK_MSG_ID_SYS_TM_MIN_LEN 21
-#define MAVLINK_MSG_ID_160_LEN 21
-#define MAVLINK_MSG_ID_160_MIN_LEN 21
-
-#define MAVLINK_MSG_ID_SYS_TM_CRC 230
-#define MAVLINK_MSG_ID_160_CRC 230
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SYS_TM { \
- 160, \
- "SYS_TM", \
- 14, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_sys_tm_t, timestamp) }, \
- { "death_stack", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_sys_tm_t, death_stack) }, \
- { "logger", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_sys_tm_t, logger) }, \
- { "ev_broker", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_sys_tm_t, ev_broker) }, \
- { "pin_obs", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_sys_tm_t, pin_obs) }, \
- { "radio", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_sys_tm_t, radio) }, \
- { "state_machines", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_sys_tm_t, state_machines) }, \
- { "sensors", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_sys_tm_t, sensors) }, \
- { "bmx160_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_sys_tm_t, bmx160_status) }, \
- { "ms5803_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_sys_tm_t, ms5803_status) }, \
- { "lis3mdl_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_sys_tm_t, lis3mdl_status) }, \
- { "gps_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_sys_tm_t, gps_status) }, \
- { "internal_adc_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_sys_tm_t, internal_adc_status) }, \
- { "ads1118_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_sys_tm_t, ads1118_status) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SYS_TM { \
- "SYS_TM", \
- 14, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_sys_tm_t, timestamp) }, \
- { "death_stack", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_sys_tm_t, death_stack) }, \
- { "logger", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_sys_tm_t, logger) }, \
- { "ev_broker", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_sys_tm_t, ev_broker) }, \
- { "pin_obs", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_sys_tm_t, pin_obs) }, \
- { "radio", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_sys_tm_t, radio) }, \
- { "state_machines", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_sys_tm_t, state_machines) }, \
- { "sensors", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_sys_tm_t, sensors) }, \
- { "bmx160_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_sys_tm_t, bmx160_status) }, \
- { "ms5803_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_sys_tm_t, ms5803_status) }, \
- { "lis3mdl_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_sys_tm_t, lis3mdl_status) }, \
- { "gps_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_sys_tm_t, gps_status) }, \
- { "internal_adc_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_sys_tm_t, internal_adc_status) }, \
- { "ads1118_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_sys_tm_t, ads1118_status) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a sys_tm 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
- * @param death_stack
- * @param logger
- * @param ev_broker
- * @param pin_obs
- * @param radio
- * @param state_machines
- * @param sensors
- * @param bmx160_status
- * @param ms5803_status
- * @param lis3mdl_status
- * @param gps_status
- * @param internal_adc_status
- * @param ads1118_status
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sys_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t death_stack, uint8_t logger, uint8_t ev_broker, uint8_t pin_obs, uint8_t radio, uint8_t state_machines, uint8_t sensors, uint8_t bmx160_status, uint8_t ms5803_status, uint8_t lis3mdl_status, uint8_t gps_status, uint8_t internal_adc_status, uint8_t ads1118_status)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, death_stack);
- _mav_put_uint8_t(buf, 9, logger);
- _mav_put_uint8_t(buf, 10, ev_broker);
- _mav_put_uint8_t(buf, 11, pin_obs);
- _mav_put_uint8_t(buf, 12, radio);
- _mav_put_uint8_t(buf, 13, state_machines);
- _mav_put_uint8_t(buf, 14, sensors);
- _mav_put_uint8_t(buf, 15, bmx160_status);
- _mav_put_uint8_t(buf, 16, ms5803_status);
- _mav_put_uint8_t(buf, 17, lis3mdl_status);
- _mav_put_uint8_t(buf, 18, gps_status);
- _mav_put_uint8_t(buf, 19, internal_adc_status);
- _mav_put_uint8_t(buf, 20, ads1118_status);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_TM_LEN);
-#else
- mavlink_sys_tm_t packet;
- packet.timestamp = timestamp;
- packet.death_stack = death_stack;
- packet.logger = logger;
- packet.ev_broker = ev_broker;
- packet.pin_obs = pin_obs;
- packet.radio = radio;
- packet.state_machines = state_machines;
- packet.sensors = sensors;
- packet.bmx160_status = bmx160_status;
- packet.ms5803_status = ms5803_status;
- packet.lis3mdl_status = lis3mdl_status;
- packet.gps_status = gps_status;
- packet.internal_adc_status = internal_adc_status;
- packet.ads1118_status = ads1118_status;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SYS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-}
-
-/**
- * @brief Pack a sys_tm 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
- * @param death_stack
- * @param logger
- * @param ev_broker
- * @param pin_obs
- * @param radio
- * @param state_machines
- * @param sensors
- * @param bmx160_status
- * @param ms5803_status
- * @param lis3mdl_status
- * @param gps_status
- * @param internal_adc_status
- * @param ads1118_status
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sys_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t death_stack,uint8_t logger,uint8_t ev_broker,uint8_t pin_obs,uint8_t radio,uint8_t state_machines,uint8_t sensors,uint8_t bmx160_status,uint8_t ms5803_status,uint8_t lis3mdl_status,uint8_t gps_status,uint8_t internal_adc_status,uint8_t ads1118_status)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, death_stack);
- _mav_put_uint8_t(buf, 9, logger);
- _mav_put_uint8_t(buf, 10, ev_broker);
- _mav_put_uint8_t(buf, 11, pin_obs);
- _mav_put_uint8_t(buf, 12, radio);
- _mav_put_uint8_t(buf, 13, state_machines);
- _mav_put_uint8_t(buf, 14, sensors);
- _mav_put_uint8_t(buf, 15, bmx160_status);
- _mav_put_uint8_t(buf, 16, ms5803_status);
- _mav_put_uint8_t(buf, 17, lis3mdl_status);
- _mav_put_uint8_t(buf, 18, gps_status);
- _mav_put_uint8_t(buf, 19, internal_adc_status);
- _mav_put_uint8_t(buf, 20, ads1118_status);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_TM_LEN);
-#else
- mavlink_sys_tm_t packet;
- packet.timestamp = timestamp;
- packet.death_stack = death_stack;
- packet.logger = logger;
- packet.ev_broker = ev_broker;
- packet.pin_obs = pin_obs;
- packet.radio = radio;
- packet.state_machines = state_machines;
- packet.sensors = sensors;
- packet.bmx160_status = bmx160_status;
- packet.ms5803_status = ms5803_status;
- packet.lis3mdl_status = lis3mdl_status;
- packet.gps_status = gps_status;
- packet.internal_adc_status = internal_adc_status;
- packet.ads1118_status = ads1118_status;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SYS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-}
-
-/**
- * @brief Encode a sys_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sys_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_tm_t* sys_tm)
-{
- return mavlink_msg_sys_tm_pack(system_id, component_id, msg, sys_tm->timestamp, sys_tm->death_stack, sys_tm->logger, sys_tm->ev_broker, sys_tm->pin_obs, sys_tm->radio, sys_tm->state_machines, sys_tm->sensors, sys_tm->bmx160_status, sys_tm->ms5803_status, sys_tm->lis3mdl_status, sys_tm->gps_status, sys_tm->internal_adc_status, sys_tm->ads1118_status);
-}
-
-/**
- * @brief Encode a sys_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sys_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sys_tm_t* sys_tm)
-{
- return mavlink_msg_sys_tm_pack_chan(system_id, component_id, chan, msg, sys_tm->timestamp, sys_tm->death_stack, sys_tm->logger, sys_tm->ev_broker, sys_tm->pin_obs, sys_tm->radio, sys_tm->state_machines, sys_tm->sensors, sys_tm->bmx160_status, sys_tm->ms5803_status, sys_tm->lis3mdl_status, sys_tm->gps_status, sys_tm->internal_adc_status, sys_tm->ads1118_status);
-}
-
-/**
- * @brief Send a sys_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [ms] Timestamp
- * @param death_stack
- * @param logger
- * @param ev_broker
- * @param pin_obs
- * @param radio
- * @param state_machines
- * @param sensors
- * @param bmx160_status
- * @param ms5803_status
- * @param lis3mdl_status
- * @param gps_status
- * @param internal_adc_status
- * @param ads1118_status
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_sys_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t death_stack, uint8_t logger, uint8_t ev_broker, uint8_t pin_obs, uint8_t radio, uint8_t state_machines, uint8_t sensors, uint8_t bmx160_status, uint8_t ms5803_status, uint8_t lis3mdl_status, uint8_t gps_status, uint8_t internal_adc_status, uint8_t ads1118_status)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, death_stack);
- _mav_put_uint8_t(buf, 9, logger);
- _mav_put_uint8_t(buf, 10, ev_broker);
- _mav_put_uint8_t(buf, 11, pin_obs);
- _mav_put_uint8_t(buf, 12, radio);
- _mav_put_uint8_t(buf, 13, state_machines);
- _mav_put_uint8_t(buf, 14, sensors);
- _mav_put_uint8_t(buf, 15, bmx160_status);
- _mav_put_uint8_t(buf, 16, ms5803_status);
- _mav_put_uint8_t(buf, 17, lis3mdl_status);
- _mav_put_uint8_t(buf, 18, gps_status);
- _mav_put_uint8_t(buf, 19, internal_adc_status);
- _mav_put_uint8_t(buf, 20, ads1118_status);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, buf, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#else
- mavlink_sys_tm_t packet;
- packet.timestamp = timestamp;
- packet.death_stack = death_stack;
- packet.logger = logger;
- packet.ev_broker = ev_broker;
- packet.pin_obs = pin_obs;
- packet.radio = radio;
- packet.state_machines = state_machines;
- packet.sensors = sensors;
- packet.bmx160_status = bmx160_status;
- packet.ms5803_status = ms5803_status;
- packet.lis3mdl_status = lis3mdl_status;
- packet.gps_status = gps_status;
- packet.internal_adc_status = internal_adc_status;
- packet.ads1118_status = ads1118_status;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, (const char *)&packet, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a sys_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_sys_tm_send_struct(mavlink_channel_t chan, const mavlink_sys_tm_t* sys_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_sys_tm_send(chan, sys_tm->timestamp, sys_tm->death_stack, sys_tm->logger, sys_tm->ev_broker, sys_tm->pin_obs, sys_tm->radio, sys_tm->state_machines, sys_tm->sensors, sys_tm->bmx160_status, sys_tm->ms5803_status, sys_tm->lis3mdl_status, sys_tm->gps_status, sys_tm->internal_adc_status, sys_tm->ads1118_status);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, (const char *)sys_tm, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SYS_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t death_stack, uint8_t logger, uint8_t ev_broker, uint8_t pin_obs, uint8_t radio, uint8_t state_machines, uint8_t sensors, uint8_t bmx160_status, uint8_t ms5803_status, uint8_t lis3mdl_status, uint8_t gps_status, uint8_t internal_adc_status, uint8_t ads1118_status)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, death_stack);
- _mav_put_uint8_t(buf, 9, logger);
- _mav_put_uint8_t(buf, 10, ev_broker);
- _mav_put_uint8_t(buf, 11, pin_obs);
- _mav_put_uint8_t(buf, 12, radio);
- _mav_put_uint8_t(buf, 13, state_machines);
- _mav_put_uint8_t(buf, 14, sensors);
- _mav_put_uint8_t(buf, 15, bmx160_status);
- _mav_put_uint8_t(buf, 16, ms5803_status);
- _mav_put_uint8_t(buf, 17, lis3mdl_status);
- _mav_put_uint8_t(buf, 18, gps_status);
- _mav_put_uint8_t(buf, 19, internal_adc_status);
- _mav_put_uint8_t(buf, 20, ads1118_status);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, buf, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#else
- mavlink_sys_tm_t *packet = (mavlink_sys_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->death_stack = death_stack;
- packet->logger = logger;
- packet->ev_broker = ev_broker;
- packet->pin_obs = pin_obs;
- packet->radio = radio;
- packet->state_machines = state_machines;
- packet->sensors = sensors;
- packet->bmx160_status = bmx160_status;
- packet->ms5803_status = ms5803_status;
- packet->lis3mdl_status = lis3mdl_status;
- packet->gps_status = gps_status;
- packet->internal_adc_status = internal_adc_status;
- packet->ads1118_status = ads1118_status;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, (const char *)packet, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SYS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from sys_tm message
- *
- * @return [ms] Timestamp
- */
-static inline uint64_t mavlink_msg_sys_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field death_stack from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_death_stack(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 8);
-}
-
-/**
- * @brief Get field logger from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_logger(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 9);
-}
-
-/**
- * @brief Get field ev_broker from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_ev_broker(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 10);
-}
-
-/**
- * @brief Get field pin_obs from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_pin_obs(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 11);
-}
-
-/**
- * @brief Get field radio from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_radio(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 12);
-}
-
-/**
- * @brief Get field state_machines from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_state_machines(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 13);
-}
-
-/**
- * @brief Get field sensors from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_sensors(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 14);
-}
-
-/**
- * @brief Get field bmx160_status from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_bmx160_status(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 15);
-}
-
-/**
- * @brief Get field ms5803_status from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_ms5803_status(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 16);
-}
-
-/**
- * @brief Get field lis3mdl_status from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_lis3mdl_status(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 17);
-}
-
-/**
- * @brief Get field gps_status from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_gps_status(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 18);
-}
-
-/**
- * @brief Get field internal_adc_status from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_internal_adc_status(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 19);
-}
-
-/**
- * @brief Get field ads1118_status from sys_tm message
- *
- * @return
- */
-static inline uint8_t mavlink_msg_sys_tm_get_ads1118_status(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 20);
-}
-
-/**
- * @brief Decode a sys_tm message into a struct
- *
- * @param msg The message to decode
- * @param sys_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_sys_tm_decode(const mavlink_message_t* msg, mavlink_sys_tm_t* sys_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- sys_tm->timestamp = mavlink_msg_sys_tm_get_timestamp(msg);
- sys_tm->death_stack = mavlink_msg_sys_tm_get_death_stack(msg);
- sys_tm->logger = mavlink_msg_sys_tm_get_logger(msg);
- sys_tm->ev_broker = mavlink_msg_sys_tm_get_ev_broker(msg);
- sys_tm->pin_obs = mavlink_msg_sys_tm_get_pin_obs(msg);
- sys_tm->radio = mavlink_msg_sys_tm_get_radio(msg);
- sys_tm->state_machines = mavlink_msg_sys_tm_get_state_machines(msg);
- sys_tm->sensors = mavlink_msg_sys_tm_get_sensors(msg);
- sys_tm->bmx160_status = mavlink_msg_sys_tm_get_bmx160_status(msg);
- sys_tm->ms5803_status = mavlink_msg_sys_tm_get_ms5803_status(msg);
- sys_tm->lis3mdl_status = mavlink_msg_sys_tm_get_lis3mdl_status(msg);
- sys_tm->gps_status = mavlink_msg_sys_tm_get_gps_status(msg);
- sys_tm->internal_adc_status = mavlink_msg_sys_tm_get_internal_adc_status(msg);
- sys_tm->ads1118_status = mavlink_msg_sys_tm_get_ads1118_status(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SYS_TM_LEN? msg->len : MAVLINK_MSG_ID_SYS_TM_LEN;
- memset(sys_tm, 0, MAVLINK_MSG_ID_SYS_TM_LEN);
- memcpy(sys_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_task_stats_tm.h b/mavlink_lib/lynx/mavlink_msg_task_stats_tm.h
deleted file mode 100644
index 571b4ae5e6ee11dd5333bdcc63f890e33b3611f8..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_task_stats_tm.h
+++ /dev/null
@@ -1,1113 +0,0 @@
-#pragma once
-// MESSAGE TASK_STATS_TM PACKING
-
-#define MAVLINK_MSG_ID_TASK_STATS_TM 165
-
-MAVPACKED(
-typedef struct __mavlink_task_stats_tm_t {
- uint64_t timestamp; /*< [ms] When was this logged */
- float task_sensors_6ms_min; /*< 6 ms task min period*/
- float task_sensors_6ms_max; /*< 6 ms task max period*/
- float task_sensors_6ms_mean; /*< 6 ms task mean period*/
- float task_sensors_6ms_stddev; /*< 6 ms task period std deviation*/
- float task_sensors_15ms_min; /*< 15 ms task min period*/
- float task_sensors_15ms_max; /*< 15 ms task max period*/
- float task_sensors_15ms_mean; /*< 15 ms task mean period*/
- float task_sensors_15ms_stddev; /*< 15 ms task period std deviation*/
- float task_sensors_20ms_min; /*< 20 ms task min period*/
- float task_sensors_20ms_max; /*< 20 ms task max period*/
- float task_sensors_20ms_mean; /*< 20 ms task mean period*/
- float task_sensors_20ms_stddev; /*< 20 ms task period std deviation*/
- float task_sensors_24ms_min; /*< 24 ms task min period*/
- float task_sensors_24ms_max; /*< 24 ms task max period*/
- float task_sensors_24ms_mean; /*< 24 ms task mean period*/
- float task_sensors_24ms_stddev; /*< 24 ms task period std deviation*/
- float task_sensors_40ms_min; /*< 40 ms task min period*/
- float task_sensors_40ms_max; /*< 40 ms task max period*/
- float task_sensors_40ms_mean; /*< 40 ms task mean period*/
- float task_sensors_40ms_stddev; /*< 40 ms task period std deviation*/
- float task_sensors_1000ms_min; /*< 1000 ms task min period*/
- float task_sensors_1000ms_max; /*< 1000 ms task max period*/
- float task_sensors_1000ms_mean; /*< 1000 ms task mean period*/
- float task_sensors_1000ms_stddev; /*< 1000 ms task period std deviation*/
- float task_ada_min; /*< ADA task min period*/
- float task_ada_max; /*< ADA task max period*/
- float task_ada_mean; /*< ADA task mean period*/
- float task_ada_stddev; /*< ADA task period std deviation*/
- float task_nas_min; /*< NavigationSystem task min period*/
- float task_nas_max; /*< NavigationSystem task max period*/
- float task_nas_mean; /*< NavigationSystem task mean period*/
- float task_nas_stddev; /*< NavigationSystem task period std deviation*/
- float task_abk_min; /*< Aerobrakes task min period*/
- float task_abk_max; /*< Aerobrakes task max period*/
- float task_abk_mean; /*< Aerobrakes task mean period*/
- float task_abk_stddev; /*< Aerobrakes task period std deviation*/
-}) mavlink_task_stats_tm_t;
-
-#define MAVLINK_MSG_ID_TASK_STATS_TM_LEN 152
-#define MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN 152
-#define MAVLINK_MSG_ID_165_LEN 152
-#define MAVLINK_MSG_ID_165_MIN_LEN 152
-
-#define MAVLINK_MSG_ID_TASK_STATS_TM_CRC 170
-#define MAVLINK_MSG_ID_165_CRC 170
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_TASK_STATS_TM { \
- 165, \
- "TASK_STATS_TM", \
- 37, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_task_stats_tm_t, timestamp) }, \
- { "task_sensors_6ms_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_task_stats_tm_t, task_sensors_6ms_min) }, \
- { "task_sensors_6ms_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_task_stats_tm_t, task_sensors_6ms_max) }, \
- { "task_sensors_6ms_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_task_stats_tm_t, task_sensors_6ms_mean) }, \
- { "task_sensors_6ms_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_task_stats_tm_t, task_sensors_6ms_stddev) }, \
- { "task_sensors_15ms_min", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_task_stats_tm_t, task_sensors_15ms_min) }, \
- { "task_sensors_15ms_max", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_task_stats_tm_t, task_sensors_15ms_max) }, \
- { "task_sensors_15ms_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_task_stats_tm_t, task_sensors_15ms_mean) }, \
- { "task_sensors_15ms_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_task_stats_tm_t, task_sensors_15ms_stddev) }, \
- { "task_sensors_20ms_min", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_task_stats_tm_t, task_sensors_20ms_min) }, \
- { "task_sensors_20ms_max", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_task_stats_tm_t, task_sensors_20ms_max) }, \
- { "task_sensors_20ms_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_task_stats_tm_t, task_sensors_20ms_mean) }, \
- { "task_sensors_20ms_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_task_stats_tm_t, task_sensors_20ms_stddev) }, \
- { "task_sensors_24ms_min", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_task_stats_tm_t, task_sensors_24ms_min) }, \
- { "task_sensors_24ms_max", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_task_stats_tm_t, task_sensors_24ms_max) }, \
- { "task_sensors_24ms_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_task_stats_tm_t, task_sensors_24ms_mean) }, \
- { "task_sensors_24ms_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_task_stats_tm_t, task_sensors_24ms_stddev) }, \
- { "task_sensors_40ms_min", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_task_stats_tm_t, task_sensors_40ms_min) }, \
- { "task_sensors_40ms_max", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_task_stats_tm_t, task_sensors_40ms_max) }, \
- { "task_sensors_40ms_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_task_stats_tm_t, task_sensors_40ms_mean) }, \
- { "task_sensors_40ms_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_task_stats_tm_t, task_sensors_40ms_stddev) }, \
- { "task_sensors_1000ms_min", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_task_stats_tm_t, task_sensors_1000ms_min) }, \
- { "task_sensors_1000ms_max", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_task_stats_tm_t, task_sensors_1000ms_max) }, \
- { "task_sensors_1000ms_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_task_stats_tm_t, task_sensors_1000ms_mean) }, \
- { "task_sensors_1000ms_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_task_stats_tm_t, task_sensors_1000ms_stddev) }, \
- { "task_ada_min", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_task_stats_tm_t, task_ada_min) }, \
- { "task_ada_max", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_task_stats_tm_t, task_ada_max) }, \
- { "task_ada_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_task_stats_tm_t, task_ada_mean) }, \
- { "task_ada_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_task_stats_tm_t, task_ada_stddev) }, \
- { "task_nas_min", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_task_stats_tm_t, task_nas_min) }, \
- { "task_nas_max", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_task_stats_tm_t, task_nas_max) }, \
- { "task_nas_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_task_stats_tm_t, task_nas_mean) }, \
- { "task_nas_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_task_stats_tm_t, task_nas_stddev) }, \
- { "task_abk_min", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_task_stats_tm_t, task_abk_min) }, \
- { "task_abk_max", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_task_stats_tm_t, task_abk_max) }, \
- { "task_abk_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_task_stats_tm_t, task_abk_mean) }, \
- { "task_abk_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_task_stats_tm_t, task_abk_stddev) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_TASK_STATS_TM { \
- "TASK_STATS_TM", \
- 37, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_task_stats_tm_t, timestamp) }, \
- { "task_sensors_6ms_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_task_stats_tm_t, task_sensors_6ms_min) }, \
- { "task_sensors_6ms_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_task_stats_tm_t, task_sensors_6ms_max) }, \
- { "task_sensors_6ms_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_task_stats_tm_t, task_sensors_6ms_mean) }, \
- { "task_sensors_6ms_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_task_stats_tm_t, task_sensors_6ms_stddev) }, \
- { "task_sensors_15ms_min", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_task_stats_tm_t, task_sensors_15ms_min) }, \
- { "task_sensors_15ms_max", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_task_stats_tm_t, task_sensors_15ms_max) }, \
- { "task_sensors_15ms_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_task_stats_tm_t, task_sensors_15ms_mean) }, \
- { "task_sensors_15ms_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_task_stats_tm_t, task_sensors_15ms_stddev) }, \
- { "task_sensors_20ms_min", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_task_stats_tm_t, task_sensors_20ms_min) }, \
- { "task_sensors_20ms_max", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_task_stats_tm_t, task_sensors_20ms_max) }, \
- { "task_sensors_20ms_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_task_stats_tm_t, task_sensors_20ms_mean) }, \
- { "task_sensors_20ms_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_task_stats_tm_t, task_sensors_20ms_stddev) }, \
- { "task_sensors_24ms_min", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_task_stats_tm_t, task_sensors_24ms_min) }, \
- { "task_sensors_24ms_max", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_task_stats_tm_t, task_sensors_24ms_max) }, \
- { "task_sensors_24ms_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_task_stats_tm_t, task_sensors_24ms_mean) }, \
- { "task_sensors_24ms_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_task_stats_tm_t, task_sensors_24ms_stddev) }, \
- { "task_sensors_40ms_min", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_task_stats_tm_t, task_sensors_40ms_min) }, \
- { "task_sensors_40ms_max", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_task_stats_tm_t, task_sensors_40ms_max) }, \
- { "task_sensors_40ms_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_task_stats_tm_t, task_sensors_40ms_mean) }, \
- { "task_sensors_40ms_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_task_stats_tm_t, task_sensors_40ms_stddev) }, \
- { "task_sensors_1000ms_min", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_task_stats_tm_t, task_sensors_1000ms_min) }, \
- { "task_sensors_1000ms_max", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_task_stats_tm_t, task_sensors_1000ms_max) }, \
- { "task_sensors_1000ms_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_task_stats_tm_t, task_sensors_1000ms_mean) }, \
- { "task_sensors_1000ms_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_task_stats_tm_t, task_sensors_1000ms_stddev) }, \
- { "task_ada_min", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_task_stats_tm_t, task_ada_min) }, \
- { "task_ada_max", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_task_stats_tm_t, task_ada_max) }, \
- { "task_ada_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_task_stats_tm_t, task_ada_mean) }, \
- { "task_ada_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_task_stats_tm_t, task_ada_stddev) }, \
- { "task_nas_min", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_task_stats_tm_t, task_nas_min) }, \
- { "task_nas_max", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_task_stats_tm_t, task_nas_max) }, \
- { "task_nas_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_task_stats_tm_t, task_nas_mean) }, \
- { "task_nas_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_task_stats_tm_t, task_nas_stddev) }, \
- { "task_abk_min", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_task_stats_tm_t, task_abk_min) }, \
- { "task_abk_max", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_task_stats_tm_t, task_abk_max) }, \
- { "task_abk_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_task_stats_tm_t, task_abk_mean) }, \
- { "task_abk_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_task_stats_tm_t, task_abk_stddev) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a task_stats_tm 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] When was this logged
- * @param task_sensors_6ms_min 6 ms task min period
- * @param task_sensors_6ms_max 6 ms task max period
- * @param task_sensors_6ms_mean 6 ms task mean period
- * @param task_sensors_6ms_stddev 6 ms task period std deviation
- * @param task_sensors_15ms_min 15 ms task min period
- * @param task_sensors_15ms_max 15 ms task max period
- * @param task_sensors_15ms_mean 15 ms task mean period
- * @param task_sensors_15ms_stddev 15 ms task period std deviation
- * @param task_sensors_20ms_min 20 ms task min period
- * @param task_sensors_20ms_max 20 ms task max period
- * @param task_sensors_20ms_mean 20 ms task mean period
- * @param task_sensors_20ms_stddev 20 ms task period std deviation
- * @param task_sensors_24ms_min 24 ms task min period
- * @param task_sensors_24ms_max 24 ms task max period
- * @param task_sensors_24ms_mean 24 ms task mean period
- * @param task_sensors_24ms_stddev 24 ms task period std deviation
- * @param task_sensors_40ms_min 40 ms task min period
- * @param task_sensors_40ms_max 40 ms task max period
- * @param task_sensors_40ms_mean 40 ms task mean period
- * @param task_sensors_40ms_stddev 40 ms task period std deviation
- * @param task_sensors_1000ms_min 1000 ms task min period
- * @param task_sensors_1000ms_max 1000 ms task max period
- * @param task_sensors_1000ms_mean 1000 ms task mean period
- * @param task_sensors_1000ms_stddev 1000 ms task period std deviation
- * @param task_ada_min ADA task min period
- * @param task_ada_max ADA task max period
- * @param task_ada_mean ADA task mean period
- * @param task_ada_stddev ADA task period std deviation
- * @param task_nas_min NavigationSystem task min period
- * @param task_nas_max NavigationSystem task max period
- * @param task_nas_mean NavigationSystem task mean period
- * @param task_nas_stddev NavigationSystem task period std deviation
- * @param task_abk_min Aerobrakes task min period
- * @param task_abk_max Aerobrakes task max period
- * @param task_abk_mean Aerobrakes task mean period
- * @param task_abk_stddev Aerobrakes task period std deviation
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_task_stats_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, float task_sensors_6ms_min, float task_sensors_6ms_max, float task_sensors_6ms_mean, float task_sensors_6ms_stddev, float task_sensors_15ms_min, float task_sensors_15ms_max, float task_sensors_15ms_mean, float task_sensors_15ms_stddev, float task_sensors_20ms_min, float task_sensors_20ms_max, float task_sensors_20ms_mean, float task_sensors_20ms_stddev, float task_sensors_24ms_min, float task_sensors_24ms_max, float task_sensors_24ms_mean, float task_sensors_24ms_stddev, float task_sensors_40ms_min, float task_sensors_40ms_max, float task_sensors_40ms_mean, float task_sensors_40ms_stddev, float task_sensors_1000ms_min, float task_sensors_1000ms_max, float task_sensors_1000ms_mean, float task_sensors_1000ms_stddev, float task_ada_min, float task_ada_max, float task_ada_mean, float task_ada_stddev, float task_nas_min, float task_nas_max, float task_nas_mean, float task_nas_stddev, float task_abk_min, float task_abk_max, float task_abk_mean, float task_abk_stddev)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TASK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, task_sensors_6ms_min);
- _mav_put_float(buf, 12, task_sensors_6ms_max);
- _mav_put_float(buf, 16, task_sensors_6ms_mean);
- _mav_put_float(buf, 20, task_sensors_6ms_stddev);
- _mav_put_float(buf, 24, task_sensors_15ms_min);
- _mav_put_float(buf, 28, task_sensors_15ms_max);
- _mav_put_float(buf, 32, task_sensors_15ms_mean);
- _mav_put_float(buf, 36, task_sensors_15ms_stddev);
- _mav_put_float(buf, 40, task_sensors_20ms_min);
- _mav_put_float(buf, 44, task_sensors_20ms_max);
- _mav_put_float(buf, 48, task_sensors_20ms_mean);
- _mav_put_float(buf, 52, task_sensors_20ms_stddev);
- _mav_put_float(buf, 56, task_sensors_24ms_min);
- _mav_put_float(buf, 60, task_sensors_24ms_max);
- _mav_put_float(buf, 64, task_sensors_24ms_mean);
- _mav_put_float(buf, 68, task_sensors_24ms_stddev);
- _mav_put_float(buf, 72, task_sensors_40ms_min);
- _mav_put_float(buf, 76, task_sensors_40ms_max);
- _mav_put_float(buf, 80, task_sensors_40ms_mean);
- _mav_put_float(buf, 84, task_sensors_40ms_stddev);
- _mav_put_float(buf, 88, task_sensors_1000ms_min);
- _mav_put_float(buf, 92, task_sensors_1000ms_max);
- _mav_put_float(buf, 96, task_sensors_1000ms_mean);
- _mav_put_float(buf, 100, task_sensors_1000ms_stddev);
- _mav_put_float(buf, 104, task_ada_min);
- _mav_put_float(buf, 108, task_ada_max);
- _mav_put_float(buf, 112, task_ada_mean);
- _mav_put_float(buf, 116, task_ada_stddev);
- _mav_put_float(buf, 120, task_nas_min);
- _mav_put_float(buf, 124, task_nas_max);
- _mav_put_float(buf, 128, task_nas_mean);
- _mav_put_float(buf, 132, task_nas_stddev);
- _mav_put_float(buf, 136, task_abk_min);
- _mav_put_float(buf, 140, task_abk_max);
- _mav_put_float(buf, 144, task_abk_mean);
- _mav_put_float(buf, 148, task_abk_stddev);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
-#else
- mavlink_task_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.task_sensors_6ms_min = task_sensors_6ms_min;
- packet.task_sensors_6ms_max = task_sensors_6ms_max;
- packet.task_sensors_6ms_mean = task_sensors_6ms_mean;
- packet.task_sensors_6ms_stddev = task_sensors_6ms_stddev;
- packet.task_sensors_15ms_min = task_sensors_15ms_min;
- packet.task_sensors_15ms_max = task_sensors_15ms_max;
- packet.task_sensors_15ms_mean = task_sensors_15ms_mean;
- packet.task_sensors_15ms_stddev = task_sensors_15ms_stddev;
- packet.task_sensors_20ms_min = task_sensors_20ms_min;
- packet.task_sensors_20ms_max = task_sensors_20ms_max;
- packet.task_sensors_20ms_mean = task_sensors_20ms_mean;
- packet.task_sensors_20ms_stddev = task_sensors_20ms_stddev;
- packet.task_sensors_24ms_min = task_sensors_24ms_min;
- packet.task_sensors_24ms_max = task_sensors_24ms_max;
- packet.task_sensors_24ms_mean = task_sensors_24ms_mean;
- packet.task_sensors_24ms_stddev = task_sensors_24ms_stddev;
- packet.task_sensors_40ms_min = task_sensors_40ms_min;
- packet.task_sensors_40ms_max = task_sensors_40ms_max;
- packet.task_sensors_40ms_mean = task_sensors_40ms_mean;
- packet.task_sensors_40ms_stddev = task_sensors_40ms_stddev;
- packet.task_sensors_1000ms_min = task_sensors_1000ms_min;
- packet.task_sensors_1000ms_max = task_sensors_1000ms_max;
- packet.task_sensors_1000ms_mean = task_sensors_1000ms_mean;
- packet.task_sensors_1000ms_stddev = task_sensors_1000ms_stddev;
- packet.task_ada_min = task_ada_min;
- packet.task_ada_max = task_ada_max;
- packet.task_ada_mean = task_ada_mean;
- packet.task_ada_stddev = task_ada_stddev;
- packet.task_nas_min = task_nas_min;
- packet.task_nas_max = task_nas_max;
- packet.task_nas_mean = task_nas_mean;
- packet.task_nas_stddev = task_nas_stddev;
- packet.task_abk_min = task_abk_min;
- packet.task_abk_max = task_abk_max;
- packet.task_abk_mean = task_abk_mean;
- packet.task_abk_stddev = task_abk_stddev;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TASK_STATS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-}
-
-/**
- * @brief Pack a task_stats_tm 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] When was this logged
- * @param task_sensors_6ms_min 6 ms task min period
- * @param task_sensors_6ms_max 6 ms task max period
- * @param task_sensors_6ms_mean 6 ms task mean period
- * @param task_sensors_6ms_stddev 6 ms task period std deviation
- * @param task_sensors_15ms_min 15 ms task min period
- * @param task_sensors_15ms_max 15 ms task max period
- * @param task_sensors_15ms_mean 15 ms task mean period
- * @param task_sensors_15ms_stddev 15 ms task period std deviation
- * @param task_sensors_20ms_min 20 ms task min period
- * @param task_sensors_20ms_max 20 ms task max period
- * @param task_sensors_20ms_mean 20 ms task mean period
- * @param task_sensors_20ms_stddev 20 ms task period std deviation
- * @param task_sensors_24ms_min 24 ms task min period
- * @param task_sensors_24ms_max 24 ms task max period
- * @param task_sensors_24ms_mean 24 ms task mean period
- * @param task_sensors_24ms_stddev 24 ms task period std deviation
- * @param task_sensors_40ms_min 40 ms task min period
- * @param task_sensors_40ms_max 40 ms task max period
- * @param task_sensors_40ms_mean 40 ms task mean period
- * @param task_sensors_40ms_stddev 40 ms task period std deviation
- * @param task_sensors_1000ms_min 1000 ms task min period
- * @param task_sensors_1000ms_max 1000 ms task max period
- * @param task_sensors_1000ms_mean 1000 ms task mean period
- * @param task_sensors_1000ms_stddev 1000 ms task period std deviation
- * @param task_ada_min ADA task min period
- * @param task_ada_max ADA task max period
- * @param task_ada_mean ADA task mean period
- * @param task_ada_stddev ADA task period std deviation
- * @param task_nas_min NavigationSystem task min period
- * @param task_nas_max NavigationSystem task max period
- * @param task_nas_mean NavigationSystem task mean period
- * @param task_nas_stddev NavigationSystem task period std deviation
- * @param task_abk_min Aerobrakes task min period
- * @param task_abk_max Aerobrakes task max period
- * @param task_abk_mean Aerobrakes task mean period
- * @param task_abk_stddev Aerobrakes task period std deviation
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_task_stats_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,float task_sensors_6ms_min,float task_sensors_6ms_max,float task_sensors_6ms_mean,float task_sensors_6ms_stddev,float task_sensors_15ms_min,float task_sensors_15ms_max,float task_sensors_15ms_mean,float task_sensors_15ms_stddev,float task_sensors_20ms_min,float task_sensors_20ms_max,float task_sensors_20ms_mean,float task_sensors_20ms_stddev,float task_sensors_24ms_min,float task_sensors_24ms_max,float task_sensors_24ms_mean,float task_sensors_24ms_stddev,float task_sensors_40ms_min,float task_sensors_40ms_max,float task_sensors_40ms_mean,float task_sensors_40ms_stddev,float task_sensors_1000ms_min,float task_sensors_1000ms_max,float task_sensors_1000ms_mean,float task_sensors_1000ms_stddev,float task_ada_min,float task_ada_max,float task_ada_mean,float task_ada_stddev,float task_nas_min,float task_nas_max,float task_nas_mean,float task_nas_stddev,float task_abk_min,float task_abk_max,float task_abk_mean,float task_abk_stddev)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TASK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, task_sensors_6ms_min);
- _mav_put_float(buf, 12, task_sensors_6ms_max);
- _mav_put_float(buf, 16, task_sensors_6ms_mean);
- _mav_put_float(buf, 20, task_sensors_6ms_stddev);
- _mav_put_float(buf, 24, task_sensors_15ms_min);
- _mav_put_float(buf, 28, task_sensors_15ms_max);
- _mav_put_float(buf, 32, task_sensors_15ms_mean);
- _mav_put_float(buf, 36, task_sensors_15ms_stddev);
- _mav_put_float(buf, 40, task_sensors_20ms_min);
- _mav_put_float(buf, 44, task_sensors_20ms_max);
- _mav_put_float(buf, 48, task_sensors_20ms_mean);
- _mav_put_float(buf, 52, task_sensors_20ms_stddev);
- _mav_put_float(buf, 56, task_sensors_24ms_min);
- _mav_put_float(buf, 60, task_sensors_24ms_max);
- _mav_put_float(buf, 64, task_sensors_24ms_mean);
- _mav_put_float(buf, 68, task_sensors_24ms_stddev);
- _mav_put_float(buf, 72, task_sensors_40ms_min);
- _mav_put_float(buf, 76, task_sensors_40ms_max);
- _mav_put_float(buf, 80, task_sensors_40ms_mean);
- _mav_put_float(buf, 84, task_sensors_40ms_stddev);
- _mav_put_float(buf, 88, task_sensors_1000ms_min);
- _mav_put_float(buf, 92, task_sensors_1000ms_max);
- _mav_put_float(buf, 96, task_sensors_1000ms_mean);
- _mav_put_float(buf, 100, task_sensors_1000ms_stddev);
- _mav_put_float(buf, 104, task_ada_min);
- _mav_put_float(buf, 108, task_ada_max);
- _mav_put_float(buf, 112, task_ada_mean);
- _mav_put_float(buf, 116, task_ada_stddev);
- _mav_put_float(buf, 120, task_nas_min);
- _mav_put_float(buf, 124, task_nas_max);
- _mav_put_float(buf, 128, task_nas_mean);
- _mav_put_float(buf, 132, task_nas_stddev);
- _mav_put_float(buf, 136, task_abk_min);
- _mav_put_float(buf, 140, task_abk_max);
- _mav_put_float(buf, 144, task_abk_mean);
- _mav_put_float(buf, 148, task_abk_stddev);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
-#else
- mavlink_task_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.task_sensors_6ms_min = task_sensors_6ms_min;
- packet.task_sensors_6ms_max = task_sensors_6ms_max;
- packet.task_sensors_6ms_mean = task_sensors_6ms_mean;
- packet.task_sensors_6ms_stddev = task_sensors_6ms_stddev;
- packet.task_sensors_15ms_min = task_sensors_15ms_min;
- packet.task_sensors_15ms_max = task_sensors_15ms_max;
- packet.task_sensors_15ms_mean = task_sensors_15ms_mean;
- packet.task_sensors_15ms_stddev = task_sensors_15ms_stddev;
- packet.task_sensors_20ms_min = task_sensors_20ms_min;
- packet.task_sensors_20ms_max = task_sensors_20ms_max;
- packet.task_sensors_20ms_mean = task_sensors_20ms_mean;
- packet.task_sensors_20ms_stddev = task_sensors_20ms_stddev;
- packet.task_sensors_24ms_min = task_sensors_24ms_min;
- packet.task_sensors_24ms_max = task_sensors_24ms_max;
- packet.task_sensors_24ms_mean = task_sensors_24ms_mean;
- packet.task_sensors_24ms_stddev = task_sensors_24ms_stddev;
- packet.task_sensors_40ms_min = task_sensors_40ms_min;
- packet.task_sensors_40ms_max = task_sensors_40ms_max;
- packet.task_sensors_40ms_mean = task_sensors_40ms_mean;
- packet.task_sensors_40ms_stddev = task_sensors_40ms_stddev;
- packet.task_sensors_1000ms_min = task_sensors_1000ms_min;
- packet.task_sensors_1000ms_max = task_sensors_1000ms_max;
- packet.task_sensors_1000ms_mean = task_sensors_1000ms_mean;
- packet.task_sensors_1000ms_stddev = task_sensors_1000ms_stddev;
- packet.task_ada_min = task_ada_min;
- packet.task_ada_max = task_ada_max;
- packet.task_ada_mean = task_ada_mean;
- packet.task_ada_stddev = task_ada_stddev;
- packet.task_nas_min = task_nas_min;
- packet.task_nas_max = task_nas_max;
- packet.task_nas_mean = task_nas_mean;
- packet.task_nas_stddev = task_nas_stddev;
- packet.task_abk_min = task_abk_min;
- packet.task_abk_max = task_abk_max;
- packet.task_abk_mean = task_abk_mean;
- packet.task_abk_stddev = task_abk_stddev;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TASK_STATS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-}
-
-/**
- * @brief Encode a task_stats_tm 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 task_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_task_stats_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_task_stats_tm_t* task_stats_tm)
-{
- return mavlink_msg_task_stats_tm_pack(system_id, component_id, msg, task_stats_tm->timestamp, task_stats_tm->task_sensors_6ms_min, task_stats_tm->task_sensors_6ms_max, task_stats_tm->task_sensors_6ms_mean, task_stats_tm->task_sensors_6ms_stddev, task_stats_tm->task_sensors_15ms_min, task_stats_tm->task_sensors_15ms_max, task_stats_tm->task_sensors_15ms_mean, task_stats_tm->task_sensors_15ms_stddev, task_stats_tm->task_sensors_20ms_min, task_stats_tm->task_sensors_20ms_max, task_stats_tm->task_sensors_20ms_mean, task_stats_tm->task_sensors_20ms_stddev, task_stats_tm->task_sensors_24ms_min, task_stats_tm->task_sensors_24ms_max, task_stats_tm->task_sensors_24ms_mean, task_stats_tm->task_sensors_24ms_stddev, task_stats_tm->task_sensors_40ms_min, task_stats_tm->task_sensors_40ms_max, task_stats_tm->task_sensors_40ms_mean, task_stats_tm->task_sensors_40ms_stddev, task_stats_tm->task_sensors_1000ms_min, task_stats_tm->task_sensors_1000ms_max, task_stats_tm->task_sensors_1000ms_mean, task_stats_tm->task_sensors_1000ms_stddev, task_stats_tm->task_ada_min, task_stats_tm->task_ada_max, task_stats_tm->task_ada_mean, task_stats_tm->task_ada_stddev, task_stats_tm->task_nas_min, task_stats_tm->task_nas_max, task_stats_tm->task_nas_mean, task_stats_tm->task_nas_stddev, task_stats_tm->task_abk_min, task_stats_tm->task_abk_max, task_stats_tm->task_abk_mean, task_stats_tm->task_abk_stddev);
-}
-
-/**
- * @brief Encode a task_stats_tm 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 task_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_task_stats_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_task_stats_tm_t* task_stats_tm)
-{
- return mavlink_msg_task_stats_tm_pack_chan(system_id, component_id, chan, msg, task_stats_tm->timestamp, task_stats_tm->task_sensors_6ms_min, task_stats_tm->task_sensors_6ms_max, task_stats_tm->task_sensors_6ms_mean, task_stats_tm->task_sensors_6ms_stddev, task_stats_tm->task_sensors_15ms_min, task_stats_tm->task_sensors_15ms_max, task_stats_tm->task_sensors_15ms_mean, task_stats_tm->task_sensors_15ms_stddev, task_stats_tm->task_sensors_20ms_min, task_stats_tm->task_sensors_20ms_max, task_stats_tm->task_sensors_20ms_mean, task_stats_tm->task_sensors_20ms_stddev, task_stats_tm->task_sensors_24ms_min, task_stats_tm->task_sensors_24ms_max, task_stats_tm->task_sensors_24ms_mean, task_stats_tm->task_sensors_24ms_stddev, task_stats_tm->task_sensors_40ms_min, task_stats_tm->task_sensors_40ms_max, task_stats_tm->task_sensors_40ms_mean, task_stats_tm->task_sensors_40ms_stddev, task_stats_tm->task_sensors_1000ms_min, task_stats_tm->task_sensors_1000ms_max, task_stats_tm->task_sensors_1000ms_mean, task_stats_tm->task_sensors_1000ms_stddev, task_stats_tm->task_ada_min, task_stats_tm->task_ada_max, task_stats_tm->task_ada_mean, task_stats_tm->task_ada_stddev, task_stats_tm->task_nas_min, task_stats_tm->task_nas_max, task_stats_tm->task_nas_mean, task_stats_tm->task_nas_stddev, task_stats_tm->task_abk_min, task_stats_tm->task_abk_max, task_stats_tm->task_abk_mean, task_stats_tm->task_abk_stddev);
-}
-
-/**
- * @brief Send a task_stats_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [ms] When was this logged
- * @param task_sensors_6ms_min 6 ms task min period
- * @param task_sensors_6ms_max 6 ms task max period
- * @param task_sensors_6ms_mean 6 ms task mean period
- * @param task_sensors_6ms_stddev 6 ms task period std deviation
- * @param task_sensors_15ms_min 15 ms task min period
- * @param task_sensors_15ms_max 15 ms task max period
- * @param task_sensors_15ms_mean 15 ms task mean period
- * @param task_sensors_15ms_stddev 15 ms task period std deviation
- * @param task_sensors_20ms_min 20 ms task min period
- * @param task_sensors_20ms_max 20 ms task max period
- * @param task_sensors_20ms_mean 20 ms task mean period
- * @param task_sensors_20ms_stddev 20 ms task period std deviation
- * @param task_sensors_24ms_min 24 ms task min period
- * @param task_sensors_24ms_max 24 ms task max period
- * @param task_sensors_24ms_mean 24 ms task mean period
- * @param task_sensors_24ms_stddev 24 ms task period std deviation
- * @param task_sensors_40ms_min 40 ms task min period
- * @param task_sensors_40ms_max 40 ms task max period
- * @param task_sensors_40ms_mean 40 ms task mean period
- * @param task_sensors_40ms_stddev 40 ms task period std deviation
- * @param task_sensors_1000ms_min 1000 ms task min period
- * @param task_sensors_1000ms_max 1000 ms task max period
- * @param task_sensors_1000ms_mean 1000 ms task mean period
- * @param task_sensors_1000ms_stddev 1000 ms task period std deviation
- * @param task_ada_min ADA task min period
- * @param task_ada_max ADA task max period
- * @param task_ada_mean ADA task mean period
- * @param task_ada_stddev ADA task period std deviation
- * @param task_nas_min NavigationSystem task min period
- * @param task_nas_max NavigationSystem task max period
- * @param task_nas_mean NavigationSystem task mean period
- * @param task_nas_stddev NavigationSystem task period std deviation
- * @param task_abk_min Aerobrakes task min period
- * @param task_abk_max Aerobrakes task max period
- * @param task_abk_mean Aerobrakes task mean period
- * @param task_abk_stddev Aerobrakes task period std deviation
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_task_stats_tm_send(mavlink_channel_t chan, uint64_t timestamp, float task_sensors_6ms_min, float task_sensors_6ms_max, float task_sensors_6ms_mean, float task_sensors_6ms_stddev, float task_sensors_15ms_min, float task_sensors_15ms_max, float task_sensors_15ms_mean, float task_sensors_15ms_stddev, float task_sensors_20ms_min, float task_sensors_20ms_max, float task_sensors_20ms_mean, float task_sensors_20ms_stddev, float task_sensors_24ms_min, float task_sensors_24ms_max, float task_sensors_24ms_mean, float task_sensors_24ms_stddev, float task_sensors_40ms_min, float task_sensors_40ms_max, float task_sensors_40ms_mean, float task_sensors_40ms_stddev, float task_sensors_1000ms_min, float task_sensors_1000ms_max, float task_sensors_1000ms_mean, float task_sensors_1000ms_stddev, float task_ada_min, float task_ada_max, float task_ada_mean, float task_ada_stddev, float task_nas_min, float task_nas_max, float task_nas_mean, float task_nas_stddev, float task_abk_min, float task_abk_max, float task_abk_mean, float task_abk_stddev)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TASK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, task_sensors_6ms_min);
- _mav_put_float(buf, 12, task_sensors_6ms_max);
- _mav_put_float(buf, 16, task_sensors_6ms_mean);
- _mav_put_float(buf, 20, task_sensors_6ms_stddev);
- _mav_put_float(buf, 24, task_sensors_15ms_min);
- _mav_put_float(buf, 28, task_sensors_15ms_max);
- _mav_put_float(buf, 32, task_sensors_15ms_mean);
- _mav_put_float(buf, 36, task_sensors_15ms_stddev);
- _mav_put_float(buf, 40, task_sensors_20ms_min);
- _mav_put_float(buf, 44, task_sensors_20ms_max);
- _mav_put_float(buf, 48, task_sensors_20ms_mean);
- _mav_put_float(buf, 52, task_sensors_20ms_stddev);
- _mav_put_float(buf, 56, task_sensors_24ms_min);
- _mav_put_float(buf, 60, task_sensors_24ms_max);
- _mav_put_float(buf, 64, task_sensors_24ms_mean);
- _mav_put_float(buf, 68, task_sensors_24ms_stddev);
- _mav_put_float(buf, 72, task_sensors_40ms_min);
- _mav_put_float(buf, 76, task_sensors_40ms_max);
- _mav_put_float(buf, 80, task_sensors_40ms_mean);
- _mav_put_float(buf, 84, task_sensors_40ms_stddev);
- _mav_put_float(buf, 88, task_sensors_1000ms_min);
- _mav_put_float(buf, 92, task_sensors_1000ms_max);
- _mav_put_float(buf, 96, task_sensors_1000ms_mean);
- _mav_put_float(buf, 100, task_sensors_1000ms_stddev);
- _mav_put_float(buf, 104, task_ada_min);
- _mav_put_float(buf, 108, task_ada_max);
- _mav_put_float(buf, 112, task_ada_mean);
- _mav_put_float(buf, 116, task_ada_stddev);
- _mav_put_float(buf, 120, task_nas_min);
- _mav_put_float(buf, 124, task_nas_max);
- _mav_put_float(buf, 128, task_nas_mean);
- _mav_put_float(buf, 132, task_nas_stddev);
- _mav_put_float(buf, 136, task_abk_min);
- _mav_put_float(buf, 140, task_abk_max);
- _mav_put_float(buf, 144, task_abk_mean);
- _mav_put_float(buf, 148, task_abk_stddev);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, buf, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-#else
- mavlink_task_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.task_sensors_6ms_min = task_sensors_6ms_min;
- packet.task_sensors_6ms_max = task_sensors_6ms_max;
- packet.task_sensors_6ms_mean = task_sensors_6ms_mean;
- packet.task_sensors_6ms_stddev = task_sensors_6ms_stddev;
- packet.task_sensors_15ms_min = task_sensors_15ms_min;
- packet.task_sensors_15ms_max = task_sensors_15ms_max;
- packet.task_sensors_15ms_mean = task_sensors_15ms_mean;
- packet.task_sensors_15ms_stddev = task_sensors_15ms_stddev;
- packet.task_sensors_20ms_min = task_sensors_20ms_min;
- packet.task_sensors_20ms_max = task_sensors_20ms_max;
- packet.task_sensors_20ms_mean = task_sensors_20ms_mean;
- packet.task_sensors_20ms_stddev = task_sensors_20ms_stddev;
- packet.task_sensors_24ms_min = task_sensors_24ms_min;
- packet.task_sensors_24ms_max = task_sensors_24ms_max;
- packet.task_sensors_24ms_mean = task_sensors_24ms_mean;
- packet.task_sensors_24ms_stddev = task_sensors_24ms_stddev;
- packet.task_sensors_40ms_min = task_sensors_40ms_min;
- packet.task_sensors_40ms_max = task_sensors_40ms_max;
- packet.task_sensors_40ms_mean = task_sensors_40ms_mean;
- packet.task_sensors_40ms_stddev = task_sensors_40ms_stddev;
- packet.task_sensors_1000ms_min = task_sensors_1000ms_min;
- packet.task_sensors_1000ms_max = task_sensors_1000ms_max;
- packet.task_sensors_1000ms_mean = task_sensors_1000ms_mean;
- packet.task_sensors_1000ms_stddev = task_sensors_1000ms_stddev;
- packet.task_ada_min = task_ada_min;
- packet.task_ada_max = task_ada_max;
- packet.task_ada_mean = task_ada_mean;
- packet.task_ada_stddev = task_ada_stddev;
- packet.task_nas_min = task_nas_min;
- packet.task_nas_max = task_nas_max;
- packet.task_nas_mean = task_nas_mean;
- packet.task_nas_stddev = task_nas_stddev;
- packet.task_abk_min = task_abk_min;
- packet.task_abk_max = task_abk_max;
- packet.task_abk_mean = task_abk_mean;
- packet.task_abk_stddev = task_abk_stddev;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, (const char *)&packet, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a task_stats_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_task_stats_tm_send_struct(mavlink_channel_t chan, const mavlink_task_stats_tm_t* task_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_task_stats_tm_send(chan, task_stats_tm->timestamp, task_stats_tm->task_sensors_6ms_min, task_stats_tm->task_sensors_6ms_max, task_stats_tm->task_sensors_6ms_mean, task_stats_tm->task_sensors_6ms_stddev, task_stats_tm->task_sensors_15ms_min, task_stats_tm->task_sensors_15ms_max, task_stats_tm->task_sensors_15ms_mean, task_stats_tm->task_sensors_15ms_stddev, task_stats_tm->task_sensors_20ms_min, task_stats_tm->task_sensors_20ms_max, task_stats_tm->task_sensors_20ms_mean, task_stats_tm->task_sensors_20ms_stddev, task_stats_tm->task_sensors_24ms_min, task_stats_tm->task_sensors_24ms_max, task_stats_tm->task_sensors_24ms_mean, task_stats_tm->task_sensors_24ms_stddev, task_stats_tm->task_sensors_40ms_min, task_stats_tm->task_sensors_40ms_max, task_stats_tm->task_sensors_40ms_mean, task_stats_tm->task_sensors_40ms_stddev, task_stats_tm->task_sensors_1000ms_min, task_stats_tm->task_sensors_1000ms_max, task_stats_tm->task_sensors_1000ms_mean, task_stats_tm->task_sensors_1000ms_stddev, task_stats_tm->task_ada_min, task_stats_tm->task_ada_max, task_stats_tm->task_ada_mean, task_stats_tm->task_ada_stddev, task_stats_tm->task_nas_min, task_stats_tm->task_nas_max, task_stats_tm->task_nas_mean, task_stats_tm->task_nas_stddev, task_stats_tm->task_abk_min, task_stats_tm->task_abk_max, task_stats_tm->task_abk_mean, task_stats_tm->task_abk_stddev);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, (const char *)task_stats_tm, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_TASK_STATS_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_task_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float task_sensors_6ms_min, float task_sensors_6ms_max, float task_sensors_6ms_mean, float task_sensors_6ms_stddev, float task_sensors_15ms_min, float task_sensors_15ms_max, float task_sensors_15ms_mean, float task_sensors_15ms_stddev, float task_sensors_20ms_min, float task_sensors_20ms_max, float task_sensors_20ms_mean, float task_sensors_20ms_stddev, float task_sensors_24ms_min, float task_sensors_24ms_max, float task_sensors_24ms_mean, float task_sensors_24ms_stddev, float task_sensors_40ms_min, float task_sensors_40ms_max, float task_sensors_40ms_mean, float task_sensors_40ms_stddev, float task_sensors_1000ms_min, float task_sensors_1000ms_max, float task_sensors_1000ms_mean, float task_sensors_1000ms_stddev, float task_ada_min, float task_ada_max, float task_ada_mean, float task_ada_stddev, float task_nas_min, float task_nas_max, float task_nas_mean, float task_nas_stddev, float task_abk_min, float task_abk_max, float task_abk_mean, float task_abk_stddev)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, task_sensors_6ms_min);
- _mav_put_float(buf, 12, task_sensors_6ms_max);
- _mav_put_float(buf, 16, task_sensors_6ms_mean);
- _mav_put_float(buf, 20, task_sensors_6ms_stddev);
- _mav_put_float(buf, 24, task_sensors_15ms_min);
- _mav_put_float(buf, 28, task_sensors_15ms_max);
- _mav_put_float(buf, 32, task_sensors_15ms_mean);
- _mav_put_float(buf, 36, task_sensors_15ms_stddev);
- _mav_put_float(buf, 40, task_sensors_20ms_min);
- _mav_put_float(buf, 44, task_sensors_20ms_max);
- _mav_put_float(buf, 48, task_sensors_20ms_mean);
- _mav_put_float(buf, 52, task_sensors_20ms_stddev);
- _mav_put_float(buf, 56, task_sensors_24ms_min);
- _mav_put_float(buf, 60, task_sensors_24ms_max);
- _mav_put_float(buf, 64, task_sensors_24ms_mean);
- _mav_put_float(buf, 68, task_sensors_24ms_stddev);
- _mav_put_float(buf, 72, task_sensors_40ms_min);
- _mav_put_float(buf, 76, task_sensors_40ms_max);
- _mav_put_float(buf, 80, task_sensors_40ms_mean);
- _mav_put_float(buf, 84, task_sensors_40ms_stddev);
- _mav_put_float(buf, 88, task_sensors_1000ms_min);
- _mav_put_float(buf, 92, task_sensors_1000ms_max);
- _mav_put_float(buf, 96, task_sensors_1000ms_mean);
- _mav_put_float(buf, 100, task_sensors_1000ms_stddev);
- _mav_put_float(buf, 104, task_ada_min);
- _mav_put_float(buf, 108, task_ada_max);
- _mav_put_float(buf, 112, task_ada_mean);
- _mav_put_float(buf, 116, task_ada_stddev);
- _mav_put_float(buf, 120, task_nas_min);
- _mav_put_float(buf, 124, task_nas_max);
- _mav_put_float(buf, 128, task_nas_mean);
- _mav_put_float(buf, 132, task_nas_stddev);
- _mav_put_float(buf, 136, task_abk_min);
- _mav_put_float(buf, 140, task_abk_max);
- _mav_put_float(buf, 144, task_abk_mean);
- _mav_put_float(buf, 148, task_abk_stddev);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, buf, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-#else
- mavlink_task_stats_tm_t *packet = (mavlink_task_stats_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->task_sensors_6ms_min = task_sensors_6ms_min;
- packet->task_sensors_6ms_max = task_sensors_6ms_max;
- packet->task_sensors_6ms_mean = task_sensors_6ms_mean;
- packet->task_sensors_6ms_stddev = task_sensors_6ms_stddev;
- packet->task_sensors_15ms_min = task_sensors_15ms_min;
- packet->task_sensors_15ms_max = task_sensors_15ms_max;
- packet->task_sensors_15ms_mean = task_sensors_15ms_mean;
- packet->task_sensors_15ms_stddev = task_sensors_15ms_stddev;
- packet->task_sensors_20ms_min = task_sensors_20ms_min;
- packet->task_sensors_20ms_max = task_sensors_20ms_max;
- packet->task_sensors_20ms_mean = task_sensors_20ms_mean;
- packet->task_sensors_20ms_stddev = task_sensors_20ms_stddev;
- packet->task_sensors_24ms_min = task_sensors_24ms_min;
- packet->task_sensors_24ms_max = task_sensors_24ms_max;
- packet->task_sensors_24ms_mean = task_sensors_24ms_mean;
- packet->task_sensors_24ms_stddev = task_sensors_24ms_stddev;
- packet->task_sensors_40ms_min = task_sensors_40ms_min;
- packet->task_sensors_40ms_max = task_sensors_40ms_max;
- packet->task_sensors_40ms_mean = task_sensors_40ms_mean;
- packet->task_sensors_40ms_stddev = task_sensors_40ms_stddev;
- packet->task_sensors_1000ms_min = task_sensors_1000ms_min;
- packet->task_sensors_1000ms_max = task_sensors_1000ms_max;
- packet->task_sensors_1000ms_mean = task_sensors_1000ms_mean;
- packet->task_sensors_1000ms_stddev = task_sensors_1000ms_stddev;
- packet->task_ada_min = task_ada_min;
- packet->task_ada_max = task_ada_max;
- packet->task_ada_mean = task_ada_mean;
- packet->task_ada_stddev = task_ada_stddev;
- packet->task_nas_min = task_nas_min;
- packet->task_nas_max = task_nas_max;
- packet->task_nas_mean = task_nas_mean;
- packet->task_nas_stddev = task_nas_stddev;
- packet->task_abk_min = task_abk_min;
- packet->task_abk_max = task_abk_max;
- packet->task_abk_mean = task_abk_mean;
- packet->task_abk_stddev = task_abk_stddev;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, (const char *)packet, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE TASK_STATS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from task_stats_tm message
- *
- * @return [ms] When was this logged
- */
-static inline uint64_t mavlink_msg_task_stats_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field task_sensors_6ms_min from task_stats_tm message
- *
- * @return 6 ms task min period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_6ms_min(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field task_sensors_6ms_max from task_stats_tm message
- *
- * @return 6 ms task max period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_6ms_max(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field task_sensors_6ms_mean from task_stats_tm message
- *
- * @return 6 ms task mean period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_6ms_mean(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field task_sensors_6ms_stddev from task_stats_tm message
- *
- * @return 6 ms task period std deviation
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_6ms_stddev(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field task_sensors_15ms_min from task_stats_tm message
- *
- * @return 15 ms task min period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_15ms_min(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field task_sensors_15ms_max from task_stats_tm message
- *
- * @return 15 ms task max period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_15ms_max(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field task_sensors_15ms_mean from task_stats_tm message
- *
- * @return 15 ms task mean period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_15ms_mean(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field task_sensors_15ms_stddev from task_stats_tm message
- *
- * @return 15 ms task period std deviation
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_15ms_stddev(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field task_sensors_20ms_min from task_stats_tm message
- *
- * @return 20 ms task min period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_20ms_min(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field task_sensors_20ms_max from task_stats_tm message
- *
- * @return 20 ms task max period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_20ms_max(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field task_sensors_20ms_mean from task_stats_tm message
- *
- * @return 20 ms task mean period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_20ms_mean(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field task_sensors_20ms_stddev from task_stats_tm message
- *
- * @return 20 ms task period std deviation
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_20ms_stddev(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field task_sensors_24ms_min from task_stats_tm message
- *
- * @return 24 ms task min period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_24ms_min(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field task_sensors_24ms_max from task_stats_tm message
- *
- * @return 24 ms task max period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_24ms_max(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field task_sensors_24ms_mean from task_stats_tm message
- *
- * @return 24 ms task mean period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_24ms_mean(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field task_sensors_24ms_stddev from task_stats_tm message
- *
- * @return 24 ms task period std deviation
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_24ms_stddev(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field task_sensors_40ms_min from task_stats_tm message
- *
- * @return 40 ms task min period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_40ms_min(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 72);
-}
-
-/**
- * @brief Get field task_sensors_40ms_max from task_stats_tm message
- *
- * @return 40 ms task max period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_40ms_max(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 76);
-}
-
-/**
- * @brief Get field task_sensors_40ms_mean from task_stats_tm message
- *
- * @return 40 ms task mean period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_40ms_mean(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 80);
-}
-
-/**
- * @brief Get field task_sensors_40ms_stddev from task_stats_tm message
- *
- * @return 40 ms task period std deviation
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_40ms_stddev(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 84);
-}
-
-/**
- * @brief Get field task_sensors_1000ms_min from task_stats_tm message
- *
- * @return 1000 ms task min period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_1000ms_min(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 88);
-}
-
-/**
- * @brief Get field task_sensors_1000ms_max from task_stats_tm message
- *
- * @return 1000 ms task max period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_1000ms_max(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 92);
-}
-
-/**
- * @brief Get field task_sensors_1000ms_mean from task_stats_tm message
- *
- * @return 1000 ms task mean period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_1000ms_mean(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 96);
-}
-
-/**
- * @brief Get field task_sensors_1000ms_stddev from task_stats_tm message
- *
- * @return 1000 ms task period std deviation
- */
-static inline float mavlink_msg_task_stats_tm_get_task_sensors_1000ms_stddev(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 100);
-}
-
-/**
- * @brief Get field task_ada_min from task_stats_tm message
- *
- * @return ADA task min period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_ada_min(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 104);
-}
-
-/**
- * @brief Get field task_ada_max from task_stats_tm message
- *
- * @return ADA task max period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_ada_max(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 108);
-}
-
-/**
- * @brief Get field task_ada_mean from task_stats_tm message
- *
- * @return ADA task mean period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_ada_mean(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 112);
-}
-
-/**
- * @brief Get field task_ada_stddev from task_stats_tm message
- *
- * @return ADA task period std deviation
- */
-static inline float mavlink_msg_task_stats_tm_get_task_ada_stddev(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 116);
-}
-
-/**
- * @brief Get field task_nas_min from task_stats_tm message
- *
- * @return NavigationSystem task min period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_nas_min(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 120);
-}
-
-/**
- * @brief Get field task_nas_max from task_stats_tm message
- *
- * @return NavigationSystem task max period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_nas_max(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 124);
-}
-
-/**
- * @brief Get field task_nas_mean from task_stats_tm message
- *
- * @return NavigationSystem task mean period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_nas_mean(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 128);
-}
-
-/**
- * @brief Get field task_nas_stddev from task_stats_tm message
- *
- * @return NavigationSystem task period std deviation
- */
-static inline float mavlink_msg_task_stats_tm_get_task_nas_stddev(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 132);
-}
-
-/**
- * @brief Get field task_abk_min from task_stats_tm message
- *
- * @return Aerobrakes task min period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_abk_min(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 136);
-}
-
-/**
- * @brief Get field task_abk_max from task_stats_tm message
- *
- * @return Aerobrakes task max period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_abk_max(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 140);
-}
-
-/**
- * @brief Get field task_abk_mean from task_stats_tm message
- *
- * @return Aerobrakes task mean period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_abk_mean(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 144);
-}
-
-/**
- * @brief Get field task_abk_stddev from task_stats_tm message
- *
- * @return Aerobrakes task period std deviation
- */
-static inline float mavlink_msg_task_stats_tm_get_task_abk_stddev(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 148);
-}
-
-/**
- * @brief Decode a task_stats_tm message into a struct
- *
- * @param msg The message to decode
- * @param task_stats_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_task_stats_tm_decode(const mavlink_message_t* msg, mavlink_task_stats_tm_t* task_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- task_stats_tm->timestamp = mavlink_msg_task_stats_tm_get_timestamp(msg);
- task_stats_tm->task_sensors_6ms_min = mavlink_msg_task_stats_tm_get_task_sensors_6ms_min(msg);
- task_stats_tm->task_sensors_6ms_max = mavlink_msg_task_stats_tm_get_task_sensors_6ms_max(msg);
- task_stats_tm->task_sensors_6ms_mean = mavlink_msg_task_stats_tm_get_task_sensors_6ms_mean(msg);
- task_stats_tm->task_sensors_6ms_stddev = mavlink_msg_task_stats_tm_get_task_sensors_6ms_stddev(msg);
- task_stats_tm->task_sensors_15ms_min = mavlink_msg_task_stats_tm_get_task_sensors_15ms_min(msg);
- task_stats_tm->task_sensors_15ms_max = mavlink_msg_task_stats_tm_get_task_sensors_15ms_max(msg);
- task_stats_tm->task_sensors_15ms_mean = mavlink_msg_task_stats_tm_get_task_sensors_15ms_mean(msg);
- task_stats_tm->task_sensors_15ms_stddev = mavlink_msg_task_stats_tm_get_task_sensors_15ms_stddev(msg);
- task_stats_tm->task_sensors_20ms_min = mavlink_msg_task_stats_tm_get_task_sensors_20ms_min(msg);
- task_stats_tm->task_sensors_20ms_max = mavlink_msg_task_stats_tm_get_task_sensors_20ms_max(msg);
- task_stats_tm->task_sensors_20ms_mean = mavlink_msg_task_stats_tm_get_task_sensors_20ms_mean(msg);
- task_stats_tm->task_sensors_20ms_stddev = mavlink_msg_task_stats_tm_get_task_sensors_20ms_stddev(msg);
- task_stats_tm->task_sensors_24ms_min = mavlink_msg_task_stats_tm_get_task_sensors_24ms_min(msg);
- task_stats_tm->task_sensors_24ms_max = mavlink_msg_task_stats_tm_get_task_sensors_24ms_max(msg);
- task_stats_tm->task_sensors_24ms_mean = mavlink_msg_task_stats_tm_get_task_sensors_24ms_mean(msg);
- task_stats_tm->task_sensors_24ms_stddev = mavlink_msg_task_stats_tm_get_task_sensors_24ms_stddev(msg);
- task_stats_tm->task_sensors_40ms_min = mavlink_msg_task_stats_tm_get_task_sensors_40ms_min(msg);
- task_stats_tm->task_sensors_40ms_max = mavlink_msg_task_stats_tm_get_task_sensors_40ms_max(msg);
- task_stats_tm->task_sensors_40ms_mean = mavlink_msg_task_stats_tm_get_task_sensors_40ms_mean(msg);
- task_stats_tm->task_sensors_40ms_stddev = mavlink_msg_task_stats_tm_get_task_sensors_40ms_stddev(msg);
- task_stats_tm->task_sensors_1000ms_min = mavlink_msg_task_stats_tm_get_task_sensors_1000ms_min(msg);
- task_stats_tm->task_sensors_1000ms_max = mavlink_msg_task_stats_tm_get_task_sensors_1000ms_max(msg);
- task_stats_tm->task_sensors_1000ms_mean = mavlink_msg_task_stats_tm_get_task_sensors_1000ms_mean(msg);
- task_stats_tm->task_sensors_1000ms_stddev = mavlink_msg_task_stats_tm_get_task_sensors_1000ms_stddev(msg);
- task_stats_tm->task_ada_min = mavlink_msg_task_stats_tm_get_task_ada_min(msg);
- task_stats_tm->task_ada_max = mavlink_msg_task_stats_tm_get_task_ada_max(msg);
- task_stats_tm->task_ada_mean = mavlink_msg_task_stats_tm_get_task_ada_mean(msg);
- task_stats_tm->task_ada_stddev = mavlink_msg_task_stats_tm_get_task_ada_stddev(msg);
- task_stats_tm->task_nas_min = mavlink_msg_task_stats_tm_get_task_nas_min(msg);
- task_stats_tm->task_nas_max = mavlink_msg_task_stats_tm_get_task_nas_max(msg);
- task_stats_tm->task_nas_mean = mavlink_msg_task_stats_tm_get_task_nas_mean(msg);
- task_stats_tm->task_nas_stddev = mavlink_msg_task_stats_tm_get_task_nas_stddev(msg);
- task_stats_tm->task_abk_min = mavlink_msg_task_stats_tm_get_task_abk_min(msg);
- task_stats_tm->task_abk_max = mavlink_msg_task_stats_tm_get_task_abk_max(msg);
- task_stats_tm->task_abk_mean = mavlink_msg_task_stats_tm_get_task_abk_mean(msg);
- task_stats_tm->task_abk_stddev = mavlink_msg_task_stats_tm_get_task_abk_stddev(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_TASK_STATS_TM_LEN? msg->len : MAVLINK_MSG_ID_TASK_STATS_TM_LEN;
- memset(task_stats_tm, 0, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
- memcpy(task_stats_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_telemetry_request_tc.h b/mavlink_lib/lynx/mavlink_msg_telemetry_request_tc.h
deleted file mode 100644
index e2f463b4c97dcdc907e0569e05b9f8f5a790b8d8..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_telemetry_request_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE TELEMETRY_REQUEST_TC PACKING
-
-#define MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC 50
-
-MAVPACKED(
-typedef struct __mavlink_telemetry_request_tc_t {
- uint8_t board_id; /*< A member of the MavTMList enum.*/
-}) mavlink_telemetry_request_tc_t;
-
-#define MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN 1
-#define MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_50_LEN 1
-#define MAVLINK_MSG_ID_50_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC 105
-#define MAVLINK_MSG_ID_50_CRC 105
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_TELEMETRY_REQUEST_TC { \
- 50, \
- "TELEMETRY_REQUEST_TC", \
- 1, \
- { { "board_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_telemetry_request_tc_t, board_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_TELEMETRY_REQUEST_TC { \
- "TELEMETRY_REQUEST_TC", \
- 1, \
- { { "board_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_telemetry_request_tc_t, board_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a telemetry_request_tc 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 board_id A member of the MavTMList enum.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_telemetry_request_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t board_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, board_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN);
-#else
- mavlink_telemetry_request_tc_t packet;
- packet.board_id = board_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Pack a telemetry_request_tc 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 board_id A member of the MavTMList enum.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_telemetry_request_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t board_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, board_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN);
-#else
- mavlink_telemetry_request_tc_t packet;
- packet.board_id = board_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Encode a telemetry_request_tc 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 telemetry_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_telemetry_request_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_telemetry_request_tc_t* telemetry_request_tc)
-{
- return mavlink_msg_telemetry_request_tc_pack(system_id, component_id, msg, telemetry_request_tc->board_id);
-}
-
-/**
- * @brief Encode a telemetry_request_tc 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 telemetry_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_telemetry_request_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_telemetry_request_tc_t* telemetry_request_tc)
-{
- return mavlink_msg_telemetry_request_tc_pack_chan(system_id, component_id, chan, msg, telemetry_request_tc->board_id);
-}
-
-/**
- * @brief Send a telemetry_request_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param board_id A member of the MavTMList enum.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_telemetry_request_tc_send(mavlink_channel_t chan, uint8_t board_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, board_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC, buf, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-#else
- mavlink_telemetry_request_tc_t packet;
- packet.board_id = board_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC, (const char *)&packet, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a telemetry_request_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_telemetry_request_tc_send_struct(mavlink_channel_t chan, const mavlink_telemetry_request_tc_t* telemetry_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_telemetry_request_tc_send(chan, telemetry_request_tc->board_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC, (const char *)telemetry_request_tc, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_telemetry_request_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t board_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, board_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC, buf, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-#else
- mavlink_telemetry_request_tc_t *packet = (mavlink_telemetry_request_tc_t *)msgbuf;
- packet->board_id = board_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC, (const char *)packet, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE TELEMETRY_REQUEST_TC UNPACKING
-
-
-/**
- * @brief Get field board_id from telemetry_request_tc message
- *
- * @return A member of the MavTMList enum.
- */
-static inline uint8_t mavlink_msg_telemetry_request_tc_get_board_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a telemetry_request_tc message into a struct
- *
- * @param msg The message to decode
- * @param telemetry_request_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_telemetry_request_tc_decode(const mavlink_message_t* msg, mavlink_telemetry_request_tc_t* telemetry_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- telemetry_request_tc->board_id = mavlink_msg_telemetry_request_tc_get_board_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN? msg->len : MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN;
- memset(telemetry_request_tc, 0, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN);
- memcpy(telemetry_request_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_test_tm.h b/mavlink_lib/lynx/mavlink_msg_test_tm.h
deleted file mode 100644
index 78057704ce204148c1c3acaab69fa9456bc240a7..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_test_tm.h
+++ /dev/null
@@ -1,338 +0,0 @@
-#pragma once
-// MESSAGE TEST_TM PACKING
-
-#define MAVLINK_MSG_ID_TEST_TM 182
-
-MAVPACKED(
-typedef struct __mavlink_test_tm_t {
- uint64_t timestamp; /*< [ms] When was this logged (mission clock)*/
- float pressure_hw; /*< Raw pressure from the HoneyWell barometer*/
- float temp_analog; /*< Analog board temperature*/
- float temp_imu; /*< IMU board temperature*/
- float battery_volt; /*< Battery voltage*/
- uint8_t gps_nsats; /*< GPS num sats*/
-}) mavlink_test_tm_t;
-
-#define MAVLINK_MSG_ID_TEST_TM_LEN 25
-#define MAVLINK_MSG_ID_TEST_TM_MIN_LEN 25
-#define MAVLINK_MSG_ID_182_LEN 25
-#define MAVLINK_MSG_ID_182_MIN_LEN 25
-
-#define MAVLINK_MSG_ID_TEST_TM_CRC 177
-#define MAVLINK_MSG_ID_182_CRC 177
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_TEST_TM { \
- 182, \
- "TEST_TM", \
- 6, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_test_tm_t, timestamp) }, \
- { "pressure_hw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_test_tm_t, pressure_hw) }, \
- { "gps_nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_test_tm_t, gps_nsats) }, \
- { "temp_analog", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_test_tm_t, temp_analog) }, \
- { "temp_imu", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_test_tm_t, temp_imu) }, \
- { "battery_volt", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_test_tm_t, battery_volt) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_TEST_TM { \
- "TEST_TM", \
- 6, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_test_tm_t, timestamp) }, \
- { "pressure_hw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_test_tm_t, pressure_hw) }, \
- { "gps_nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_test_tm_t, gps_nsats) }, \
- { "temp_analog", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_test_tm_t, temp_analog) }, \
- { "temp_imu", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_test_tm_t, temp_imu) }, \
- { "battery_volt", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_test_tm_t, battery_volt) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a test_tm 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] When was this logged (mission clock)
- * @param pressure_hw Raw pressure from the HoneyWell barometer
- * @param gps_nsats GPS num sats
- * @param temp_analog Analog board temperature
- * @param temp_imu IMU board temperature
- * @param battery_volt Battery voltage
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_test_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, float pressure_hw, uint8_t gps_nsats, float temp_analog, float temp_imu, float battery_volt)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TEST_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_hw);
- _mav_put_float(buf, 12, temp_analog);
- _mav_put_float(buf, 16, temp_imu);
- _mav_put_float(buf, 20, battery_volt);
- _mav_put_uint8_t(buf, 24, gps_nsats);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TEST_TM_LEN);
-#else
- mavlink_test_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_hw = pressure_hw;
- packet.temp_analog = temp_analog;
- packet.temp_imu = temp_imu;
- packet.battery_volt = battery_volt;
- packet.gps_nsats = gps_nsats;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TEST_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TEST_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TEST_TM_MIN_LEN, MAVLINK_MSG_ID_TEST_TM_LEN, MAVLINK_MSG_ID_TEST_TM_CRC);
-}
-
-/**
- * @brief Pack a test_tm 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] When was this logged (mission clock)
- * @param pressure_hw Raw pressure from the HoneyWell barometer
- * @param gps_nsats GPS num sats
- * @param temp_analog Analog board temperature
- * @param temp_imu IMU board temperature
- * @param battery_volt Battery voltage
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_test_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,float pressure_hw,uint8_t gps_nsats,float temp_analog,float temp_imu,float battery_volt)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TEST_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_hw);
- _mav_put_float(buf, 12, temp_analog);
- _mav_put_float(buf, 16, temp_imu);
- _mav_put_float(buf, 20, battery_volt);
- _mav_put_uint8_t(buf, 24, gps_nsats);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TEST_TM_LEN);
-#else
- mavlink_test_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_hw = pressure_hw;
- packet.temp_analog = temp_analog;
- packet.temp_imu = temp_imu;
- packet.battery_volt = battery_volt;
- packet.gps_nsats = gps_nsats;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TEST_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TEST_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TEST_TM_MIN_LEN, MAVLINK_MSG_ID_TEST_TM_LEN, MAVLINK_MSG_ID_TEST_TM_CRC);
-}
-
-/**
- * @brief Encode a test_tm 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 test_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_test_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_test_tm_t* test_tm)
-{
- return mavlink_msg_test_tm_pack(system_id, component_id, msg, test_tm->timestamp, test_tm->pressure_hw, test_tm->gps_nsats, test_tm->temp_analog, test_tm->temp_imu, test_tm->battery_volt);
-}
-
-/**
- * @brief Encode a test_tm 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 test_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_test_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_test_tm_t* test_tm)
-{
- return mavlink_msg_test_tm_pack_chan(system_id, component_id, chan, msg, test_tm->timestamp, test_tm->pressure_hw, test_tm->gps_nsats, test_tm->temp_analog, test_tm->temp_imu, test_tm->battery_volt);
-}
-
-/**
- * @brief Send a test_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [ms] When was this logged (mission clock)
- * @param pressure_hw Raw pressure from the HoneyWell barometer
- * @param gps_nsats GPS num sats
- * @param temp_analog Analog board temperature
- * @param temp_imu IMU board temperature
- * @param battery_volt Battery voltage
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_test_tm_send(mavlink_channel_t chan, uint64_t timestamp, float pressure_hw, uint8_t gps_nsats, float temp_analog, float temp_imu, float battery_volt)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TEST_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_hw);
- _mav_put_float(buf, 12, temp_analog);
- _mav_put_float(buf, 16, temp_imu);
- _mav_put_float(buf, 20, battery_volt);
- _mav_put_uint8_t(buf, 24, gps_nsats);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TM, buf, MAVLINK_MSG_ID_TEST_TM_MIN_LEN, MAVLINK_MSG_ID_TEST_TM_LEN, MAVLINK_MSG_ID_TEST_TM_CRC);
-#else
- mavlink_test_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_hw = pressure_hw;
- packet.temp_analog = temp_analog;
- packet.temp_imu = temp_imu;
- packet.battery_volt = battery_volt;
- packet.gps_nsats = gps_nsats;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TM, (const char *)&packet, MAVLINK_MSG_ID_TEST_TM_MIN_LEN, MAVLINK_MSG_ID_TEST_TM_LEN, MAVLINK_MSG_ID_TEST_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a test_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_test_tm_send_struct(mavlink_channel_t chan, const mavlink_test_tm_t* test_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_test_tm_send(chan, test_tm->timestamp, test_tm->pressure_hw, test_tm->gps_nsats, test_tm->temp_analog, test_tm->temp_imu, test_tm->battery_volt);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TM, (const char *)test_tm, MAVLINK_MSG_ID_TEST_TM_MIN_LEN, MAVLINK_MSG_ID_TEST_TM_LEN, MAVLINK_MSG_ID_TEST_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_TEST_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_test_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float pressure_hw, uint8_t gps_nsats, float temp_analog, float temp_imu, float battery_volt)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_hw);
- _mav_put_float(buf, 12, temp_analog);
- _mav_put_float(buf, 16, temp_imu);
- _mav_put_float(buf, 20, battery_volt);
- _mav_put_uint8_t(buf, 24, gps_nsats);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TM, buf, MAVLINK_MSG_ID_TEST_TM_MIN_LEN, MAVLINK_MSG_ID_TEST_TM_LEN, MAVLINK_MSG_ID_TEST_TM_CRC);
-#else
- mavlink_test_tm_t *packet = (mavlink_test_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->pressure_hw = pressure_hw;
- packet->temp_analog = temp_analog;
- packet->temp_imu = temp_imu;
- packet->battery_volt = battery_volt;
- packet->gps_nsats = gps_nsats;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TM, (const char *)packet, MAVLINK_MSG_ID_TEST_TM_MIN_LEN, MAVLINK_MSG_ID_TEST_TM_LEN, MAVLINK_MSG_ID_TEST_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE TEST_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from test_tm message
- *
- * @return [ms] When was this logged (mission clock)
- */
-static inline uint64_t mavlink_msg_test_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field pressure_hw from test_tm message
- *
- * @return Raw pressure from the HoneyWell barometer
- */
-static inline float mavlink_msg_test_tm_get_pressure_hw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field gps_nsats from test_tm message
- *
- * @return GPS num sats
- */
-static inline uint8_t mavlink_msg_test_tm_get_gps_nsats(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 24);
-}
-
-/**
- * @brief Get field temp_analog from test_tm message
- *
- * @return Analog board temperature
- */
-static inline float mavlink_msg_test_tm_get_temp_analog(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field temp_imu from test_tm message
- *
- * @return IMU board temperature
- */
-static inline float mavlink_msg_test_tm_get_temp_imu(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field battery_volt from test_tm message
- *
- * @return Battery voltage
- */
-static inline float mavlink_msg_test_tm_get_battery_volt(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Decode a test_tm message into a struct
- *
- * @param msg The message to decode
- * @param test_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_test_tm_decode(const mavlink_message_t* msg, mavlink_test_tm_t* test_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- test_tm->timestamp = mavlink_msg_test_tm_get_timestamp(msg);
- test_tm->pressure_hw = mavlink_msg_test_tm_get_pressure_hw(msg);
- test_tm->temp_analog = mavlink_msg_test_tm_get_temp_analog(msg);
- test_tm->temp_imu = mavlink_msg_test_tm_get_temp_imu(msg);
- test_tm->battery_volt = mavlink_msg_test_tm_get_battery_volt(msg);
- test_tm->gps_nsats = mavlink_msg_test_tm_get_gps_nsats(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_TEST_TM_LEN? msg->len : MAVLINK_MSG_ID_TEST_TM_LEN;
- memset(test_tm, 0, MAVLINK_MSG_ID_TEST_TM_LEN);
- memcpy(test_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_tmtc_tm.h b/mavlink_lib/lynx/mavlink_msg_tmtc_tm.h
deleted file mode 100644
index 1cf128852a34bc0412c3ce9cee30708120de0b91..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_tmtc_tm.h
+++ /dev/null
@@ -1,513 +0,0 @@
-#pragma once
-// MESSAGE TMTC_TM PACKING
-
-#define MAVLINK_MSG_ID_TMTC_TM 164
-
-MAVPACKED(
-typedef struct __mavlink_tmtc_tm_t {
- uint64_t timestamp; /*< [ms] When was this logged */
- uint32_t parse_state; /*< Parsing state machine*/
- uint16_t n_send_queue; /*< Current len of the occupied portion of the queue*/
- uint16_t max_send_queue; /*< Max occupied len of the queue */
- uint16_t n_send_errors; /*< Number of packet not sent correctly by the TMTC*/
- uint16_t packet_rx_success_count; /*< Received packets*/
- uint16_t packet_rx_drop_count; /*< Number of packet drops */
- uint8_t msg_received; /*< Number of received messages*/
- uint8_t buffer_overrun; /*< Number of buffer overruns*/
- uint8_t parse_error; /*< Number of parse errors*/
- 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 */
-}) mavlink_tmtc_tm_t;
-
-#define MAVLINK_MSG_ID_TMTC_TM_LEN 28
-#define MAVLINK_MSG_ID_TMTC_TM_MIN_LEN 28
-#define MAVLINK_MSG_ID_164_LEN 28
-#define MAVLINK_MSG_ID_164_MIN_LEN 28
-
-#define MAVLINK_MSG_ID_TMTC_TM_CRC 164
-#define MAVLINK_MSG_ID_164_CRC 164
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_TMTC_TM { \
- 164, \
- "TMTC_TM", \
- 13, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_tmtc_tm_t, timestamp) }, \
- { "n_send_queue", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_tmtc_tm_t, n_send_queue) }, \
- { "max_send_queue", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_tmtc_tm_t, max_send_queue) }, \
- { "n_send_errors", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_tmtc_tm_t, n_send_errors) }, \
- { "msg_received", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_tmtc_tm_t, msg_received) }, \
- { "buffer_overrun", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_tmtc_tm_t, buffer_overrun) }, \
- { "parse_error", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_tmtc_tm_t, parse_error) }, \
- { "parse_state", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_tmtc_tm_t, parse_state) }, \
- { "packet_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_tmtc_tm_t, packet_idx) }, \
- { "current_rx_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_tmtc_tm_t, current_rx_seq) }, \
- { "current_tx_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_tmtc_tm_t, current_tx_seq) }, \
- { "packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_tmtc_tm_t, packet_rx_success_count) }, \
- { "packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_tmtc_tm_t, packet_rx_drop_count) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_TMTC_TM { \
- "TMTC_TM", \
- 13, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_tmtc_tm_t, timestamp) }, \
- { "n_send_queue", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_tmtc_tm_t, n_send_queue) }, \
- { "max_send_queue", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_tmtc_tm_t, max_send_queue) }, \
- { "n_send_errors", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_tmtc_tm_t, n_send_errors) }, \
- { "msg_received", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_tmtc_tm_t, msg_received) }, \
- { "buffer_overrun", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_tmtc_tm_t, buffer_overrun) }, \
- { "parse_error", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_tmtc_tm_t, parse_error) }, \
- { "parse_state", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_tmtc_tm_t, parse_state) }, \
- { "packet_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_tmtc_tm_t, packet_idx) }, \
- { "current_rx_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_tmtc_tm_t, current_rx_seq) }, \
- { "current_tx_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_tmtc_tm_t, current_tx_seq) }, \
- { "packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_tmtc_tm_t, packet_rx_success_count) }, \
- { "packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_tmtc_tm_t, packet_rx_drop_count) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a tmtc_tm 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] When was this logged
- * @param n_send_queue Current len of the occupied portion of the queue
- * @param max_send_queue Max occupied len of the queue
- * @param n_send_errors Number of packet not sent correctly by the TMTC
- * @param msg_received Number of received messages
- * @param buffer_overrun Number of buffer overruns
- * @param parse_error Number of parse errors
- * @param parse_state Parsing state machine
- * @param packet_idx Index in current packet
- * @param current_rx_seq Sequence number of last packet received
- * @param current_tx_seq Sequence number of last packet sent
- * @param packet_rx_success_count Received packets
- * @param packet_rx_drop_count Number of packet drops
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_tmtc_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint16_t n_send_queue, uint16_t max_send_queue, uint16_t n_send_errors, uint8_t msg_received, uint8_t buffer_overrun, uint8_t parse_error, uint32_t parse_state, uint8_t packet_idx, uint8_t current_rx_seq, uint8_t current_tx_seq, uint16_t packet_rx_success_count, uint16_t packet_rx_drop_count)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TMTC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint32_t(buf, 8, parse_state);
- _mav_put_uint16_t(buf, 12, n_send_queue);
- _mav_put_uint16_t(buf, 14, max_send_queue);
- _mav_put_uint16_t(buf, 16, n_send_errors);
- _mav_put_uint16_t(buf, 18, packet_rx_success_count);
- _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
- _mav_put_uint8_t(buf, 22, msg_received);
- _mav_put_uint8_t(buf, 23, buffer_overrun);
- _mav_put_uint8_t(buf, 24, parse_error);
- _mav_put_uint8_t(buf, 25, packet_idx);
- _mav_put_uint8_t(buf, 26, current_rx_seq);
- _mav_put_uint8_t(buf, 27, current_tx_seq);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TMTC_TM_LEN);
-#else
- mavlink_tmtc_tm_t packet;
- packet.timestamp = timestamp;
- packet.parse_state = parse_state;
- packet.n_send_queue = n_send_queue;
- packet.max_send_queue = max_send_queue;
- packet.n_send_errors = n_send_errors;
- packet.packet_rx_success_count = packet_rx_success_count;
- packet.packet_rx_drop_count = packet_rx_drop_count;
- packet.msg_received = msg_received;
- packet.buffer_overrun = buffer_overrun;
- packet.parse_error = parse_error;
- packet.packet_idx = packet_idx;
- packet.current_rx_seq = current_rx_seq;
- packet.current_tx_seq = current_tx_seq;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TMTC_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TMTC_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TMTC_TM_MIN_LEN, MAVLINK_MSG_ID_TMTC_TM_LEN, MAVLINK_MSG_ID_TMTC_TM_CRC);
-}
-
-/**
- * @brief Pack a tmtc_tm 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] When was this logged
- * @param n_send_queue Current len of the occupied portion of the queue
- * @param max_send_queue Max occupied len of the queue
- * @param n_send_errors Number of packet not sent correctly by the TMTC
- * @param msg_received Number of received messages
- * @param buffer_overrun Number of buffer overruns
- * @param parse_error Number of parse errors
- * @param parse_state Parsing state machine
- * @param packet_idx Index in current packet
- * @param current_rx_seq Sequence number of last packet received
- * @param current_tx_seq Sequence number of last packet sent
- * @param packet_rx_success_count Received packets
- * @param packet_rx_drop_count Number of packet drops
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_tmtc_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint16_t n_send_queue,uint16_t max_send_queue,uint16_t n_send_errors,uint8_t msg_received,uint8_t buffer_overrun,uint8_t parse_error,uint32_t parse_state,uint8_t packet_idx,uint8_t current_rx_seq,uint8_t current_tx_seq,uint16_t packet_rx_success_count,uint16_t packet_rx_drop_count)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TMTC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint32_t(buf, 8, parse_state);
- _mav_put_uint16_t(buf, 12, n_send_queue);
- _mav_put_uint16_t(buf, 14, max_send_queue);
- _mav_put_uint16_t(buf, 16, n_send_errors);
- _mav_put_uint16_t(buf, 18, packet_rx_success_count);
- _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
- _mav_put_uint8_t(buf, 22, msg_received);
- _mav_put_uint8_t(buf, 23, buffer_overrun);
- _mav_put_uint8_t(buf, 24, parse_error);
- _mav_put_uint8_t(buf, 25, packet_idx);
- _mav_put_uint8_t(buf, 26, current_rx_seq);
- _mav_put_uint8_t(buf, 27, current_tx_seq);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TMTC_TM_LEN);
-#else
- mavlink_tmtc_tm_t packet;
- packet.timestamp = timestamp;
- packet.parse_state = parse_state;
- packet.n_send_queue = n_send_queue;
- packet.max_send_queue = max_send_queue;
- packet.n_send_errors = n_send_errors;
- packet.packet_rx_success_count = packet_rx_success_count;
- packet.packet_rx_drop_count = packet_rx_drop_count;
- packet.msg_received = msg_received;
- packet.buffer_overrun = buffer_overrun;
- packet.parse_error = parse_error;
- packet.packet_idx = packet_idx;
- packet.current_rx_seq = current_rx_seq;
- packet.current_tx_seq = current_tx_seq;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TMTC_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TMTC_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TMTC_TM_MIN_LEN, MAVLINK_MSG_ID_TMTC_TM_LEN, MAVLINK_MSG_ID_TMTC_TM_CRC);
-}
-
-/**
- * @brief Encode a tmtc_tm 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 tmtc_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_tmtc_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_tmtc_tm_t* tmtc_tm)
-{
- return mavlink_msg_tmtc_tm_pack(system_id, component_id, msg, tmtc_tm->timestamp, tmtc_tm->n_send_queue, tmtc_tm->max_send_queue, tmtc_tm->n_send_errors, tmtc_tm->msg_received, tmtc_tm->buffer_overrun, tmtc_tm->parse_error, tmtc_tm->parse_state, tmtc_tm->packet_idx, tmtc_tm->current_rx_seq, tmtc_tm->current_tx_seq, tmtc_tm->packet_rx_success_count, tmtc_tm->packet_rx_drop_count);
-}
-
-/**
- * @brief Encode a tmtc_tm 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 tmtc_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_tmtc_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_tmtc_tm_t* tmtc_tm)
-{
- return mavlink_msg_tmtc_tm_pack_chan(system_id, component_id, chan, msg, tmtc_tm->timestamp, tmtc_tm->n_send_queue, tmtc_tm->max_send_queue, tmtc_tm->n_send_errors, tmtc_tm->msg_received, tmtc_tm->buffer_overrun, tmtc_tm->parse_error, tmtc_tm->parse_state, tmtc_tm->packet_idx, tmtc_tm->current_rx_seq, tmtc_tm->current_tx_seq, tmtc_tm->packet_rx_success_count, tmtc_tm->packet_rx_drop_count);
-}
-
-/**
- * @brief Send a tmtc_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [ms] When was this logged
- * @param n_send_queue Current len of the occupied portion of the queue
- * @param max_send_queue Max occupied len of the queue
- * @param n_send_errors Number of packet not sent correctly by the TMTC
- * @param msg_received Number of received messages
- * @param buffer_overrun Number of buffer overruns
- * @param parse_error Number of parse errors
- * @param parse_state Parsing state machine
- * @param packet_idx Index in current packet
- * @param current_rx_seq Sequence number of last packet received
- * @param current_tx_seq Sequence number of last packet sent
- * @param packet_rx_success_count Received packets
- * @param packet_rx_drop_count Number of packet drops
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_tmtc_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint16_t n_send_queue, uint16_t max_send_queue, uint16_t n_send_errors, uint8_t msg_received, uint8_t buffer_overrun, uint8_t parse_error, uint32_t parse_state, uint8_t packet_idx, uint8_t current_rx_seq, uint8_t current_tx_seq, uint16_t packet_rx_success_count, uint16_t packet_rx_drop_count)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TMTC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint32_t(buf, 8, parse_state);
- _mav_put_uint16_t(buf, 12, n_send_queue);
- _mav_put_uint16_t(buf, 14, max_send_queue);
- _mav_put_uint16_t(buf, 16, n_send_errors);
- _mav_put_uint16_t(buf, 18, packet_rx_success_count);
- _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
- _mav_put_uint8_t(buf, 22, msg_received);
- _mav_put_uint8_t(buf, 23, buffer_overrun);
- _mav_put_uint8_t(buf, 24, parse_error);
- _mav_put_uint8_t(buf, 25, packet_idx);
- _mav_put_uint8_t(buf, 26, current_rx_seq);
- _mav_put_uint8_t(buf, 27, current_tx_seq);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TMTC_TM, buf, MAVLINK_MSG_ID_TMTC_TM_MIN_LEN, MAVLINK_MSG_ID_TMTC_TM_LEN, MAVLINK_MSG_ID_TMTC_TM_CRC);
-#else
- mavlink_tmtc_tm_t packet;
- packet.timestamp = timestamp;
- packet.parse_state = parse_state;
- packet.n_send_queue = n_send_queue;
- packet.max_send_queue = max_send_queue;
- packet.n_send_errors = n_send_errors;
- packet.packet_rx_success_count = packet_rx_success_count;
- packet.packet_rx_drop_count = packet_rx_drop_count;
- packet.msg_received = msg_received;
- packet.buffer_overrun = buffer_overrun;
- packet.parse_error = parse_error;
- packet.packet_idx = packet_idx;
- packet.current_rx_seq = current_rx_seq;
- packet.current_tx_seq = current_tx_seq;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TMTC_TM, (const char *)&packet, MAVLINK_MSG_ID_TMTC_TM_MIN_LEN, MAVLINK_MSG_ID_TMTC_TM_LEN, MAVLINK_MSG_ID_TMTC_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a tmtc_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_tmtc_tm_send_struct(mavlink_channel_t chan, const mavlink_tmtc_tm_t* tmtc_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_tmtc_tm_send(chan, tmtc_tm->timestamp, tmtc_tm->n_send_queue, tmtc_tm->max_send_queue, tmtc_tm->n_send_errors, tmtc_tm->msg_received, tmtc_tm->buffer_overrun, tmtc_tm->parse_error, tmtc_tm->parse_state, tmtc_tm->packet_idx, tmtc_tm->current_rx_seq, tmtc_tm->current_tx_seq, tmtc_tm->packet_rx_success_count, tmtc_tm->packet_rx_drop_count);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TMTC_TM, (const char *)tmtc_tm, MAVLINK_MSG_ID_TMTC_TM_MIN_LEN, MAVLINK_MSG_ID_TMTC_TM_LEN, MAVLINK_MSG_ID_TMTC_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_TMTC_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_tmtc_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint16_t n_send_queue, uint16_t max_send_queue, uint16_t n_send_errors, uint8_t msg_received, uint8_t buffer_overrun, uint8_t parse_error, uint32_t parse_state, uint8_t packet_idx, uint8_t current_rx_seq, uint8_t current_tx_seq, uint16_t packet_rx_success_count, uint16_t packet_rx_drop_count)
-{
-#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, parse_state);
- _mav_put_uint16_t(buf, 12, n_send_queue);
- _mav_put_uint16_t(buf, 14, max_send_queue);
- _mav_put_uint16_t(buf, 16, n_send_errors);
- _mav_put_uint16_t(buf, 18, packet_rx_success_count);
- _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
- _mav_put_uint8_t(buf, 22, msg_received);
- _mav_put_uint8_t(buf, 23, buffer_overrun);
- _mav_put_uint8_t(buf, 24, parse_error);
- _mav_put_uint8_t(buf, 25, packet_idx);
- _mav_put_uint8_t(buf, 26, current_rx_seq);
- _mav_put_uint8_t(buf, 27, current_tx_seq);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TMTC_TM, buf, MAVLINK_MSG_ID_TMTC_TM_MIN_LEN, MAVLINK_MSG_ID_TMTC_TM_LEN, MAVLINK_MSG_ID_TMTC_TM_CRC);
-#else
- mavlink_tmtc_tm_t *packet = (mavlink_tmtc_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->parse_state = parse_state;
- packet->n_send_queue = n_send_queue;
- packet->max_send_queue = max_send_queue;
- packet->n_send_errors = n_send_errors;
- packet->packet_rx_success_count = packet_rx_success_count;
- packet->packet_rx_drop_count = packet_rx_drop_count;
- packet->msg_received = msg_received;
- packet->buffer_overrun = buffer_overrun;
- packet->parse_error = parse_error;
- packet->packet_idx = packet_idx;
- packet->current_rx_seq = current_rx_seq;
- packet->current_tx_seq = current_tx_seq;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TMTC_TM, (const char *)packet, MAVLINK_MSG_ID_TMTC_TM_MIN_LEN, MAVLINK_MSG_ID_TMTC_TM_LEN, MAVLINK_MSG_ID_TMTC_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE TMTC_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from tmtc_tm message
- *
- * @return [ms] When was this logged
- */
-static inline uint64_t mavlink_msg_tmtc_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field n_send_queue from tmtc_tm message
- *
- * @return Current len of the occupied portion of the queue
- */
-static inline uint16_t mavlink_msg_tmtc_tm_get_n_send_queue(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 12);
-}
-
-/**
- * @brief Get field max_send_queue from tmtc_tm message
- *
- * @return Max occupied len of the queue
- */
-static inline uint16_t mavlink_msg_tmtc_tm_get_max_send_queue(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 14);
-}
-
-/**
- * @brief Get field n_send_errors from tmtc_tm message
- *
- * @return Number of packet not sent correctly by the TMTC
- */
-static inline uint16_t mavlink_msg_tmtc_tm_get_n_send_errors(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 16);
-}
-
-/**
- * @brief Get field msg_received from tmtc_tm message
- *
- * @return Number of received messages
- */
-static inline uint8_t mavlink_msg_tmtc_tm_get_msg_received(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 22);
-}
-
-/**
- * @brief Get field buffer_overrun from tmtc_tm message
- *
- * @return Number of buffer overruns
- */
-static inline uint8_t mavlink_msg_tmtc_tm_get_buffer_overrun(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 23);
-}
-
-/**
- * @brief Get field parse_error from tmtc_tm message
- *
- * @return Number of parse errors
- */
-static inline uint8_t mavlink_msg_tmtc_tm_get_parse_error(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 24);
-}
-
-/**
- * @brief Get field parse_state from tmtc_tm message
- *
- * @return Parsing state machine
- */
-static inline uint32_t mavlink_msg_tmtc_tm_get_parse_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 8);
-}
-
-/**
- * @brief Get field packet_idx from tmtc_tm message
- *
- * @return Index in current packet
- */
-static inline uint8_t mavlink_msg_tmtc_tm_get_packet_idx(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 25);
-}
-
-/**
- * @brief Get field current_rx_seq from tmtc_tm message
- *
- * @return Sequence number of last packet received
- */
-static inline uint8_t mavlink_msg_tmtc_tm_get_current_rx_seq(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 26);
-}
-
-/**
- * @brief Get field current_tx_seq from tmtc_tm message
- *
- * @return Sequence number of last packet sent
- */
-static inline uint8_t mavlink_msg_tmtc_tm_get_current_tx_seq(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 27);
-}
-
-/**
- * @brief Get field packet_rx_success_count from tmtc_tm message
- *
- * @return Received packets
- */
-static inline uint16_t mavlink_msg_tmtc_tm_get_packet_rx_success_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 18);
-}
-
-/**
- * @brief Get field packet_rx_drop_count from tmtc_tm message
- *
- * @return Number of packet drops
- */
-static inline uint16_t mavlink_msg_tmtc_tm_get_packet_rx_drop_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 20);
-}
-
-/**
- * @brief Decode a tmtc_tm message into a struct
- *
- * @param msg The message to decode
- * @param tmtc_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_tmtc_tm_decode(const mavlink_message_t* msg, mavlink_tmtc_tm_t* tmtc_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- tmtc_tm->timestamp = mavlink_msg_tmtc_tm_get_timestamp(msg);
- tmtc_tm->parse_state = mavlink_msg_tmtc_tm_get_parse_state(msg);
- tmtc_tm->n_send_queue = mavlink_msg_tmtc_tm_get_n_send_queue(msg);
- tmtc_tm->max_send_queue = mavlink_msg_tmtc_tm_get_max_send_queue(msg);
- tmtc_tm->n_send_errors = mavlink_msg_tmtc_tm_get_n_send_errors(msg);
- tmtc_tm->packet_rx_success_count = mavlink_msg_tmtc_tm_get_packet_rx_success_count(msg);
- tmtc_tm->packet_rx_drop_count = mavlink_msg_tmtc_tm_get_packet_rx_drop_count(msg);
- tmtc_tm->msg_received = mavlink_msg_tmtc_tm_get_msg_received(msg);
- tmtc_tm->buffer_overrun = mavlink_msg_tmtc_tm_get_buffer_overrun(msg);
- tmtc_tm->parse_error = mavlink_msg_tmtc_tm_get_parse_error(msg);
- tmtc_tm->packet_idx = mavlink_msg_tmtc_tm_get_packet_idx(msg);
- tmtc_tm->current_rx_seq = mavlink_msg_tmtc_tm_get_current_rx_seq(msg);
- tmtc_tm->current_tx_seq = mavlink_msg_tmtc_tm_get_current_tx_seq(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_TMTC_TM_LEN? msg->len : MAVLINK_MSG_ID_TMTC_TM_LEN;
- memset(tmtc_tm, 0, MAVLINK_MSG_ID_TMTC_TM_LEN);
- memcpy(tmtc_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_upload_setting_tc.h b/mavlink_lib/lynx/mavlink_msg_upload_setting_tc.h
deleted file mode 100644
index ea3de324c7113b52bd0854f7f8bf9ac19683f98d..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_upload_setting_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE UPLOAD_SETTING_TC PACKING
-
-#define MAVLINK_MSG_ID_UPLOAD_SETTING_TC 21
-
-MAVPACKED(
-typedef struct __mavlink_upload_setting_tc_t {
- float setting; /*< The value of the setting to be uploaded*/
- uint8_t setting_id; /*< A member of the MavSettingList enum.*/
-}) mavlink_upload_setting_tc_t;
-
-#define MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN 5
-#define MAVLINK_MSG_ID_UPLOAD_SETTING_TC_MIN_LEN 5
-#define MAVLINK_MSG_ID_21_LEN 5
-#define MAVLINK_MSG_ID_21_MIN_LEN 5
-
-#define MAVLINK_MSG_ID_UPLOAD_SETTING_TC_CRC 90
-#define MAVLINK_MSG_ID_21_CRC 90
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_UPLOAD_SETTING_TC { \
- 21, \
- "UPLOAD_SETTING_TC", \
- 2, \
- { { "setting_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_upload_setting_tc_t, setting_id) }, \
- { "setting", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_upload_setting_tc_t, setting) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_UPLOAD_SETTING_TC { \
- "UPLOAD_SETTING_TC", \
- 2, \
- { { "setting_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_upload_setting_tc_t, setting_id) }, \
- { "setting", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_upload_setting_tc_t, setting) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a upload_setting_tc 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 setting_id A member of the MavSettingList enum.
- * @param setting The value of the setting to be uploaded
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_upload_setting_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t setting_id, float setting)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN];
- _mav_put_float(buf, 0, setting);
- _mav_put_uint8_t(buf, 4, setting_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN);
-#else
- mavlink_upload_setting_tc_t packet;
- packet.setting = setting;
- packet.setting_id = setting_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_UPLOAD_SETTING_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_MIN_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_CRC);
-}
-
-/**
- * @brief Pack a upload_setting_tc 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 setting_id A member of the MavSettingList enum.
- * @param setting The value of the setting to be uploaded
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_upload_setting_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t setting_id,float setting)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN];
- _mav_put_float(buf, 0, setting);
- _mav_put_uint8_t(buf, 4, setting_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN);
-#else
- mavlink_upload_setting_tc_t packet;
- packet.setting = setting;
- packet.setting_id = setting_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_UPLOAD_SETTING_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_MIN_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_CRC);
-}
-
-/**
- * @brief Encode a upload_setting_tc 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 upload_setting_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_upload_setting_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_upload_setting_tc_t* upload_setting_tc)
-{
- return mavlink_msg_upload_setting_tc_pack(system_id, component_id, msg, upload_setting_tc->setting_id, upload_setting_tc->setting);
-}
-
-/**
- * @brief Encode a upload_setting_tc 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 upload_setting_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_upload_setting_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_upload_setting_tc_t* upload_setting_tc)
-{
- return mavlink_msg_upload_setting_tc_pack_chan(system_id, component_id, chan, msg, upload_setting_tc->setting_id, upload_setting_tc->setting);
-}
-
-/**
- * @brief Send a upload_setting_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param setting_id A member of the MavSettingList enum.
- * @param setting The value of the setting to be uploaded
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_upload_setting_tc_send(mavlink_channel_t chan, uint8_t setting_id, float setting)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN];
- _mav_put_float(buf, 0, setting);
- _mav_put_uint8_t(buf, 4, setting_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UPLOAD_SETTING_TC, buf, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_MIN_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_CRC);
-#else
- mavlink_upload_setting_tc_t packet;
- packet.setting = setting;
- packet.setting_id = setting_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UPLOAD_SETTING_TC, (const char *)&packet, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_MIN_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a upload_setting_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_upload_setting_tc_send_struct(mavlink_channel_t chan, const mavlink_upload_setting_tc_t* upload_setting_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_upload_setting_tc_send(chan, upload_setting_tc->setting_id, upload_setting_tc->setting);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UPLOAD_SETTING_TC, (const char *)upload_setting_tc, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_MIN_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_upload_setting_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t setting_id, float setting)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, setting);
- _mav_put_uint8_t(buf, 4, setting_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UPLOAD_SETTING_TC, buf, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_MIN_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_CRC);
-#else
- mavlink_upload_setting_tc_t *packet = (mavlink_upload_setting_tc_t *)msgbuf;
- packet->setting = setting;
- packet->setting_id = setting_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UPLOAD_SETTING_TC, (const char *)packet, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_MIN_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE UPLOAD_SETTING_TC UNPACKING
-
-
-/**
- * @brief Get field setting_id from upload_setting_tc message
- *
- * @return A member of the MavSettingList enum.
- */
-static inline uint8_t mavlink_msg_upload_setting_tc_get_setting_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 4);
-}
-
-/**
- * @brief Get field setting from upload_setting_tc message
- *
- * @return The value of the setting to be uploaded
- */
-static inline float mavlink_msg_upload_setting_tc_get_setting(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a upload_setting_tc message into a struct
- *
- * @param msg The message to decode
- * @param upload_setting_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_upload_setting_tc_decode(const mavlink_message_t* msg, mavlink_upload_setting_tc_t* upload_setting_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- upload_setting_tc->setting = mavlink_msg_upload_setting_tc_get_setting(msg);
- upload_setting_tc->setting_id = mavlink_msg_upload_setting_tc_get_setting_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN? msg->len : MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN;
- memset(upload_setting_tc, 0, MAVLINK_MSG_ID_UPLOAD_SETTING_TC_LEN);
- memcpy(upload_setting_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/mavlink_msg_windtunnel_tm.h b/mavlink_lib/lynx/mavlink_msg_windtunnel_tm.h
deleted file mode 100644
index 1979123d3ccc9bb891bca69bbd6419de3748b48f..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/mavlink_msg_windtunnel_tm.h
+++ /dev/null
@@ -1,438 +0,0 @@
-#pragma once
-// MESSAGE WINDTUNNEL_TM PACKING
-
-#define MAVLINK_MSG_ID_WINDTUNNEL_TM 183
-
-MAVPACKED(
-typedef struct __mavlink_windtunnel_tm_t {
- uint64_t timestamp; /*< [ms] When was this logged*/
- double pressure_dpl; /*< [Pa] Pressure from deployment vane*/
- float pressure_digital; /*< [Pa] Pressure from digital pressure sensor*/
- float pressure_differential; /*< [Pa] Differential pressure*/
- float pressure_static; /*< [Pa] Pressure from static port*/
- float ab_angle; /*< [deg] Current aerobrake angle*/
- float wind_speed; /*< [m/s] Current tunnel wind speed*/
- float log_status; /*< Logger status*/
- float log_num; /*< Logger file number*/
- float last_RSSI; /*< [dBm] Last message RSSI*/
-}) mavlink_windtunnel_tm_t;
-
-#define MAVLINK_MSG_ID_WINDTUNNEL_TM_LEN 48
-#define MAVLINK_MSG_ID_WINDTUNNEL_TM_MIN_LEN 48
-#define MAVLINK_MSG_ID_183_LEN 48
-#define MAVLINK_MSG_ID_183_MIN_LEN 48
-
-#define MAVLINK_MSG_ID_WINDTUNNEL_TM_CRC 176
-#define MAVLINK_MSG_ID_183_CRC 176
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_WINDTUNNEL_TM { \
- 183, \
- "WINDTUNNEL_TM", \
- 10, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_windtunnel_tm_t, timestamp) }, \
- { "pressure_digital", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_windtunnel_tm_t, pressure_digital) }, \
- { "pressure_differential", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_windtunnel_tm_t, pressure_differential) }, \
- { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_windtunnel_tm_t, pressure_static) }, \
- { "pressure_dpl", NULL, MAVLINK_TYPE_DOUBLE, 0, 8, offsetof(mavlink_windtunnel_tm_t, pressure_dpl) }, \
- { "ab_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_windtunnel_tm_t, ab_angle) }, \
- { "wind_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_windtunnel_tm_t, wind_speed) }, \
- { "log_status", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_windtunnel_tm_t, log_status) }, \
- { "log_num", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_windtunnel_tm_t, log_num) }, \
- { "last_RSSI", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_windtunnel_tm_t, last_RSSI) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_WINDTUNNEL_TM { \
- "WINDTUNNEL_TM", \
- 10, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_windtunnel_tm_t, timestamp) }, \
- { "pressure_digital", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_windtunnel_tm_t, pressure_digital) }, \
- { "pressure_differential", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_windtunnel_tm_t, pressure_differential) }, \
- { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_windtunnel_tm_t, pressure_static) }, \
- { "pressure_dpl", NULL, MAVLINK_TYPE_DOUBLE, 0, 8, offsetof(mavlink_windtunnel_tm_t, pressure_dpl) }, \
- { "ab_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_windtunnel_tm_t, ab_angle) }, \
- { "wind_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_windtunnel_tm_t, wind_speed) }, \
- { "log_status", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_windtunnel_tm_t, log_status) }, \
- { "log_num", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_windtunnel_tm_t, log_num) }, \
- { "last_RSSI", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_windtunnel_tm_t, last_RSSI) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a windtunnel_tm 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] When was this logged
- * @param pressure_digital [Pa] Pressure from digital pressure sensor
- * @param pressure_differential [Pa] Differential pressure
- * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane
- * @param ab_angle [deg] Current aerobrake angle
- * @param wind_speed [m/s] Current tunnel wind speed
- * @param log_status Logger status
- * @param log_num Logger file number
- * @param last_RSSI [dBm] Last message RSSI
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_windtunnel_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, float pressure_digital, float pressure_differential, float pressure_static, double pressure_dpl, float ab_angle, float wind_speed, float log_status, float log_num, float last_RSSI)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_WINDTUNNEL_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, pressure_dpl);
- _mav_put_float(buf, 16, pressure_digital);
- _mav_put_float(buf, 20, pressure_differential);
- _mav_put_float(buf, 24, pressure_static);
- _mav_put_float(buf, 28, ab_angle);
- _mav_put_float(buf, 32, wind_speed);
- _mav_put_float(buf, 36, log_status);
- _mav_put_float(buf, 40, log_num);
- _mav_put_float(buf, 44, last_RSSI);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WINDTUNNEL_TM_LEN);
-#else
- mavlink_windtunnel_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_dpl = pressure_dpl;
- packet.pressure_digital = pressure_digital;
- packet.pressure_differential = pressure_differential;
- packet.pressure_static = pressure_static;
- packet.ab_angle = ab_angle;
- packet.wind_speed = wind_speed;
- packet.log_status = log_status;
- packet.log_num = log_num;
- packet.last_RSSI = last_RSSI;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WINDTUNNEL_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_WINDTUNNEL_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WINDTUNNEL_TM_MIN_LEN, MAVLINK_MSG_ID_WINDTUNNEL_TM_LEN, MAVLINK_MSG_ID_WINDTUNNEL_TM_CRC);
-}
-
-/**
- * @brief Pack a windtunnel_tm 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] When was this logged
- * @param pressure_digital [Pa] Pressure from digital pressure sensor
- * @param pressure_differential [Pa] Differential pressure
- * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane
- * @param ab_angle [deg] Current aerobrake angle
- * @param wind_speed [m/s] Current tunnel wind speed
- * @param log_status Logger status
- * @param log_num Logger file number
- * @param last_RSSI [dBm] Last message RSSI
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_windtunnel_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,float pressure_digital,float pressure_differential,float pressure_static,double pressure_dpl,float ab_angle,float wind_speed,float log_status,float log_num,float last_RSSI)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_WINDTUNNEL_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, pressure_dpl);
- _mav_put_float(buf, 16, pressure_digital);
- _mav_put_float(buf, 20, pressure_differential);
- _mav_put_float(buf, 24, pressure_static);
- _mav_put_float(buf, 28, ab_angle);
- _mav_put_float(buf, 32, wind_speed);
- _mav_put_float(buf, 36, log_status);
- _mav_put_float(buf, 40, log_num);
- _mav_put_float(buf, 44, last_RSSI);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WINDTUNNEL_TM_LEN);
-#else
- mavlink_windtunnel_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_dpl = pressure_dpl;
- packet.pressure_digital = pressure_digital;
- packet.pressure_differential = pressure_differential;
- packet.pressure_static = pressure_static;
- packet.ab_angle = ab_angle;
- packet.wind_speed = wind_speed;
- packet.log_status = log_status;
- packet.log_num = log_num;
- packet.last_RSSI = last_RSSI;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WINDTUNNEL_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_WINDTUNNEL_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WINDTUNNEL_TM_MIN_LEN, MAVLINK_MSG_ID_WINDTUNNEL_TM_LEN, MAVLINK_MSG_ID_WINDTUNNEL_TM_CRC);
-}
-
-/**
- * @brief Encode a windtunnel_tm 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 windtunnel_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_windtunnel_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_windtunnel_tm_t* windtunnel_tm)
-{
- return mavlink_msg_windtunnel_tm_pack(system_id, component_id, msg, windtunnel_tm->timestamp, windtunnel_tm->pressure_digital, windtunnel_tm->pressure_differential, windtunnel_tm->pressure_static, windtunnel_tm->pressure_dpl, windtunnel_tm->ab_angle, windtunnel_tm->wind_speed, windtunnel_tm->log_status, windtunnel_tm->log_num, windtunnel_tm->last_RSSI);
-}
-
-/**
- * @brief Encode a windtunnel_tm 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 windtunnel_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_windtunnel_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_windtunnel_tm_t* windtunnel_tm)
-{
- return mavlink_msg_windtunnel_tm_pack_chan(system_id, component_id, chan, msg, windtunnel_tm->timestamp, windtunnel_tm->pressure_digital, windtunnel_tm->pressure_differential, windtunnel_tm->pressure_static, windtunnel_tm->pressure_dpl, windtunnel_tm->ab_angle, windtunnel_tm->wind_speed, windtunnel_tm->log_status, windtunnel_tm->log_num, windtunnel_tm->last_RSSI);
-}
-
-/**
- * @brief Send a windtunnel_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [ms] When was this logged
- * @param pressure_digital [Pa] Pressure from digital pressure sensor
- * @param pressure_differential [Pa] Differential pressure
- * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane
- * @param ab_angle [deg] Current aerobrake angle
- * @param wind_speed [m/s] Current tunnel wind speed
- * @param log_status Logger status
- * @param log_num Logger file number
- * @param last_RSSI [dBm] Last message RSSI
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_windtunnel_tm_send(mavlink_channel_t chan, uint64_t timestamp, float pressure_digital, float pressure_differential, float pressure_static, double pressure_dpl, float ab_angle, float wind_speed, float log_status, float log_num, float last_RSSI)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_WINDTUNNEL_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, pressure_dpl);
- _mav_put_float(buf, 16, pressure_digital);
- _mav_put_float(buf, 20, pressure_differential);
- _mav_put_float(buf, 24, pressure_static);
- _mav_put_float(buf, 28, ab_angle);
- _mav_put_float(buf, 32, wind_speed);
- _mav_put_float(buf, 36, log_status);
- _mav_put_float(buf, 40, log_num);
- _mav_put_float(buf, 44, last_RSSI);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WINDTUNNEL_TM, buf, MAVLINK_MSG_ID_WINDTUNNEL_TM_MIN_LEN, MAVLINK_MSG_ID_WINDTUNNEL_TM_LEN, MAVLINK_MSG_ID_WINDTUNNEL_TM_CRC);
-#else
- mavlink_windtunnel_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_dpl = pressure_dpl;
- packet.pressure_digital = pressure_digital;
- packet.pressure_differential = pressure_differential;
- packet.pressure_static = pressure_static;
- packet.ab_angle = ab_angle;
- packet.wind_speed = wind_speed;
- packet.log_status = log_status;
- packet.log_num = log_num;
- packet.last_RSSI = last_RSSI;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WINDTUNNEL_TM, (const char *)&packet, MAVLINK_MSG_ID_WINDTUNNEL_TM_MIN_LEN, MAVLINK_MSG_ID_WINDTUNNEL_TM_LEN, MAVLINK_MSG_ID_WINDTUNNEL_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a windtunnel_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_windtunnel_tm_send_struct(mavlink_channel_t chan, const mavlink_windtunnel_tm_t* windtunnel_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_windtunnel_tm_send(chan, windtunnel_tm->timestamp, windtunnel_tm->pressure_digital, windtunnel_tm->pressure_differential, windtunnel_tm->pressure_static, windtunnel_tm->pressure_dpl, windtunnel_tm->ab_angle, windtunnel_tm->wind_speed, windtunnel_tm->log_status, windtunnel_tm->log_num, windtunnel_tm->last_RSSI);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WINDTUNNEL_TM, (const char *)windtunnel_tm, MAVLINK_MSG_ID_WINDTUNNEL_TM_MIN_LEN, MAVLINK_MSG_ID_WINDTUNNEL_TM_LEN, MAVLINK_MSG_ID_WINDTUNNEL_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_WINDTUNNEL_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_windtunnel_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float pressure_digital, float pressure_differential, float pressure_static, double pressure_dpl, float ab_angle, float wind_speed, float log_status, float log_num, float last_RSSI)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, pressure_dpl);
- _mav_put_float(buf, 16, pressure_digital);
- _mav_put_float(buf, 20, pressure_differential);
- _mav_put_float(buf, 24, pressure_static);
- _mav_put_float(buf, 28, ab_angle);
- _mav_put_float(buf, 32, wind_speed);
- _mav_put_float(buf, 36, log_status);
- _mav_put_float(buf, 40, log_num);
- _mav_put_float(buf, 44, last_RSSI);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WINDTUNNEL_TM, buf, MAVLINK_MSG_ID_WINDTUNNEL_TM_MIN_LEN, MAVLINK_MSG_ID_WINDTUNNEL_TM_LEN, MAVLINK_MSG_ID_WINDTUNNEL_TM_CRC);
-#else
- mavlink_windtunnel_tm_t *packet = (mavlink_windtunnel_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->pressure_dpl = pressure_dpl;
- packet->pressure_digital = pressure_digital;
- packet->pressure_differential = pressure_differential;
- packet->pressure_static = pressure_static;
- packet->ab_angle = ab_angle;
- packet->wind_speed = wind_speed;
- packet->log_status = log_status;
- packet->log_num = log_num;
- packet->last_RSSI = last_RSSI;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WINDTUNNEL_TM, (const char *)packet, MAVLINK_MSG_ID_WINDTUNNEL_TM_MIN_LEN, MAVLINK_MSG_ID_WINDTUNNEL_TM_LEN, MAVLINK_MSG_ID_WINDTUNNEL_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE WINDTUNNEL_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from windtunnel_tm message
- *
- * @return [ms] When was this logged
- */
-static inline uint64_t mavlink_msg_windtunnel_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field pressure_digital from windtunnel_tm message
- *
- * @return [Pa] Pressure from digital pressure sensor
- */
-static inline float mavlink_msg_windtunnel_tm_get_pressure_digital(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field pressure_differential from windtunnel_tm message
- *
- * @return [Pa] Differential pressure
- */
-static inline float mavlink_msg_windtunnel_tm_get_pressure_differential(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field pressure_static from windtunnel_tm message
- *
- * @return [Pa] Pressure from static port
- */
-static inline float mavlink_msg_windtunnel_tm_get_pressure_static(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field pressure_dpl from windtunnel_tm message
- *
- * @return [Pa] Pressure from deployment vane
- */
-static inline double mavlink_msg_windtunnel_tm_get_pressure_dpl(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_double(msg, 8);
-}
-
-/**
- * @brief Get field ab_angle from windtunnel_tm message
- *
- * @return [deg] Current aerobrake angle
- */
-static inline float mavlink_msg_windtunnel_tm_get_ab_angle(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field wind_speed from windtunnel_tm message
- *
- * @return [m/s] Current tunnel wind speed
- */
-static inline float mavlink_msg_windtunnel_tm_get_wind_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field log_status from windtunnel_tm message
- *
- * @return Logger status
- */
-static inline float mavlink_msg_windtunnel_tm_get_log_status(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field log_num from windtunnel_tm message
- *
- * @return Logger file number
- */
-static inline float mavlink_msg_windtunnel_tm_get_log_num(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field last_RSSI from windtunnel_tm message
- *
- * @return [dBm] Last message RSSI
- */
-static inline float mavlink_msg_windtunnel_tm_get_last_RSSI(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Decode a windtunnel_tm message into a struct
- *
- * @param msg The message to decode
- * @param windtunnel_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_windtunnel_tm_decode(const mavlink_message_t* msg, mavlink_windtunnel_tm_t* windtunnel_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- windtunnel_tm->timestamp = mavlink_msg_windtunnel_tm_get_timestamp(msg);
- windtunnel_tm->pressure_dpl = mavlink_msg_windtunnel_tm_get_pressure_dpl(msg);
- windtunnel_tm->pressure_digital = mavlink_msg_windtunnel_tm_get_pressure_digital(msg);
- windtunnel_tm->pressure_differential = mavlink_msg_windtunnel_tm_get_pressure_differential(msg);
- windtunnel_tm->pressure_static = mavlink_msg_windtunnel_tm_get_pressure_static(msg);
- windtunnel_tm->ab_angle = mavlink_msg_windtunnel_tm_get_ab_angle(msg);
- windtunnel_tm->wind_speed = mavlink_msg_windtunnel_tm_get_wind_speed(msg);
- windtunnel_tm->log_status = mavlink_msg_windtunnel_tm_get_log_status(msg);
- windtunnel_tm->log_num = mavlink_msg_windtunnel_tm_get_log_num(msg);
- windtunnel_tm->last_RSSI = mavlink_msg_windtunnel_tm_get_last_RSSI(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_WINDTUNNEL_TM_LEN? msg->len : MAVLINK_MSG_ID_WINDTUNNEL_TM_LEN;
- memset(windtunnel_tm, 0, MAVLINK_MSG_ID_WINDTUNNEL_TM_LEN);
- memcpy(windtunnel_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lynx/testsuite.h b/mavlink_lib/lynx/testsuite.h
deleted file mode 100644
index 49b6e5a5bab7d57cb75fb1597d30b79ac39b60fa..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/testsuite.h
+++ /dev/null
@@ -1,2189 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol testsuite generated from lynx.xml
- * @see http://qgroundcontrol.org/mavlink/
- */
-#pragma once
-#ifndef LYNX_TESTSUITE_H
-#define LYNX_TESTSUITE_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#ifndef MAVLINK_TEST_ALL
-#define MAVLINK_TEST_ALL
-
-static void mavlink_test_lynx(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_lynx(system_id, component_id, last_msg);
-}
-#endif
-
-
-
-
-static void mavlink_test_ping_tc(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_PING_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ping_tc_t packet_in = {
- 93372036854775807ULL
- };
- mavlink_ping_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_PING_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PING_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ping_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_pack(system_id, component_id, &msg , packet1.timestamp );
- mavlink_msg_ping_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp );
- mavlink_msg_ping_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ping_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_send(MAVLINK_COMM_1 , packet1.timestamp );
- mavlink_msg_ping_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_noarg_tc(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_NOARG_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_noarg_tc_t packet_in = {
- 5
- };
- mavlink_noarg_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.command_id = packet_in.command_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_NOARG_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NOARG_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_noarg_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_noarg_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_noarg_tc_pack(system_id, component_id, &msg , packet1.command_id );
- mavlink_msg_noarg_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_noarg_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.command_id );
- mavlink_msg_noarg_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_noarg_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_noarg_tc_send(MAVLINK_COMM_1 , packet1.command_id );
- mavlink_msg_noarg_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_start_launch_tc(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_START_LAUNCH_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_start_launch_tc_t packet_in = {
- 93372036854775807ULL
- };
- mavlink_start_launch_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.launch_code = packet_in.launch_code;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_start_launch_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_start_launch_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_start_launch_tc_pack(system_id, component_id, &msg , packet1.launch_code );
- mavlink_msg_start_launch_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_start_launch_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.launch_code );
- mavlink_msg_start_launch_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_start_launch_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_start_launch_tc_send(MAVLINK_COMM_1 , packet1.launch_code );
- mavlink_msg_start_launch_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_upload_setting_tc(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_UPLOAD_SETTING_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_upload_setting_tc_t packet_in = {
- 17.0,17
- };
- mavlink_upload_setting_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.setting = packet_in.setting;
- packet1.setting_id = packet_in.setting_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_UPLOAD_SETTING_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_UPLOAD_SETTING_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_upload_setting_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_upload_setting_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_upload_setting_tc_pack(system_id, component_id, &msg , packet1.setting_id , packet1.setting );
- mavlink_msg_upload_setting_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_upload_setting_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.setting_id , packet1.setting );
- mavlink_msg_upload_setting_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_upload_setting_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_upload_setting_tc_send(MAVLINK_COMM_1 , packet1.setting_id , packet1.setting );
- mavlink_msg_upload_setting_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_set_aerobrake_angle_tc(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_SET_AEROBRAKE_ANGLE_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_aerobrake_angle_tc_t packet_in = {
- 17.0
- };
- mavlink_set_aerobrake_angle_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.angle = packet_in.angle;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_AEROBRAKE_ANGLE_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_aerobrake_angle_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_aerobrake_angle_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_aerobrake_angle_tc_pack(system_id, component_id, &msg , packet1.angle );
- mavlink_msg_set_aerobrake_angle_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_aerobrake_angle_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.angle );
- mavlink_msg_set_aerobrake_angle_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_aerobrake_angle_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_aerobrake_angle_tc_send(MAVLINK_COMM_1 , packet1.angle );
- mavlink_msg_set_aerobrake_angle_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_set_reference_altitude(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_SET_REFERENCE_ALTITUDE >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_reference_altitude_t packet_in = {
- 17.0
- };
- mavlink_set_reference_altitude_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.ref_altitude = packet_in.ref_altitude;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_altitude_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_reference_altitude_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_altitude_pack(system_id, component_id, &msg , packet1.ref_altitude );
- mavlink_msg_set_reference_altitude_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_altitude_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.ref_altitude );
- mavlink_msg_set_reference_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; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_reference_altitude_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_altitude_send(MAVLINK_COMM_1 , packet1.ref_altitude );
- mavlink_msg_set_reference_altitude_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_set_reference_temperature_tc(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_SET_REFERENCE_TEMPERATURE_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_reference_temperature_tc_t packet_in = {
- 17.0
- };
- mavlink_set_reference_temperature_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.ref_temp = packet_in.ref_temp;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_temperature_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_reference_temperature_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_temperature_tc_pack(system_id, component_id, &msg , packet1.ref_temp );
- mavlink_msg_set_reference_temperature_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_temperature_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.ref_temp );
- mavlink_msg_set_reference_temperature_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_reference_temperature_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_temperature_tc_send(MAVLINK_COMM_1 , packet1.ref_temp );
- mavlink_msg_set_reference_temperature_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_set_deployment_altitude_tc(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_SET_DEPLOYMENT_ALTITUDE_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_deployment_altitude_tc_t packet_in = {
- 17.0
- };
- mavlink_set_deployment_altitude_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.dpl_altitude = packet_in.dpl_altitude;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_deployment_altitude_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_deployment_altitude_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_deployment_altitude_tc_pack(system_id, component_id, &msg , packet1.dpl_altitude );
- mavlink_msg_set_deployment_altitude_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_deployment_altitude_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.dpl_altitude );
- mavlink_msg_set_deployment_altitude_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_deployment_altitude_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_deployment_altitude_tc_send(MAVLINK_COMM_1 , packet1.dpl_altitude );
- mavlink_msg_set_deployment_altitude_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_set_initial_orientation_tc(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_SET_INITIAL_ORIENTATION_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_initial_orientation_tc_t packet_in = {
- 17.0,45.0,73.0
- };
- mavlink_set_initial_orientation_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.yaw = packet_in.yaw;
- packet1.pitch = packet_in.pitch;
- packet1.roll = packet_in.roll;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_initial_orientation_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_initial_orientation_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_initial_orientation_tc_pack(system_id, component_id, &msg , packet1.yaw , packet1.pitch , packet1.roll );
- mavlink_msg_set_initial_orientation_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_initial_orientation_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.yaw , packet1.pitch , packet1.roll );
- mavlink_msg_set_initial_orientation_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_initial_orientation_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_initial_orientation_tc_send(MAVLINK_COMM_1 , packet1.yaw , packet1.pitch , packet1.roll );
- mavlink_msg_set_initial_orientation_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_set_initial_coordinates_tc(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_SET_INITIAL_COORDINATES_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_initial_coordinates_tc_t packet_in = {
- 17.0,45.0
- };
- mavlink_set_initial_coordinates_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.latitude = packet_in.latitude;
- packet1.longitude = packet_in.longitude;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_initial_coordinates_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_initial_coordinates_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_initial_coordinates_tc_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude );
- mavlink_msg_set_initial_coordinates_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_initial_coordinates_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude );
- mavlink_msg_set_initial_coordinates_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_initial_coordinates_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_initial_coordinates_tc_send(MAVLINK_COMM_1 , packet1.latitude , packet1.longitude );
- mavlink_msg_set_initial_coordinates_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_telemetry_request_tc(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_TELEMETRY_REQUEST_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_telemetry_request_tc_t packet_in = {
- 5
- };
- mavlink_telemetry_request_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.board_id = packet_in.board_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_telemetry_request_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_telemetry_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_telemetry_request_tc_pack(system_id, component_id, &msg , packet1.board_id );
- mavlink_msg_telemetry_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_telemetry_request_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.board_id );
- mavlink_msg_telemetry_request_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_telemetry_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_telemetry_request_tc_send(MAVLINK_COMM_1 , packet1.board_id );
- mavlink_msg_telemetry_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_raw_event_tc(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_RAW_EVENT_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_raw_event_tc_t packet_in = {
- 5,72
- };
- mavlink_raw_event_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.Event_id = packet_in.Event_id;
- packet1.Topic_id = packet_in.Topic_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_raw_event_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_pack(system_id, component_id, &msg , packet1.Event_id , packet1.Topic_id );
- mavlink_msg_raw_event_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.Event_id , packet1.Topic_id );
- mavlink_msg_raw_event_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_raw_event_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_send(MAVLINK_COMM_1 , packet1.Event_id , packet1.Topic_id );
- mavlink_msg_raw_event_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_ack_tm(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_ACK_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ack_tm_t packet_in = {
- 5,72
- };
- mavlink_ack_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.recv_msgid = packet_in.recv_msgid;
- packet1.seq_ack = packet_in.seq_ack;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_ACK_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ACK_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_pack(system_id, component_id, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_ack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_ack_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_send(MAVLINK_COMM_1 , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_ack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_nack_tm(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_NACK_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_nack_tm_t packet_in = {
- 5,72
- };
- mavlink_nack_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.recv_msgid = packet_in.recv_msgid;
- packet1.seq_ack = packet_in.seq_ack;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_NACK_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NACK_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nack_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_nack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nack_tm_pack(system_id, component_id, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_nack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nack_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_nack_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_nack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nack_tm_send(MAVLINK_COMM_1 , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_nack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_sys_tm(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_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_sys_tm_t packet_in = {
- 93372036854775807ULL,29,96,163,230,41,108,175,242,53,120,187,254,65
- };
- mavlink_sys_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.death_stack = packet_in.death_stack;
- packet1.logger = packet_in.logger;
- packet1.ev_broker = packet_in.ev_broker;
- packet1.pin_obs = packet_in.pin_obs;
- packet1.radio = packet_in.radio;
- packet1.state_machines = packet_in.state_machines;
- packet1.sensors = packet_in.sensors;
- packet1.bmx160_status = packet_in.bmx160_status;
- packet1.ms5803_status = packet_in.ms5803_status;
- packet1.lis3mdl_status = packet_in.lis3mdl_status;
- packet1.gps_status = packet_in.gps_status;
- packet1.internal_adc_status = packet_in.internal_adc_status;
- packet1.ads1118_status = packet_in.ads1118_status;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SYS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SYS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sys_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_sys_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sys_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.death_stack , packet1.logger , packet1.ev_broker , packet1.pin_obs , packet1.radio , packet1.state_machines , packet1.sensors , packet1.bmx160_status , packet1.ms5803_status , packet1.lis3mdl_status , packet1.gps_status , packet1.internal_adc_status , packet1.ads1118_status );
- mavlink_msg_sys_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sys_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.death_stack , packet1.logger , packet1.ev_broker , packet1.pin_obs , packet1.radio , packet1.state_machines , packet1.sensors , packet1.bmx160_status , packet1.ms5803_status , packet1.lis3mdl_status , packet1.gps_status , packet1.internal_adc_status , packet1.ads1118_status );
- mavlink_msg_sys_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_sys_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sys_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.death_stack , packet1.logger , packet1.ev_broker , packet1.pin_obs , packet1.radio , packet1.state_machines , packet1.sensors , packet1.bmx160_status , packet1.ms5803_status , packet1.lis3mdl_status , packet1.gps_status , packet1.internal_adc_status , packet1.ads1118_status );
- mavlink_msg_sys_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_fmm_tm(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_FMM_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_fmm_tm_t packet_in = {
- 93372036854775807ULL,29
- };
- mavlink_fmm_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- 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_FMM_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FMM_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_fmm_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_fmm_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_fmm_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state );
- mavlink_msg_fmm_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_fmm_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state );
- mavlink_msg_fmm_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_fmm_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_fmm_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state );
- mavlink_msg_fmm_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_pin_obs_tm(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_PIN_OBS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_pin_obs_tm_t packet_in = {
- 93372036854775807ULL,93372036854776311ULL,93372036854776815ULL,93372036854777319ULL,101,168,235,46,113,180
- };
- mavlink_pin_obs_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.pin_launch_last_change = packet_in.pin_launch_last_change;
- packet1.pin_nosecone_last_change = packet_in.pin_nosecone_last_change;
- packet1.pin_dpl_servo_last_change = packet_in.pin_dpl_servo_last_change;
- packet1.pin_launch_num_changes = packet_in.pin_launch_num_changes;
- packet1.pin_launch_state = packet_in.pin_launch_state;
- packet1.pin_nosecone_num_changes = packet_in.pin_nosecone_num_changes;
- packet1.pin_nosecone_state = packet_in.pin_nosecone_state;
- packet1.pin_dpl_servo_num_changes = packet_in.pin_dpl_servo_num_changes;
- packet1.pin_dpl_servo_state = packet_in.pin_dpl_servo_state;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_PIN_OBS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PIN_OBS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pin_obs_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_pin_obs_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pin_obs_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.pin_launch_last_change , packet1.pin_launch_num_changes , packet1.pin_launch_state , packet1.pin_nosecone_last_change , packet1.pin_nosecone_num_changes , packet1.pin_nosecone_state , packet1.pin_dpl_servo_last_change , packet1.pin_dpl_servo_num_changes , packet1.pin_dpl_servo_state );
- mavlink_msg_pin_obs_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pin_obs_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.pin_launch_last_change , packet1.pin_launch_num_changes , packet1.pin_launch_state , packet1.pin_nosecone_last_change , packet1.pin_nosecone_num_changes , packet1.pin_nosecone_state , packet1.pin_dpl_servo_last_change , packet1.pin_dpl_servo_num_changes , packet1.pin_dpl_servo_state );
- mavlink_msg_pin_obs_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_pin_obs_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pin_obs_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.pin_launch_last_change , packet1.pin_launch_num_changes , packet1.pin_launch_state , packet1.pin_nosecone_last_change , packet1.pin_nosecone_num_changes , packet1.pin_nosecone_state , packet1.pin_dpl_servo_last_change , packet1.pin_dpl_servo_num_changes , packet1.pin_dpl_servo_state );
- mavlink_msg_pin_obs_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_logger_tm(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_LOGGER_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_logger_tm_t packet_in = {
- 93372036854775807ULL,963497880,963498088,963498296,963498504,963498712,963498920,963499128,963499336,963499544,19523
- };
- mavlink_logger_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.statTooLargeSamples = packet_in.statTooLargeSamples;
- packet1.statDroppedSamples = packet_in.statDroppedSamples;
- packet1.statQueuedSamples = packet_in.statQueuedSamples;
- packet1.statBufferFilled = packet_in.statBufferFilled;
- packet1.statBufferWritten = packet_in.statBufferWritten;
- packet1.statWriteFailed = packet_in.statWriteFailed;
- packet1.statWriteError = packet_in.statWriteError;
- packet1.statWriteTime = packet_in.statWriteTime;
- packet1.statMaxWriteTime = packet_in.statMaxWriteTime;
- packet1.statLogNumber = packet_in.statLogNumber;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_logger_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_logger_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_logger_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.statLogNumber , packet1.statTooLargeSamples , packet1.statDroppedSamples , packet1.statQueuedSamples , packet1.statBufferFilled , packet1.statBufferWritten , packet1.statWriteFailed , packet1.statWriteError , packet1.statWriteTime , packet1.statMaxWriteTime );
- mavlink_msg_logger_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_logger_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.statLogNumber , packet1.statTooLargeSamples , packet1.statDroppedSamples , packet1.statQueuedSamples , packet1.statBufferFilled , packet1.statBufferWritten , packet1.statWriteFailed , packet1.statWriteError , packet1.statWriteTime , packet1.statMaxWriteTime );
- mavlink_msg_logger_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_logger_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_logger_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.statLogNumber , packet1.statTooLargeSamples , packet1.statDroppedSamples , packet1.statQueuedSamples , packet1.statBufferFilled , packet1.statBufferWritten , packet1.statWriteFailed , packet1.statWriteError , packet1.statWriteTime , packet1.statMaxWriteTime );
- mavlink_msg_logger_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_tmtc_tm(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_TMTC_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_tmtc_tm_t packet_in = {
- 93372036854775807ULL,963497880,17859,17963,18067,18171,18275,199,10,77,144,211,22
- };
- mavlink_tmtc_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.parse_state = packet_in.parse_state;
- packet1.n_send_queue = packet_in.n_send_queue;
- packet1.max_send_queue = packet_in.max_send_queue;
- packet1.n_send_errors = packet_in.n_send_errors;
- packet1.packet_rx_success_count = packet_in.packet_rx_success_count;
- packet1.packet_rx_drop_count = packet_in.packet_rx_drop_count;
- packet1.msg_received = packet_in.msg_received;
- packet1.buffer_overrun = packet_in.buffer_overrun;
- packet1.parse_error = packet_in.parse_error;
- packet1.packet_idx = packet_in.packet_idx;
- packet1.current_rx_seq = packet_in.current_rx_seq;
- packet1.current_tx_seq = packet_in.current_tx_seq;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_TMTC_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TMTC_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_tmtc_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_tmtc_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_tmtc_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.n_send_queue , packet1.max_send_queue , packet1.n_send_errors , packet1.msg_received , packet1.buffer_overrun , packet1.parse_error , packet1.parse_state , packet1.packet_idx , packet1.current_rx_seq , packet1.current_tx_seq , packet1.packet_rx_success_count , packet1.packet_rx_drop_count );
- mavlink_msg_tmtc_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_tmtc_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.n_send_queue , packet1.max_send_queue , packet1.n_send_errors , packet1.msg_received , packet1.buffer_overrun , packet1.parse_error , packet1.parse_state , packet1.packet_idx , packet1.current_rx_seq , packet1.current_tx_seq , packet1.packet_rx_success_count , packet1.packet_rx_drop_count );
- mavlink_msg_tmtc_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_tmtc_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_tmtc_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.n_send_queue , packet1.max_send_queue , packet1.n_send_errors , packet1.msg_received , packet1.buffer_overrun , packet1.parse_error , packet1.parse_state , packet1.packet_idx , packet1.current_rx_seq , packet1.current_tx_seq , packet1.packet_rx_success_count , packet1.packet_rx_drop_count );
- mavlink_msg_tmtc_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_task_stats_tm(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_TASK_STATS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_task_stats_tm_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,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0
- };
- mavlink_task_stats_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.task_sensors_6ms_min = packet_in.task_sensors_6ms_min;
- packet1.task_sensors_6ms_max = packet_in.task_sensors_6ms_max;
- packet1.task_sensors_6ms_mean = packet_in.task_sensors_6ms_mean;
- packet1.task_sensors_6ms_stddev = packet_in.task_sensors_6ms_stddev;
- packet1.task_sensors_15ms_min = packet_in.task_sensors_15ms_min;
- packet1.task_sensors_15ms_max = packet_in.task_sensors_15ms_max;
- packet1.task_sensors_15ms_mean = packet_in.task_sensors_15ms_mean;
- packet1.task_sensors_15ms_stddev = packet_in.task_sensors_15ms_stddev;
- packet1.task_sensors_20ms_min = packet_in.task_sensors_20ms_min;
- packet1.task_sensors_20ms_max = packet_in.task_sensors_20ms_max;
- packet1.task_sensors_20ms_mean = packet_in.task_sensors_20ms_mean;
- packet1.task_sensors_20ms_stddev = packet_in.task_sensors_20ms_stddev;
- packet1.task_sensors_24ms_min = packet_in.task_sensors_24ms_min;
- packet1.task_sensors_24ms_max = packet_in.task_sensors_24ms_max;
- packet1.task_sensors_24ms_mean = packet_in.task_sensors_24ms_mean;
- packet1.task_sensors_24ms_stddev = packet_in.task_sensors_24ms_stddev;
- packet1.task_sensors_40ms_min = packet_in.task_sensors_40ms_min;
- packet1.task_sensors_40ms_max = packet_in.task_sensors_40ms_max;
- packet1.task_sensors_40ms_mean = packet_in.task_sensors_40ms_mean;
- packet1.task_sensors_40ms_stddev = packet_in.task_sensors_40ms_stddev;
- packet1.task_sensors_1000ms_min = packet_in.task_sensors_1000ms_min;
- packet1.task_sensors_1000ms_max = packet_in.task_sensors_1000ms_max;
- packet1.task_sensors_1000ms_mean = packet_in.task_sensors_1000ms_mean;
- packet1.task_sensors_1000ms_stddev = packet_in.task_sensors_1000ms_stddev;
- packet1.task_ada_min = packet_in.task_ada_min;
- packet1.task_ada_max = packet_in.task_ada_max;
- packet1.task_ada_mean = packet_in.task_ada_mean;
- packet1.task_ada_stddev = packet_in.task_ada_stddev;
- packet1.task_nas_min = packet_in.task_nas_min;
- packet1.task_nas_max = packet_in.task_nas_max;
- packet1.task_nas_mean = packet_in.task_nas_mean;
- packet1.task_nas_stddev = packet_in.task_nas_stddev;
- packet1.task_abk_min = packet_in.task_abk_min;
- packet1.task_abk_max = packet_in.task_abk_max;
- packet1.task_abk_mean = packet_in.task_abk_mean;
- packet1.task_abk_stddev = packet_in.task_abk_stddev;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_task_stats_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_task_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_task_stats_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.task_sensors_6ms_min , packet1.task_sensors_6ms_max , packet1.task_sensors_6ms_mean , packet1.task_sensors_6ms_stddev , packet1.task_sensors_15ms_min , packet1.task_sensors_15ms_max , packet1.task_sensors_15ms_mean , packet1.task_sensors_15ms_stddev , packet1.task_sensors_20ms_min , packet1.task_sensors_20ms_max , packet1.task_sensors_20ms_mean , packet1.task_sensors_20ms_stddev , packet1.task_sensors_24ms_min , packet1.task_sensors_24ms_max , packet1.task_sensors_24ms_mean , packet1.task_sensors_24ms_stddev , packet1.task_sensors_40ms_min , packet1.task_sensors_40ms_max , packet1.task_sensors_40ms_mean , packet1.task_sensors_40ms_stddev , packet1.task_sensors_1000ms_min , packet1.task_sensors_1000ms_max , packet1.task_sensors_1000ms_mean , packet1.task_sensors_1000ms_stddev , packet1.task_ada_min , packet1.task_ada_max , packet1.task_ada_mean , packet1.task_ada_stddev , packet1.task_nas_min , packet1.task_nas_max , packet1.task_nas_mean , packet1.task_nas_stddev , packet1.task_abk_min , packet1.task_abk_max , packet1.task_abk_mean , packet1.task_abk_stddev );
- mavlink_msg_task_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_task_stats_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.task_sensors_6ms_min , packet1.task_sensors_6ms_max , packet1.task_sensors_6ms_mean , packet1.task_sensors_6ms_stddev , packet1.task_sensors_15ms_min , packet1.task_sensors_15ms_max , packet1.task_sensors_15ms_mean , packet1.task_sensors_15ms_stddev , packet1.task_sensors_20ms_min , packet1.task_sensors_20ms_max , packet1.task_sensors_20ms_mean , packet1.task_sensors_20ms_stddev , packet1.task_sensors_24ms_min , packet1.task_sensors_24ms_max , packet1.task_sensors_24ms_mean , packet1.task_sensors_24ms_stddev , packet1.task_sensors_40ms_min , packet1.task_sensors_40ms_max , packet1.task_sensors_40ms_mean , packet1.task_sensors_40ms_stddev , packet1.task_sensors_1000ms_min , packet1.task_sensors_1000ms_max , packet1.task_sensors_1000ms_mean , packet1.task_sensors_1000ms_stddev , packet1.task_ada_min , packet1.task_ada_max , packet1.task_ada_mean , packet1.task_ada_stddev , packet1.task_nas_min , packet1.task_nas_max , packet1.task_nas_mean , packet1.task_nas_stddev , packet1.task_abk_min , packet1.task_abk_max , packet1.task_abk_mean , packet1.task_abk_stddev );
- mavlink_msg_task_stats_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_task_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_task_stats_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.task_sensors_6ms_min , packet1.task_sensors_6ms_max , packet1.task_sensors_6ms_mean , packet1.task_sensors_6ms_stddev , packet1.task_sensors_15ms_min , packet1.task_sensors_15ms_max , packet1.task_sensors_15ms_mean , packet1.task_sensors_15ms_stddev , packet1.task_sensors_20ms_min , packet1.task_sensors_20ms_max , packet1.task_sensors_20ms_mean , packet1.task_sensors_20ms_stddev , packet1.task_sensors_24ms_min , packet1.task_sensors_24ms_max , packet1.task_sensors_24ms_mean , packet1.task_sensors_24ms_stddev , packet1.task_sensors_40ms_min , packet1.task_sensors_40ms_max , packet1.task_sensors_40ms_mean , packet1.task_sensors_40ms_stddev , packet1.task_sensors_1000ms_min , packet1.task_sensors_1000ms_max , packet1.task_sensors_1000ms_mean , packet1.task_sensors_1000ms_stddev , packet1.task_ada_min , packet1.task_ada_max , packet1.task_ada_mean , packet1.task_ada_stddev , packet1.task_nas_min , packet1.task_nas_max , packet1.task_nas_mean , packet1.task_nas_stddev , packet1.task_abk_min , packet1.task_abk_max , packet1.task_abk_mean , packet1.task_abk_stddev );
- mavlink_msg_task_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_dpl_tm(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_DPL_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_dpl_tm_t packet_in = {
- 93372036854775807ULL,73.0,41,108
- };
- mavlink_dpl_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.servo_position = packet_in.servo_position;
- packet1.fsm_state = packet_in.fsm_state;
- packet1.cutters_enabled = packet_in.cutters_enabled;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_DPL_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DPL_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_dpl_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_dpl_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_dpl_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.fsm_state , packet1.cutters_enabled , packet1.servo_position );
- mavlink_msg_dpl_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_dpl_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.fsm_state , packet1.cutters_enabled , packet1.servo_position );
- mavlink_msg_dpl_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_dpl_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_dpl_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.fsm_state , packet1.cutters_enabled , packet1.servo_position );
- mavlink_msg_dpl_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_ada_tm(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_ADA_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ada_tm_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,161,228,39,106
- };
- mavlink_ada_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.target_dpl_altitude = packet_in.target_dpl_altitude;
- packet1.kalman_x0 = packet_in.kalman_x0;
- packet1.kalman_x1 = packet_in.kalman_x1;
- packet1.kalman_x2 = packet_in.kalman_x2;
- packet1.vert_speed = packet_in.vert_speed;
- packet1.msl_altitude = packet_in.msl_altitude;
- packet1.ref_pressure = packet_in.ref_pressure;
- packet1.ref_altitude = packet_in.ref_altitude;
- packet1.ref_temperature = packet_in.ref_temperature;
- packet1.msl_pressure = packet_in.msl_pressure;
- packet1.msl_temperature = packet_in.msl_temperature;
- packet1.state = packet_in.state;
- packet1.apogee_reached = packet_in.apogee_reached;
- packet1.aerobrakes_disabled = packet_in.aerobrakes_disabled;
- packet1.dpl_altitude_reached = packet_in.dpl_altitude_reached;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_ADA_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ADA_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ada_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ada_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ada_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state , packet1.apogee_reached , packet1.aerobrakes_disabled , packet1.dpl_altitude_reached , packet1.target_dpl_altitude , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.vert_speed , packet1.msl_altitude , packet1.ref_pressure , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_pressure , packet1.msl_temperature );
- mavlink_msg_ada_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ada_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state , packet1.apogee_reached , packet1.aerobrakes_disabled , packet1.dpl_altitude_reached , packet1.target_dpl_altitude , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.vert_speed , packet1.msl_altitude , packet1.ref_pressure , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_pressure , packet1.msl_temperature );
- mavlink_msg_ada_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ada_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ada_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state , packet1.apogee_reached , packet1.aerobrakes_disabled , packet1.dpl_altitude_reached , packet1.target_dpl_altitude , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.vert_speed , packet1.msl_altitude , packet1.ref_pressure , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_pressure , packet1.msl_temperature );
- mavlink_msg_ada_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_abk_tm(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_ABK_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_abk_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,101,168
- };
- mavlink_abk_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.servo_position = packet_in.servo_position;
- packet1.estimated_cd = packet_in.estimated_cd;
- packet1.pid_error = packet_in.pid_error;
- packet1.z = packet_in.z;
- packet1.vz = packet_in.vz;
- packet1.v_mod = packet_in.v_mod;
- packet1.state = packet_in.state;
- packet1.trajectory = packet_in.trajectory;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_ABK_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ABK_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_abk_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_abk_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_abk_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state , packet1.servo_position , packet1.estimated_cd , packet1.pid_error , packet1.z , packet1.vz , packet1.v_mod , packet1.trajectory );
- mavlink_msg_abk_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_abk_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state , packet1.servo_position , packet1.estimated_cd , packet1.pid_error , packet1.z , packet1.vz , packet1.v_mod , packet1.trajectory );
- mavlink_msg_abk_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_abk_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_abk_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state , packet1.servo_position , packet1.estimated_cd , packet1.pid_error , packet1.z , packet1.vz , packet1.v_mod , packet1.trajectory );
- mavlink_msg_abk_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_nas_tm(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_NAS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_nas_tm_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,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,121
- };
- mavlink_nas_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.x0 = packet_in.x0;
- packet1.x1 = packet_in.x1;
- packet1.x2 = packet_in.x2;
- packet1.x3 = packet_in.x3;
- packet1.x4 = packet_in.x4;
- packet1.x5 = packet_in.x5;
- packet1.x6 = packet_in.x6;
- packet1.x7 = packet_in.x7;
- packet1.x8 = packet_in.x8;
- packet1.x9 = packet_in.x9;
- packet1.x10 = packet_in.x10;
- packet1.x11 = packet_in.x11;
- packet1.x12 = packet_in.x12;
- packet1.ref_pressure = packet_in.ref_pressure;
- packet1.ref_temperature = packet_in.ref_temperature;
- packet1.ref_latitude = packet_in.ref_latitude;
- packet1.ref_longitude = packet_in.ref_longitude;
- packet1.ref_accel_x = packet_in.ref_accel_x;
- packet1.ref_accel_y = packet_in.ref_accel_y;
- packet1.ref_accel_z = packet_in.ref_accel_z;
- packet1.ref_mag_x = packet_in.ref_mag_x;
- packet1.ref_mag_y = packet_in.ref_mag_y;
- packet1.ref_mag_z = packet_in.ref_mag_z;
- packet1.triad_roll = packet_in.triad_roll;
- packet1.triad_pitch = packet_in.triad_pitch;
- packet1.triad_yaw = packet_in.triad_yaw;
- packet1.roll = packet_in.roll;
- packet1.pitch = packet_in.pitch;
- packet1.yaw = packet_in.yaw;
- 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_NAS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NAS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nas_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_nas_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nas_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state , packet1.x0 , packet1.x1 , packet1.x2 , packet1.x3 , packet1.x4 , packet1.x5 , packet1.x6 , packet1.x7 , packet1.x8 , packet1.x9 , packet1.x10 , packet1.x11 , packet1.x12 , packet1.ref_pressure , packet1.ref_temperature , packet1.ref_latitude , packet1.ref_longitude , packet1.ref_accel_x , packet1.ref_accel_y , packet1.ref_accel_z , packet1.ref_mag_x , packet1.ref_mag_y , packet1.ref_mag_z , packet1.triad_roll , packet1.triad_pitch , packet1.triad_yaw , packet1.roll , packet1.pitch , packet1.yaw );
- mavlink_msg_nas_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nas_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state , packet1.x0 , packet1.x1 , packet1.x2 , packet1.x3 , packet1.x4 , packet1.x5 , packet1.x6 , packet1.x7 , packet1.x8 , packet1.x9 , packet1.x10 , packet1.x11 , packet1.x12 , packet1.ref_pressure , packet1.ref_temperature , packet1.ref_latitude , packet1.ref_longitude , packet1.ref_accel_x , packet1.ref_accel_y , packet1.ref_accel_z , packet1.ref_mag_x , packet1.ref_mag_y , packet1.ref_mag_z , packet1.triad_roll , packet1.triad_pitch , packet1.triad_yaw , packet1.roll , packet1.pitch , packet1.yaw );
- mavlink_msg_nas_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_nas_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nas_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state , packet1.x0 , packet1.x1 , packet1.x2 , packet1.x3 , packet1.x4 , packet1.x5 , packet1.x6 , packet1.x7 , packet1.x8 , packet1.x9 , packet1.x10 , packet1.x11 , packet1.x12 , packet1.ref_pressure , packet1.ref_temperature , packet1.ref_latitude , packet1.ref_longitude , packet1.ref_accel_x , packet1.ref_accel_y , packet1.ref_accel_z , packet1.ref_mag_x , packet1.ref_mag_y , packet1.ref_mag_z , packet1.triad_roll , packet1.triad_pitch , packet1.triad_yaw , packet1.roll , packet1.pitch , packet1.yaw );
- mavlink_msg_nas_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_adc_tm(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_ADC_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_adc_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0
- };
- mavlink_adc_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.pitot_pressure = packet_in.pitot_pressure;
- packet1.dpl_pressure = packet_in.dpl_pressure;
- packet1.static_pressure = packet_in.static_pressure;
- packet1.bat_voltage = packet_in.bat_voltage;
- packet1.bat_voltage_5v = packet_in.bat_voltage_5v;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_ADC_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ADC_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adc_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_adc_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adc_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.pitot_pressure , packet1.dpl_pressure , packet1.static_pressure , packet1.bat_voltage , packet1.bat_voltage_5v );
- mavlink_msg_adc_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adc_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.pitot_pressure , packet1.dpl_pressure , packet1.static_pressure , packet1.bat_voltage , packet1.bat_voltage_5v );
- mavlink_msg_adc_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_adc_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adc_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.pitot_pressure , packet1.dpl_pressure , packet1.static_pressure , packet1.bat_voltage , packet1.bat_voltage_5v );
- mavlink_msg_adc_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_ms5803_tm(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_MS5803_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ms5803_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0
- };
- mavlink_ms5803_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.pressure = packet_in.pressure;
- 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_MS5803_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MS5803_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ms5803_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ms5803_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ms5803_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.pressure , packet1.temperature );
- mavlink_msg_ms5803_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ms5803_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.pressure , packet1.temperature );
- mavlink_msg_ms5803_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ms5803_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ms5803_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.pressure , packet1.temperature );
- mavlink_msg_ms5803_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_bmx160_tm(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_BMX160_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_bmx160_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0
- };
- mavlink_bmx160_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.acc_x = packet_in.acc_x;
- packet1.acc_y = packet_in.acc_y;
- packet1.acc_z = packet_in.acc_z;
- packet1.gyro_x = packet_in.gyro_x;
- packet1.gyro_y = packet_in.gyro_y;
- packet1.gyro_z = packet_in.gyro_z;
- packet1.mag_x = packet_in.mag_x;
- packet1.mag_y = packet_in.mag_y;
- packet1.mag_z = packet_in.mag_z;
- packet1.temp = packet_in.temp;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_BMX160_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_BMX160_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_bmx160_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_bmx160_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_bmx160_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.temp );
- mavlink_msg_bmx160_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_bmx160_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.temp );
- mavlink_msg_bmx160_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_bmx160_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_bmx160_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.temp );
- mavlink_msg_bmx160_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_lis3mdl_tm(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_LIS3MDL_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_lis3mdl_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0
- };
- mavlink_lis3mdl_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.mag_x = packet_in.mag_x;
- packet1.mag_y = packet_in.mag_y;
- packet1.mag_z = packet_in.mag_z;
- packet1.temp = packet_in.temp;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_LIS3MDL_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LIS3MDL_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_lis3mdl_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_lis3mdl_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_lis3mdl_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.temp );
- mavlink_msg_lis3mdl_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_lis3mdl_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.temp );
- mavlink_msg_lis3mdl_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_lis3mdl_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_lis3mdl_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.temp );
- mavlink_msg_lis3mdl_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_gps_tm(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_GPS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_gps_tm_t packet_in = {
- 93372036854775807ULL,179.0,235.0,291.0,241.0,269.0,297.0,325.0,353.0,161,228
- };
- mavlink_gps_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.latitude = packet_in.latitude;
- packet1.longitude = packet_in.longitude;
- packet1.height = packet_in.height;
- packet1.vel_north = packet_in.vel_north;
- packet1.vel_east = packet_in.vel_east;
- packet1.vel_down = packet_in.vel_down;
- packet1.speed = packet_in.speed;
- packet1.track = packet_in.track;
- packet1.fix = packet_in.fix;
- packet1.n_satellites = packet_in.n_satellites;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_GPS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gps_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_gps_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gps_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.fix , packet1.latitude , packet1.longitude , packet1.height , packet1.vel_north , packet1.vel_east , packet1.vel_down , packet1.speed , packet1.track , packet1.n_satellites );
- mavlink_msg_gps_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gps_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.fix , packet1.latitude , packet1.longitude , packet1.height , packet1.vel_north , packet1.vel_east , packet1.vel_down , packet1.speed , packet1.track , packet1.n_satellites );
- mavlink_msg_gps_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_gps_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gps_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.fix , packet1.latitude , packet1.longitude , packet1.height , packet1.vel_north , packet1.vel_east , packet1.vel_down , packet1.speed , packet1.track , packet1.n_satellites );
- mavlink_msg_gps_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_hr_tm(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_HR_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_hr_tm_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,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,1081.0,217,28,95,162,229,40,107,174,241,52
- };
- mavlink_hr_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.pressure_ada = packet_in.pressure_ada;
- packet1.pressure_digi = packet_in.pressure_digi;
- packet1.pressure_static = packet_in.pressure_static;
- packet1.pressure_dpl = packet_in.pressure_dpl;
- packet1.airspeed_pitot = packet_in.airspeed_pitot;
- packet1.msl_altitude = packet_in.msl_altitude;
- packet1.ada_vert_speed = packet_in.ada_vert_speed;
- packet1.ada_vert_accel = packet_in.ada_vert_accel;
- packet1.acc_x = packet_in.acc_x;
- packet1.acc_y = packet_in.acc_y;
- packet1.acc_z = packet_in.acc_z;
- packet1.gyro_x = packet_in.gyro_x;
- packet1.gyro_y = packet_in.gyro_y;
- packet1.gyro_z = packet_in.gyro_z;
- packet1.mag_x = packet_in.mag_x;
- packet1.mag_y = packet_in.mag_y;
- packet1.mag_z = packet_in.mag_z;
- packet1.gps_lat = packet_in.gps_lat;
- packet1.gps_lon = packet_in.gps_lon;
- packet1.gps_alt = packet_in.gps_alt;
- packet1.vbat = packet_in.vbat;
- packet1.vsupply_5v = packet_in.vsupply_5v;
- packet1.temperature = packet_in.temperature;
- packet1.ab_angle = packet_in.ab_angle;
- packet1.ab_estimated_cd = packet_in.ab_estimated_cd;
- packet1.nas_x = packet_in.nas_x;
- packet1.nas_y = packet_in.nas_y;
- packet1.nas_z = packet_in.nas_z;
- packet1.nas_vx = packet_in.nas_vx;
- packet1.nas_vy = packet_in.nas_vy;
- packet1.nas_vz = packet_in.nas_vz;
- packet1.nas_roll = packet_in.nas_roll;
- packet1.nas_pitch = packet_in.nas_pitch;
- packet1.nas_yaw = packet_in.nas_yaw;
- packet1.nas_bias0 = packet_in.nas_bias0;
- packet1.nas_bias1 = packet_in.nas_bias1;
- packet1.nas_bias2 = packet_in.nas_bias2;
- packet1.ada_state = packet_in.ada_state;
- packet1.fmm_state = packet_in.fmm_state;
- packet1.dpl_state = packet_in.dpl_state;
- packet1.ab_state = packet_in.ab_state;
- packet1.nas_state = packet_in.nas_state;
- packet1.gps_fix = packet_in.gps_fix;
- packet1.pin_launch = packet_in.pin_launch;
- packet1.pin_nosecone = packet_in.pin_nosecone;
- packet1.servo_sensor = packet_in.servo_sensor;
- packet1.logger_error = packet_in.logger_error;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_HR_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HR_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_hr_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_hr_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_hr_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.ab_state , packet1.nas_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.msl_altitude , packet1.ada_vert_speed , packet1.ada_vert_accel , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.vbat , packet1.vsupply_5v , packet1.temperature , packet1.pin_launch , packet1.pin_nosecone , packet1.servo_sensor , packet1.ab_angle , packet1.ab_estimated_cd , packet1.nas_x , packet1.nas_y , packet1.nas_z , packet1.nas_vx , packet1.nas_vy , packet1.nas_vz , packet1.nas_roll , packet1.nas_pitch , packet1.nas_yaw , packet1.nas_bias0 , packet1.nas_bias1 , packet1.nas_bias2 , packet1.logger_error );
- mavlink_msg_hr_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_hr_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.ab_state , packet1.nas_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.msl_altitude , packet1.ada_vert_speed , packet1.ada_vert_accel , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.vbat , packet1.vsupply_5v , packet1.temperature , packet1.pin_launch , packet1.pin_nosecone , packet1.servo_sensor , packet1.ab_angle , packet1.ab_estimated_cd , packet1.nas_x , packet1.nas_y , packet1.nas_z , packet1.nas_vx , packet1.nas_vy , packet1.nas_vz , packet1.nas_roll , packet1.nas_pitch , packet1.nas_yaw , packet1.nas_bias0 , packet1.nas_bias1 , packet1.nas_bias2 , packet1.logger_error );
- mavlink_msg_hr_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_hr_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_hr_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.ab_state , packet1.nas_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.msl_altitude , packet1.ada_vert_speed , packet1.ada_vert_accel , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.vbat , packet1.vsupply_5v , packet1.temperature , packet1.pin_launch , packet1.pin_nosecone , packet1.servo_sensor , packet1.ab_angle , packet1.ab_estimated_cd , packet1.nas_x , packet1.nas_y , packet1.nas_z , packet1.nas_vx , packet1.nas_vy , packet1.nas_vz , packet1.nas_roll , packet1.nas_pitch , packet1.nas_yaw , packet1.nas_bias0 , packet1.nas_bias1 , packet1.nas_bias2 , packet1.logger_error );
- mavlink_msg_hr_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_lr_tm(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_LR_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_lr_tm_t packet_in = {
- 93372036854775807ULL,93372036854776311ULL,93372036854776815ULL,93372036854777319ULL,93372036854777823ULL,93372036854778327ULL,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,963503496
- };
- mavlink_lr_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.liftoff_ts = packet_in.liftoff_ts;
- packet1.liftoff_max_acc_ts = packet_in.liftoff_max_acc_ts;
- packet1.max_z_speed_ts = packet_in.max_z_speed_ts;
- packet1.apogee_ts = packet_in.apogee_ts;
- packet1.drogue_dpl_ts = packet_in.drogue_dpl_ts;
- packet1.main_dpl_altitude_ts = packet_in.main_dpl_altitude_ts;
- packet1.liftoff_max_acc = packet_in.liftoff_max_acc;
- packet1.max_z_speed = packet_in.max_z_speed;
- packet1.max_airspeed_pitot = packet_in.max_airspeed_pitot;
- packet1.max_speed_altitude = packet_in.max_speed_altitude;
- packet1.apogee_lat = packet_in.apogee_lat;
- packet1.apogee_lon = packet_in.apogee_lon;
- packet1.static_min_pressure = packet_in.static_min_pressure;
- packet1.digital_min_pressure = packet_in.digital_min_pressure;
- packet1.ada_min_pressure = packet_in.ada_min_pressure;
- packet1.baro_max_altitutde = packet_in.baro_max_altitutde;
- packet1.gps_max_altitude = packet_in.gps_max_altitude;
- packet1.drogue_dpl_max_acc = packet_in.drogue_dpl_max_acc;
- packet1.dpl_vane_max_pressure = packet_in.dpl_vane_max_pressure;
- packet1.main_dpl_altitude = packet_in.main_dpl_altitude;
- packet1.main_dpl_zspeed = packet_in.main_dpl_zspeed;
- packet1.main_dpl_acc = packet_in.main_dpl_acc;
- packet1.cpu_load = packet_in.cpu_load;
- packet1.free_heap = packet_in.free_heap;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_LR_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LR_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_lr_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_lr_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_lr_tm_pack(system_id, component_id, &msg , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.static_min_pressure , packet1.digital_min_pressure , packet1.ada_min_pressure , packet1.baro_max_altitutde , packet1.gps_max_altitude , packet1.drogue_dpl_ts , packet1.drogue_dpl_max_acc , packet1.dpl_vane_max_pressure , packet1.main_dpl_altitude_ts , packet1.main_dpl_altitude , packet1.main_dpl_zspeed , packet1.main_dpl_acc , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_lr_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_lr_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.static_min_pressure , packet1.digital_min_pressure , packet1.ada_min_pressure , packet1.baro_max_altitutde , packet1.gps_max_altitude , packet1.drogue_dpl_ts , packet1.drogue_dpl_max_acc , packet1.dpl_vane_max_pressure , packet1.main_dpl_altitude_ts , packet1.main_dpl_altitude , packet1.main_dpl_zspeed , packet1.main_dpl_acc , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_lr_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_lr_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_lr_tm_send(MAVLINK_COMM_1 , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.static_min_pressure , packet1.digital_min_pressure , packet1.ada_min_pressure , packet1.baro_max_altitutde , packet1.gps_max_altitude , packet1.drogue_dpl_ts , packet1.drogue_dpl_max_acc , packet1.dpl_vane_max_pressure , packet1.main_dpl_altitude_ts , packet1.main_dpl_altitude , packet1.main_dpl_zspeed , packet1.main_dpl_acc , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_lr_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_test_tm(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_TEST_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_test_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,77
- };
- mavlink_test_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.pressure_hw = packet_in.pressure_hw;
- packet1.temp_analog = packet_in.temp_analog;
- packet1.temp_imu = packet_in.temp_imu;
- packet1.battery_volt = packet_in.battery_volt;
- packet1.gps_nsats = packet_in.gps_nsats;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_TEST_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TEST_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_test_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_test_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_test_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.pressure_hw , packet1.gps_nsats , packet1.temp_analog , packet1.temp_imu , packet1.battery_volt );
- mavlink_msg_test_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_test_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.pressure_hw , packet1.gps_nsats , packet1.temp_analog , packet1.temp_imu , packet1.battery_volt );
- mavlink_msg_test_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_test_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_test_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.pressure_hw , packet1.gps_nsats , packet1.temp_analog , packet1.temp_imu , packet1.battery_volt );
- mavlink_msg_test_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_windtunnel_tm(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_WINDTUNNEL_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_windtunnel_tm_t packet_in = {
- 93372036854775807ULL,179.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0
- };
- mavlink_windtunnel_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.pressure_dpl = packet_in.pressure_dpl;
- packet1.pressure_digital = packet_in.pressure_digital;
- packet1.pressure_differential = packet_in.pressure_differential;
- packet1.pressure_static = packet_in.pressure_static;
- packet1.ab_angle = packet_in.ab_angle;
- packet1.wind_speed = packet_in.wind_speed;
- packet1.log_status = packet_in.log_status;
- packet1.log_num = packet_in.log_num;
- packet1.last_RSSI = packet_in.last_RSSI;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_WINDTUNNEL_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_WINDTUNNEL_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_windtunnel_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_windtunnel_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_windtunnel_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.pressure_digital , packet1.pressure_differential , packet1.pressure_static , packet1.pressure_dpl , packet1.ab_angle , packet1.wind_speed , packet1.log_status , packet1.log_num , packet1.last_RSSI );
- mavlink_msg_windtunnel_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_windtunnel_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.pressure_digital , packet1.pressure_differential , packet1.pressure_static , packet1.pressure_dpl , packet1.ab_angle , packet1.wind_speed , packet1.log_status , packet1.log_num , packet1.last_RSSI );
- mavlink_msg_windtunnel_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_windtunnel_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_windtunnel_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.pressure_digital , packet1.pressure_differential , packet1.pressure_static , packet1.pressure_dpl , packet1.ab_angle , packet1.wind_speed , packet1.log_status , packet1.log_num , packet1.last_RSSI );
- mavlink_msg_windtunnel_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_sensors_tm(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_SENSORS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_sensors_tm_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,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,61
- };
- mavlink_sensors_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.bmx160_acc_x = packet_in.bmx160_acc_x;
- packet1.bmx160_acc_y = packet_in.bmx160_acc_y;
- packet1.bmx160_acc_z = packet_in.bmx160_acc_z;
- packet1.bmx160_gyro_x = packet_in.bmx160_gyro_x;
- packet1.bmx160_gyro_y = packet_in.bmx160_gyro_y;
- packet1.bmx160_gyro_z = packet_in.bmx160_gyro_z;
- packet1.bmx160_mag_x = packet_in.bmx160_mag_x;
- packet1.bmx160_mag_y = packet_in.bmx160_mag_y;
- packet1.bmx160_mag_z = packet_in.bmx160_mag_z;
- packet1.bmx160_temp = packet_in.bmx160_temp;
- packet1.ms5803_press = packet_in.ms5803_press;
- packet1.ms5803_temp = packet_in.ms5803_temp;
- packet1.dpl_press = packet_in.dpl_press;
- packet1.pitot_press = packet_in.pitot_press;
- packet1.static_press = packet_in.static_press;
- packet1.lis3mdl_mag_x = packet_in.lis3mdl_mag_x;
- packet1.lis3mdl_mag_y = packet_in.lis3mdl_mag_y;
- packet1.lis3mdl_mag_z = packet_in.lis3mdl_mag_z;
- packet1.lis3mdl_temp = packet_in.lis3mdl_temp;
- packet1.gps_lat = packet_in.gps_lat;
- packet1.gps_lon = packet_in.gps_lon;
- packet1.gps_alt = packet_in.gps_alt;
- packet1.vbat = packet_in.vbat;
- packet1.vsupply_5v = packet_in.vsupply_5v;
- packet1.gps_fix = packet_in.gps_fix;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SENSORS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SENSORS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensors_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_sensors_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensors_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.bmx160_acc_x , packet1.bmx160_acc_y , packet1.bmx160_acc_z , packet1.bmx160_gyro_x , packet1.bmx160_gyro_y , packet1.bmx160_gyro_z , packet1.bmx160_mag_x , packet1.bmx160_mag_y , packet1.bmx160_mag_z , packet1.bmx160_temp , packet1.ms5803_press , packet1.ms5803_temp , packet1.dpl_press , packet1.pitot_press , packet1.static_press , packet1.lis3mdl_mag_x , packet1.lis3mdl_mag_y , packet1.lis3mdl_mag_z , packet1.lis3mdl_temp , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.gps_fix , packet1.vbat , packet1.vsupply_5v );
- mavlink_msg_sensors_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensors_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.bmx160_acc_x , packet1.bmx160_acc_y , packet1.bmx160_acc_z , packet1.bmx160_gyro_x , packet1.bmx160_gyro_y , packet1.bmx160_gyro_z , packet1.bmx160_mag_x , packet1.bmx160_mag_y , packet1.bmx160_mag_z , packet1.bmx160_temp , packet1.ms5803_press , packet1.ms5803_temp , packet1.dpl_press , packet1.pitot_press , packet1.static_press , packet1.lis3mdl_mag_x , packet1.lis3mdl_mag_y , packet1.lis3mdl_mag_z , packet1.lis3mdl_temp , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.gps_fix , packet1.vbat , packet1.vsupply_5v );
- mavlink_msg_sensors_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_sensors_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensors_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.bmx160_acc_x , packet1.bmx160_acc_y , packet1.bmx160_acc_z , packet1.bmx160_gyro_x , packet1.bmx160_gyro_y , packet1.bmx160_gyro_z , packet1.bmx160_mag_x , packet1.bmx160_mag_y , packet1.bmx160_mag_z , packet1.bmx160_temp , packet1.ms5803_press , packet1.ms5803_temp , packet1.dpl_press , packet1.pitot_press , packet1.static_press , packet1.lis3mdl_mag_x , packet1.lis3mdl_mag_y , packet1.lis3mdl_mag_z , packet1.lis3mdl_temp , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.gps_fix , packet1.vbat , packet1.vsupply_5v );
- mavlink_msg_sensors_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_lynx(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
-{
- mavlink_test_ping_tc(system_id, component_id, last_msg);
- mavlink_test_noarg_tc(system_id, component_id, last_msg);
- mavlink_test_start_launch_tc(system_id, component_id, last_msg);
- mavlink_test_upload_setting_tc(system_id, component_id, last_msg);
- mavlink_test_set_aerobrake_angle_tc(system_id, component_id, last_msg);
- mavlink_test_set_reference_altitude(system_id, component_id, last_msg);
- mavlink_test_set_reference_temperature_tc(system_id, component_id, last_msg);
- mavlink_test_set_deployment_altitude_tc(system_id, component_id, last_msg);
- mavlink_test_set_initial_orientation_tc(system_id, component_id, last_msg);
- mavlink_test_set_initial_coordinates_tc(system_id, component_id, last_msg);
- mavlink_test_telemetry_request_tc(system_id, component_id, last_msg);
- mavlink_test_raw_event_tc(system_id, component_id, last_msg);
- mavlink_test_ack_tm(system_id, component_id, last_msg);
- mavlink_test_nack_tm(system_id, component_id, last_msg);
- mavlink_test_sys_tm(system_id, component_id, last_msg);
- mavlink_test_fmm_tm(system_id, component_id, last_msg);
- mavlink_test_pin_obs_tm(system_id, component_id, last_msg);
- mavlink_test_logger_tm(system_id, component_id, last_msg);
- mavlink_test_tmtc_tm(system_id, component_id, last_msg);
- mavlink_test_task_stats_tm(system_id, component_id, last_msg);
- mavlink_test_dpl_tm(system_id, component_id, last_msg);
- mavlink_test_ada_tm(system_id, component_id, last_msg);
- mavlink_test_abk_tm(system_id, component_id, last_msg);
- mavlink_test_nas_tm(system_id, component_id, last_msg);
- mavlink_test_adc_tm(system_id, component_id, last_msg);
- mavlink_test_ms5803_tm(system_id, component_id, last_msg);
- mavlink_test_bmx160_tm(system_id, component_id, last_msg);
- mavlink_test_lis3mdl_tm(system_id, component_id, last_msg);
- mavlink_test_gps_tm(system_id, component_id, last_msg);
- mavlink_test_hr_tm(system_id, component_id, last_msg);
- mavlink_test_lr_tm(system_id, component_id, last_msg);
- mavlink_test_test_tm(system_id, component_id, last_msg);
- mavlink_test_windtunnel_tm(system_id, component_id, last_msg);
- mavlink_test_sensors_tm(system_id, component_id, last_msg);
-}
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // LYNX_TESTSUITE_H
diff --git a/mavlink_lib/lynx/version.h b/mavlink_lib/lynx/version.h
deleted file mode 100644
index fe8220a253be6ab81aeeeb0cb667180d2b1ac8c6..0000000000000000000000000000000000000000
--- a/mavlink_lib/lynx/version.h
+++ /dev/null
@@ -1,14 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol built from lynx.xml
- * @see http://mavlink.org
- */
-#pragma once
-
-#ifndef MAVLINK_VERSION_H
-#define MAVLINK_VERSION_H
-
-#define MAVLINK_BUILD_DATE "Mon Sep 27 2021"
-#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
-#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 166
-
-#endif // MAVLINK_VERSION_H
diff --git a/mavlink_lib/lyra/lyra.h b/mavlink_lib/lyra/lyra.h
deleted file mode 100644
index aa09b7c7ddfe2d4e25915f8465aa7e99a5496f9a..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/lyra.h
+++ /dev/null
@@ -1,262 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol generated from lyra.xml
- * @see http://mavlink.org
- */
-#pragma once
-#ifndef MAVLINK_LYRA_H
-#define MAVLINK_LYRA_H
-
-#ifndef MAVLINK_H
- #error Wrong include order: MAVLINK_LYRA.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
-
-#undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH -6834851485668065312
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-// MESSAGE LENGTHS AND CRCS
-
-#ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 8, 2, 4, 8, 1, 5, 5, 7, 4, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 74, 64, 32, 60, 32, 32, 32, 32, 56, 21, 5, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 52, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 86, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 14, 14, 46, 28, 27, 53, 77, 29, 176, 163, 92, 76, 42, 35, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
-#endif
-
-#ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 160, 226, 113, 38, 71, 67, 218, 44, 81, 181, 110, 22, 65, 79, 180, 246, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 146, 57, 72, 87, 229, 245, 212, 140, 148, 6, 155, 87, 255, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 117, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 202, 164, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 242, 142, 108, 133, 234, 66, 11, 214, 84, 245, 115, 63, 79, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
-#endif
-
-#include "../protocol.h"
-
-#define MAVLINK_ENABLED_LYRA
-
-// ENUM DEFINITIONS
-
-
-/** @brief Enum that lists all the system IDs of the various devices */
-#ifndef HAVE_ENUM_SysIDs
-#define HAVE_ENUM_SysIDs
-typedef enum SysIDs
-{
- MAV_SYSID_MAIN=1, /* | */
- MAV_SYSID_PAYLOAD=2, /* | */
- MAV_SYSID_RIG=3, /* | */
- MAV_SYSID_GS=4, /* | */
- SysIDs_ENUM_END=5, /* | */
-} SysIDs;
-#endif
-
-/** @brief Enum list for all the telemetries that can be requested */
-#ifndef HAVE_ENUM_SystemTMList
-#define HAVE_ENUM_SystemTMList
-typedef enum SystemTMList
-{
- MAV_SYS_ID=1, /* State of init results about system hardware/software components | */
- MAV_FSM_ID=2, /* States of all On-Board FSMs | */
- MAV_PIN_OBS_ID=3, /* Pin observer data | */
- MAV_LOGGER_ID=4, /* SD Logger stats | */
- MAV_MAVLINK_STATS=5, /* Mavlink driver stats | */
- MAV_TASK_STATS_ID=6, /* Task scheduler statistics answer: n mavlink messages where n is the number of tasks | */
- MAV_ADA_ID=7, /* ADA Status | */
- MAV_NAS_ID=8, /* NavigationSystem data | */
- MAV_MEA_ID=9, /* MEA Status | */
- MAV_CAN_ID=10, /* Canbus stats | */
- MAV_FLIGHT_ID=11, /* Flight telemetry | */
- MAV_STATS_ID=12, /* Satistics telemetry | */
- MAV_SENSORS_STATE_ID=13, /* Sensors init state telemetry | */
- MAV_GSE_ID=14, /* Ground Segnement Equipment | */
- MAV_MOTOR_ID=15, /* Rocket Motor data | */
- SystemTMList_ENUM_END=16, /* | */
-} SystemTMList;
-#endif
-
-/** @brief Enum list of all sensors telemetries that can be requested */
-#ifndef HAVE_ENUM_SensorsTMList
-#define HAVE_ENUM_SensorsTMList
-typedef enum SensorsTMList
-{
- MAV_GPS_ID=1, /* GPS data | */
- MAV_BMX160_ID=2, /* BMX160 IMU data | */
- MAV_VN100_ID=3, /* VN100 IMU data | */
- MAV_MPU9250_ID=4, /* MPU9250 IMU data | */
- MAV_ADS_ID=5, /* ADS 8 channel ADC data | */
- MAV_MS5803_ID=6, /* MS5803 barometer data | */
- MAV_BME280_ID=7, /* BME280 barometer data | */
- MAV_CURRENT_SENSE_ID=8, /* Electrical current sensors data | */
- MAV_LIS3MDL_ID=9, /* LIS3MDL compass data | */
- MAV_DPL_PRESS_ID=10, /* Deployment pressure data | */
- MAV_STATIC_PRESS_ID=11, /* Static pressure data | */
- MAV_PITOT_PRESS_ID=12, /* Pitot pressure data | */
- MAV_BATTERY_VOLTAGE_ID=13, /* Battery voltage data | */
- MAV_LOAD_CELL_ID=14, /* Load cell data | */
- MAV_FILLING_PRESS_ID=15, /* Filling line pressure | */
- MAV_TANK_TOP_PRESS_ID=16, /* Top tank pressure | */
- MAV_TANK_BOTTOM_PRESS_ID=17, /* Bottom tank pressure | */
- MAV_TANK_TEMP_ID=18, /* Tank temperature | */
- MAV_COMBUSTION_PRESS_ID=19, /* Combustion chamber pressure | */
- MAV_VESSEL_PRESS_ID=20, /* Vessel pressure | */
- MAV_LOAD_CELL_VESSEL_ID=21, /* Vessel tank weight | */
- MAV_LOAD_CELL_TANK_ID=22, /* Tank weight | */
- MAV_LIS2MDL_ID=23, /* Magnetometer data | */
- MAV_LPS28DFW_ID=24, /* Pressure sensor data | */
- MAV_LSM6DSRX_ID=25, /* IMU data | */
- MAV_H3LIS331DL_ID=26, /* 400G accelerometer | */
- MAV_LPS22DF_ID=27, /* Pressure sensor data | */
- SensorsTMList_ENUM_END=28, /* | */
-} SensorsTMList;
-#endif
-
-/** @brief Enum of the commands */
-#ifndef HAVE_ENUM_MavCommandList
-#define HAVE_ENUM_MavCommandList
-typedef enum MavCommandList
-{
- MAV_CMD_ARM=1, /* Command to arm the rocket | */
- MAV_CMD_DISARM=2, /* Command to disarm the rocket | */
- MAV_CMD_CALIBRATE=3, /* Command to trigger the calibration | */
- MAV_CMD_SAVE_CALIBRATION=4, /* Command to save the current calibration into a file | */
- MAV_CMD_FORCE_INIT=5, /* Command to init the rocket | */
- MAV_CMD_FORCE_LAUNCH=6, /* Command to force the launch state on the rocket | */
- MAV_CMD_FORCE_LANDING=7, /* Command to communicate the end of the mission and close the file descriptors in the SD card | */
- MAV_CMD_FORCE_APOGEE=8, /* Command to trigger the apogee event | */
- MAV_CMD_FORCE_EXPULSION=9, /* Command to open the nosecone | */
- MAV_CMD_FORCE_DEPLOYMENT=10, /* Command to activate the thermal cutters and cut the drogue, activating both thermal cutters sequentially | */
- MAV_CMD_START_LOGGING=11, /* Command to enable sensor logging | */
- MAV_CMD_STOP_LOGGING=12, /* Command to permanently close the log file | */
- MAV_CMD_FORCE_REBOOT=13, /* Command to reset the board from test status | */
- MAV_CMD_ENTER_TEST_MODE=14, /* Command to enter the test mode | */
- MAV_CMD_EXIT_TEST_MODE=15, /* Command to exit the test mode | */
- MAV_CMD_START_RECORDING=16, /* Command to start the internal cameras recordings | */
- MAV_CMD_STOP_RECORDING=17, /* Command to stop the internal cameras recordings | */
- MavCommandList_ENUM_END=18, /* | */
-} MavCommandList;
-#endif
-
-/** @brief Enum of all the servos used on Gemini */
-#ifndef HAVE_ENUM_ServosList
-#define HAVE_ENUM_ServosList
-typedef enum ServosList
-{
- AIR_BRAKES_SERVO=1, /* | */
- EXPULSION_SERVO=2, /* | */
- PARAFOIL_LEFT_SERVO=3, /* | */
- PARAFOIL_RIGHT_SERVO=4, /* | */
- MAIN_VALVE=5, /* | */
- VENTING_VALVE=6, /* | */
- RELEASE_VALVE=7, /* | */
- FILLING_VALVE=8, /* | */
- DISCONNECT_SERVO=9, /* | */
- ServosList_ENUM_END=10, /* | */
-} ServosList;
-#endif
-
-/** @brief Enum of all the steppers used on Gemini systems */
-#ifndef HAVE_ENUM_StepperList
-#define HAVE_ENUM_StepperList
-typedef enum StepperList
-{
- STEPPER_X=1, /* | */
- STEPPER_Y=2, /* | */
- StepperList_ENUM_END=3, /* | */
-} StepperList;
-#endif
-
-/** @brief Enum of all the pins used on Gemini */
-#ifndef HAVE_ENUM_PinsList
-#define HAVE_ENUM_PinsList
-typedef enum PinsList
-{
- LAUNCH_PIN=1, /* | */
- NOSECONE_PIN=2, /* | */
- DEPLOYMENT_PIN=3, /* | */
- QUICK_CONNECTOR_PIN=4, /* | */
- PinsList_ENUM_END=5, /* | */
-} PinsList;
-#endif
-
-// MAVLINK VERSION
-
-#ifndef MAVLINK_VERSION
-#define MAVLINK_VERSION 1
-#endif
-
-#if (MAVLINK_VERSION == 0)
-#undef MAVLINK_VERSION
-#define MAVLINK_VERSION 1
-#endif
-
-// MESSAGE DEFINITIONS
-#include "./mavlink_msg_ping_tc.h"
-#include "./mavlink_msg_command_tc.h"
-#include "./mavlink_msg_system_tm_request_tc.h"
-#include "./mavlink_msg_sensor_tm_request_tc.h"
-#include "./mavlink_msg_servo_tm_request_tc.h"
-#include "./mavlink_msg_set_servo_angle_tc.h"
-#include "./mavlink_msg_wiggle_servo_tc.h"
-#include "./mavlink_msg_reset_servo_tc.h"
-#include "./mavlink_msg_set_reference_altitude_tc.h"
-#include "./mavlink_msg_set_reference_temperature_tc.h"
-#include "./mavlink_msg_set_orientation_tc.h"
-#include "./mavlink_msg_set_coordinates_tc.h"
-#include "./mavlink_msg_raw_event_tc.h"
-#include "./mavlink_msg_set_deployment_altitude_tc.h"
-#include "./mavlink_msg_set_target_coordinates_tc.h"
-#include "./mavlink_msg_set_algorithm_tc.h"
-#include "./mavlink_msg_set_atomic_valve_timing_tc.h"
-#include "./mavlink_msg_set_valve_maximum_aperture_tc.h"
-#include "./mavlink_msg_conrig_state_tc.h"
-#include "./mavlink_msg_set_ignition_time_tc.h"
-#include "./mavlink_msg_set_stepper_angle_tc.h"
-#include "./mavlink_msg_set_stepper_steps_tc.h"
-#include "./mavlink_msg_ack_tm.h"
-#include "./mavlink_msg_nack_tm.h"
-#include "./mavlink_msg_gps_tm.h"
-#include "./mavlink_msg_imu_tm.h"
-#include "./mavlink_msg_pressure_tm.h"
-#include "./mavlink_msg_adc_tm.h"
-#include "./mavlink_msg_voltage_tm.h"
-#include "./mavlink_msg_current_tm.h"
-#include "./mavlink_msg_temp_tm.h"
-#include "./mavlink_msg_load_tm.h"
-#include "./mavlink_msg_attitude_tm.h"
-#include "./mavlink_msg_sensor_state_tm.h"
-#include "./mavlink_msg_servo_tm.h"
-#include "./mavlink_msg_pin_tm.h"
-#include "./mavlink_msg_receiver_tm.h"
-#include "./mavlink_msg_arp_tm.h"
-#include "./mavlink_msg_set_antenna_coordinates_arp_tc.h"
-#include "./mavlink_msg_set_rocket_coordinates_arp_tc.h"
-#include "./mavlink_msg_sys_tm.h"
-#include "./mavlink_msg_fsm_tm.h"
-#include "./mavlink_msg_logger_tm.h"
-#include "./mavlink_msg_mavlink_stats_tm.h"
-#include "./mavlink_msg_task_stats_tm.h"
-#include "./mavlink_msg_ada_tm.h"
-#include "./mavlink_msg_nas_tm.h"
-#include "./mavlink_msg_mea_tm.h"
-#include "./mavlink_msg_rocket_flight_tm.h"
-#include "./mavlink_msg_payload_flight_tm.h"
-#include "./mavlink_msg_rocket_stats_tm.h"
-#include "./mavlink_msg_payload_stats_tm.h"
-#include "./mavlink_msg_gse_tm.h"
-#include "./mavlink_msg_motor_tm.h"
-
-// base include
-
-
-#undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH -6834851485668065312
-
-#if MAVLINK_THIS_XML_HASH == MAVLINK_PRIMARY_XML_HASH
-# define MAVLINK_MESSAGE_INFO {{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING_TC, MAVLINK_MESSAGE_INFO_COMMAND_TC, MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC, MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC, MAVLINK_MESSAGE_INFO_RESET_SERVO_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC, MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_RAW_EVENT_TC, MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC, MAVLINK_MESSAGE_INFO_SET_ATOMIC_VALVE_TIMING_TC, MAVLINK_MESSAGE_INFO_SET_VALVE_MAXIMUM_APERTURE_TC, MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC, MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC, MAVLINK_MESSAGE_INFO_SET_STEPPER_ANGLE_TC, MAVLINK_MESSAGE_INFO_SET_STEPPER_STEPS_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACK_TM, MAVLINK_MESSAGE_INFO_NACK_TM, MAVLINK_MESSAGE_INFO_GPS_TM, MAVLINK_MESSAGE_INFO_IMU_TM, MAVLINK_MESSAGE_INFO_PRESSURE_TM, MAVLINK_MESSAGE_INFO_ADC_TM, MAVLINK_MESSAGE_INFO_VOLTAGE_TM, MAVLINK_MESSAGE_INFO_CURRENT_TM, MAVLINK_MESSAGE_INFO_TEMP_TM, MAVLINK_MESSAGE_INFO_LOAD_TM, MAVLINK_MESSAGE_INFO_ATTITUDE_TM, MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM, MAVLINK_MESSAGE_INFO_SERVO_TM, MAVLINK_MESSAGE_INFO_PIN_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_RECEIVER_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ARP_TM, MAVLINK_MESSAGE_INFO_SET_ANTENNA_COORDINATES_ARP_TC, MAVLINK_MESSAGE_INFO_SET_ROCKET_COORDINATES_ARP_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_TM, MAVLINK_MESSAGE_INFO_FSM_TM, MAVLINK_MESSAGE_INFO_LOGGER_TM, MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM, MAVLINK_MESSAGE_INFO_TASK_STATS_TM, MAVLINK_MESSAGE_INFO_ADA_TM, MAVLINK_MESSAGE_INFO_NAS_TM, MAVLINK_MESSAGE_INFO_MEA_TM, MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM, MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM, MAVLINK_MESSAGE_INFO_GSE_TM, MAVLINK_MESSAGE_INFO_MOTOR_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
-# define MAVLINK_MESSAGE_NAMES {{ "ACK_TM", 100 }, { "ADA_TM", 205 }, { "ADC_TM", 105 }, { "ARP_TM", 169 }, { "ATTITUDE_TM", 110 }, { "COMMAND_TC", 2 }, { "CONRIG_STATE_TC", 19 }, { "CURRENT_TM", 107 }, { "FSM_TM", 201 }, { "GPS_TM", 102 }, { "GSE_TM", 212 }, { "IMU_TM", 103 }, { "LOAD_TM", 109 }, { "LOGGER_TM", 202 }, { "MAVLINK_STATS_TM", 203 }, { "MEA_TM", 207 }, { "MOTOR_TM", 213 }, { "NACK_TM", 101 }, { "NAS_TM", 206 }, { "PAYLOAD_FLIGHT_TM", 209 }, { "PAYLOAD_STATS_TM", 211 }, { "PING_TC", 1 }, { "PIN_TM", 113 }, { "PRESSURE_TM", 104 }, { "RAW_EVENT_TC", 13 }, { "RECEIVER_TM", 150 }, { "RESET_SERVO_TC", 8 }, { "ROCKET_FLIGHT_TM", 208 }, { "ROCKET_STATS_TM", 210 }, { "SENSOR_STATE_TM", 111 }, { "SENSOR_TM_REQUEST_TC", 4 }, { "SERVO_TM", 112 }, { "SERVO_TM_REQUEST_TC", 5 }, { "SET_ALGORITHM_TC", 16 }, { "SET_ANTENNA_COORDINATES_ARP_TC", 170 }, { "SET_ATOMIC_VALVE_TIMING_TC", 17 }, { "SET_COORDINATES_TC", 12 }, { "SET_DEPLOYMENT_ALTITUDE_TC", 14 }, { "SET_IGNITION_TIME_TC", 20 }, { "SET_ORIENTATION_TC", 11 }, { "SET_REFERENCE_ALTITUDE_TC", 9 }, { "SET_REFERENCE_TEMPERATURE_TC", 10 }, { "SET_ROCKET_COORDINATES_ARP_TC", 171 }, { "SET_SERVO_ANGLE_TC", 6 }, { "SET_STEPPER_ANGLE_TC", 21 }, { "SET_STEPPER_STEPS_TC", 22 }, { "SET_TARGET_COORDINATES_TC", 15 }, { "SET_VALVE_MAXIMUM_APERTURE_TC", 18 }, { "SYSTEM_TM_REQUEST_TC", 3 }, { "SYS_TM", 200 }, { "TASK_STATS_TM", 204 }, { "TEMP_TM", 108 }, { "VOLTAGE_TM", 106 }, { "WIGGLE_SERVO_TC", 7 }}
-# if MAVLINK_COMMAND_24BIT
-# include "../mavlink_get_info.h"
-# endif
-#endif
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // MAVLINK_LYRA_H
diff --git a/mavlink_lib/lyra/mavlink.h b/mavlink_lib/lyra/mavlink.h
deleted file mode 100644
index 20de852be485f52799c1360308e7abec8122a18b..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink.h
+++ /dev/null
@@ -1,34 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol built from lyra.xml
- * @see http://mavlink.org
- */
-#pragma once
-#ifndef MAVLINK_H
-#define MAVLINK_H
-
-#define MAVLINK_PRIMARY_XML_HASH -6834851485668065312
-
-#ifndef MAVLINK_STX
-#define MAVLINK_STX 254
-#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 0
-#endif
-
-#include "version.h"
-#include "lyra.h"
-
-#endif // MAVLINK_H
diff --git a/mavlink_lib/lyra/mavlink_msg_ack_tm.h b/mavlink_lib/lyra/mavlink_msg_ack_tm.h
deleted file mode 100644
index 8abc2a50773e576580ab8179be7c6a2348071c59..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_ack_tm.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE ACK_TM PACKING
-
-#define MAVLINK_MSG_ID_ACK_TM 100
-
-
-typedef struct __mavlink_ack_tm_t {
- uint8_t recv_msgid; /*< Message id of the received message*/
- uint8_t seq_ack; /*< Sequence number of the received message*/
-} mavlink_ack_tm_t;
-
-#define MAVLINK_MSG_ID_ACK_TM_LEN 2
-#define MAVLINK_MSG_ID_ACK_TM_MIN_LEN 2
-#define MAVLINK_MSG_ID_100_LEN 2
-#define MAVLINK_MSG_ID_100_MIN_LEN 2
-
-#define MAVLINK_MSG_ID_ACK_TM_CRC 50
-#define MAVLINK_MSG_ID_100_CRC 50
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ACK_TM { \
- 100, \
- "ACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_ack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_ack_tm_t, seq_ack) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ACK_TM { \
- "ACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_ack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_ack_tm_t, seq_ack) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ack_tm 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 recv_msgid Message id of the received message
- * @param seq_ack Sequence number of the received message
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ack_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACK_TM_LEN);
-#else
- mavlink_ack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ACK_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-}
-
-/**
- * @brief Pack a ack_tm 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 recv_msgid Message id of the received message
- * @param seq_ack Sequence number of the received message
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ack_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t recv_msgid,uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACK_TM_LEN);
-#else
- mavlink_ack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ACK_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-}
-
-/**
- * @brief Encode a ack_tm 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 ack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ack_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ack_tm_t* ack_tm)
-{
- return mavlink_msg_ack_tm_pack(system_id, component_id, msg, ack_tm->recv_msgid, ack_tm->seq_ack);
-}
-
-/**
- * @brief Encode a ack_tm 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 ack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ack_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ack_tm_t* ack_tm)
-{
- return mavlink_msg_ack_tm_pack_chan(system_id, component_id, chan, msg, ack_tm->recv_msgid, ack_tm->seq_ack);
-}
-
-/**
- * @brief Send a ack_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param recv_msgid Message id of the received message
- * @param seq_ack Sequence number of the received message
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ack_tm_send(mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, buf, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#else
- mavlink_ack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, (const char *)&packet, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a ack_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ack_tm_send_struct(mavlink_channel_t chan, const mavlink_ack_tm_t* ack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ack_tm_send(chan, ack_tm->recv_msgid, ack_tm->seq_ack);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, (const char *)ack_tm, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ACK_TM_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_ack_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, buf, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#else
- mavlink_ack_tm_t *packet = (mavlink_ack_tm_t *)msgbuf;
- packet->recv_msgid = recv_msgid;
- packet->seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, (const char *)packet, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ACK_TM UNPACKING
-
-
-/**
- * @brief Get field recv_msgid from ack_tm message
- *
- * @return Message id of the received message
- */
-static inline uint8_t mavlink_msg_ack_tm_get_recv_msgid(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field seq_ack from ack_tm message
- *
- * @return Sequence number of the received message
- */
-static inline uint8_t mavlink_msg_ack_tm_get_seq_ack(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Decode a ack_tm message into a struct
- *
- * @param msg The message to decode
- * @param ack_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ack_tm_decode(const mavlink_message_t* msg, mavlink_ack_tm_t* ack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ack_tm->recv_msgid = mavlink_msg_ack_tm_get_recv_msgid(msg);
- ack_tm->seq_ack = mavlink_msg_ack_tm_get_seq_ack(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ACK_TM_LEN? msg->len : MAVLINK_MSG_ID_ACK_TM_LEN;
- memset(ack_tm, 0, MAVLINK_MSG_ID_ACK_TM_LEN);
- memcpy(ack_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_ada_tm.h b/mavlink_lib/lyra/mavlink_msg_ada_tm.h
deleted file mode 100644
index f96a75c0db6fcd54bea1d9bb6658860e7e998179..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_ada_tm.h
+++ /dev/null
@@ -1,513 +0,0 @@
-#pragma once
-// MESSAGE ADA_TM PACKING
-
-#define MAVLINK_MSG_ID_ADA_TM 205
-
-
-typedef struct __mavlink_ada_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float kalman_x0; /*< Kalman state variable 0 (pressure)*/
- float kalman_x1; /*< Kalman state variable 1 (pressure velocity)*/
- float kalman_x2; /*< Kalman state variable 2 (pressure acceleration)*/
- float vertical_speed; /*< [m/s] Vertical speed computed by the ADA*/
- float msl_altitude; /*< [m] Altitude w.r.t. mean sea level*/
- float ref_pressure; /*< [Pa] Calibration pressure*/
- float ref_altitude; /*< [m] Calibration altitude*/
- float ref_temperature; /*< [degC] Calibration temperature*/
- float msl_pressure; /*< [Pa] Expected pressure at mean sea level*/
- float msl_temperature; /*< [degC] Expected temperature at mean sea level*/
- float dpl_altitude; /*< [m] Main parachute deployment altituyde*/
- uint8_t state; /*< ADA current state*/
-} mavlink_ada_tm_t;
-
-#define MAVLINK_MSG_ID_ADA_TM_LEN 53
-#define MAVLINK_MSG_ID_ADA_TM_MIN_LEN 53
-#define MAVLINK_MSG_ID_205_LEN 53
-#define MAVLINK_MSG_ID_205_MIN_LEN 53
-
-#define MAVLINK_MSG_ID_ADA_TM_CRC 234
-#define MAVLINK_MSG_ID_205_CRC 234
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ADA_TM { \
- 205, \
- "ADA_TM", \
- 13, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ada_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_ada_tm_t, state) }, \
- { "kalman_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ada_tm_t, kalman_x0) }, \
- { "kalman_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ada_tm_t, kalman_x1) }, \
- { "kalman_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ada_tm_t, kalman_x2) }, \
- { "vertical_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ada_tm_t, vertical_speed) }, \
- { "msl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ada_tm_t, msl_altitude) }, \
- { "ref_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_ada_tm_t, ref_pressure) }, \
- { "ref_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_ada_tm_t, ref_altitude) }, \
- { "ref_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_ada_tm_t, ref_temperature) }, \
- { "msl_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_ada_tm_t, msl_pressure) }, \
- { "msl_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_ada_tm_t, msl_temperature) }, \
- { "dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_ada_tm_t, dpl_altitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ADA_TM { \
- "ADA_TM", \
- 13, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ada_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_ada_tm_t, state) }, \
- { "kalman_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ada_tm_t, kalman_x0) }, \
- { "kalman_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ada_tm_t, kalman_x1) }, \
- { "kalman_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ada_tm_t, kalman_x2) }, \
- { "vertical_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ada_tm_t, vertical_speed) }, \
- { "msl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ada_tm_t, msl_altitude) }, \
- { "ref_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_ada_tm_t, ref_pressure) }, \
- { "ref_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_ada_tm_t, ref_altitude) }, \
- { "ref_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_ada_tm_t, ref_temperature) }, \
- { "msl_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_ada_tm_t, msl_pressure) }, \
- { "msl_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_ada_tm_t, msl_temperature) }, \
- { "dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_ada_tm_t, dpl_altitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ada_tm 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] When was this logged
- * @param state ADA current state
- * @param kalman_x0 Kalman state variable 0 (pressure)
- * @param kalman_x1 Kalman state variable 1 (pressure velocity)
- * @param kalman_x2 Kalman state variable 2 (pressure acceleration)
- * @param vertical_speed [m/s] Vertical speed computed by the ADA
- * @param msl_altitude [m] Altitude w.r.t. mean sea level
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_altitude [m] Calibration altitude
- * @param ref_temperature [degC] Calibration temperature
- * @param msl_pressure [Pa] Expected pressure at mean sea level
- * @param msl_temperature [degC] Expected temperature at mean sea level
- * @param dpl_altitude [m] Main parachute deployment altituyde
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ada_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float vertical_speed, float msl_altitude, float ref_pressure, float ref_altitude, float ref_temperature, float msl_pressure, float msl_temperature, float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, kalman_x0);
- _mav_put_float(buf, 12, kalman_x1);
- _mav_put_float(buf, 16, kalman_x2);
- _mav_put_float(buf, 20, vertical_speed);
- _mav_put_float(buf, 24, msl_altitude);
- _mav_put_float(buf, 28, ref_pressure);
- _mav_put_float(buf, 32, ref_altitude);
- _mav_put_float(buf, 36, ref_temperature);
- _mav_put_float(buf, 40, msl_pressure);
- _mav_put_float(buf, 44, msl_temperature);
- _mav_put_float(buf, 48, dpl_altitude);
- _mav_put_uint8_t(buf, 52, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADA_TM_LEN);
-#else
- mavlink_ada_tm_t packet;
- packet.timestamp = timestamp;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.vertical_speed = vertical_speed;
- packet.msl_altitude = msl_altitude;
- packet.ref_pressure = ref_pressure;
- packet.ref_altitude = ref_altitude;
- packet.ref_temperature = ref_temperature;
- packet.msl_pressure = msl_pressure;
- packet.msl_temperature = msl_temperature;
- packet.dpl_altitude = dpl_altitude;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADA_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADA_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-}
-
-/**
- * @brief Pack a ada_tm 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] When was this logged
- * @param state ADA current state
- * @param kalman_x0 Kalman state variable 0 (pressure)
- * @param kalman_x1 Kalman state variable 1 (pressure velocity)
- * @param kalman_x2 Kalman state variable 2 (pressure acceleration)
- * @param vertical_speed [m/s] Vertical speed computed by the ADA
- * @param msl_altitude [m] Altitude w.r.t. mean sea level
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_altitude [m] Calibration altitude
- * @param ref_temperature [degC] Calibration temperature
- * @param msl_pressure [Pa] Expected pressure at mean sea level
- * @param msl_temperature [degC] Expected temperature at mean sea level
- * @param dpl_altitude [m] Main parachute deployment altituyde
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ada_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t state,float kalman_x0,float kalman_x1,float kalman_x2,float vertical_speed,float msl_altitude,float ref_pressure,float ref_altitude,float ref_temperature,float msl_pressure,float msl_temperature,float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, kalman_x0);
- _mav_put_float(buf, 12, kalman_x1);
- _mav_put_float(buf, 16, kalman_x2);
- _mav_put_float(buf, 20, vertical_speed);
- _mav_put_float(buf, 24, msl_altitude);
- _mav_put_float(buf, 28, ref_pressure);
- _mav_put_float(buf, 32, ref_altitude);
- _mav_put_float(buf, 36, ref_temperature);
- _mav_put_float(buf, 40, msl_pressure);
- _mav_put_float(buf, 44, msl_temperature);
- _mav_put_float(buf, 48, dpl_altitude);
- _mav_put_uint8_t(buf, 52, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADA_TM_LEN);
-#else
- mavlink_ada_tm_t packet;
- packet.timestamp = timestamp;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.vertical_speed = vertical_speed;
- packet.msl_altitude = msl_altitude;
- packet.ref_pressure = ref_pressure;
- packet.ref_altitude = ref_altitude;
- packet.ref_temperature = ref_temperature;
- packet.msl_pressure = msl_pressure;
- packet.msl_temperature = msl_temperature;
- packet.dpl_altitude = dpl_altitude;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADA_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADA_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-}
-
-/**
- * @brief Encode a ada_tm 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 ada_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ada_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ada_tm_t* ada_tm)
-{
- return mavlink_msg_ada_tm_pack(system_id, component_id, msg, ada_tm->timestamp, ada_tm->state, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->vertical_speed, ada_tm->msl_altitude, ada_tm->ref_pressure, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_pressure, ada_tm->msl_temperature, ada_tm->dpl_altitude);
-}
-
-/**
- * @brief Encode a ada_tm 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 ada_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ada_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ada_tm_t* ada_tm)
-{
- return mavlink_msg_ada_tm_pack_chan(system_id, component_id, chan, msg, ada_tm->timestamp, ada_tm->state, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->vertical_speed, ada_tm->msl_altitude, ada_tm->ref_pressure, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_pressure, ada_tm->msl_temperature, ada_tm->dpl_altitude);
-}
-
-/**
- * @brief Send a ada_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param state ADA current state
- * @param kalman_x0 Kalman state variable 0 (pressure)
- * @param kalman_x1 Kalman state variable 1 (pressure velocity)
- * @param kalman_x2 Kalman state variable 2 (pressure acceleration)
- * @param vertical_speed [m/s] Vertical speed computed by the ADA
- * @param msl_altitude [m] Altitude w.r.t. mean sea level
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_altitude [m] Calibration altitude
- * @param ref_temperature [degC] Calibration temperature
- * @param msl_pressure [Pa] Expected pressure at mean sea level
- * @param msl_temperature [degC] Expected temperature at mean sea level
- * @param dpl_altitude [m] Main parachute deployment altituyde
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ada_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float vertical_speed, float msl_altitude, float ref_pressure, float ref_altitude, float ref_temperature, float msl_pressure, float msl_temperature, float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, kalman_x0);
- _mav_put_float(buf, 12, kalman_x1);
- _mav_put_float(buf, 16, kalman_x2);
- _mav_put_float(buf, 20, vertical_speed);
- _mav_put_float(buf, 24, msl_altitude);
- _mav_put_float(buf, 28, ref_pressure);
- _mav_put_float(buf, 32, ref_altitude);
- _mav_put_float(buf, 36, ref_temperature);
- _mav_put_float(buf, 40, msl_pressure);
- _mav_put_float(buf, 44, msl_temperature);
- _mav_put_float(buf, 48, dpl_altitude);
- _mav_put_uint8_t(buf, 52, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, buf, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#else
- mavlink_ada_tm_t packet;
- packet.timestamp = timestamp;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.vertical_speed = vertical_speed;
- packet.msl_altitude = msl_altitude;
- packet.ref_pressure = ref_pressure;
- packet.ref_altitude = ref_altitude;
- packet.ref_temperature = ref_temperature;
- packet.msl_pressure = msl_pressure;
- packet.msl_temperature = msl_temperature;
- packet.dpl_altitude = dpl_altitude;
- packet.state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, (const char *)&packet, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a ada_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ada_tm_send_struct(mavlink_channel_t chan, const mavlink_ada_tm_t* ada_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ada_tm_send(chan, ada_tm->timestamp, ada_tm->state, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->vertical_speed, ada_tm->msl_altitude, ada_tm->ref_pressure, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_pressure, ada_tm->msl_temperature, ada_tm->dpl_altitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, (const char *)ada_tm, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ADA_TM_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_ada_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float vertical_speed, float msl_altitude, float ref_pressure, float ref_altitude, float ref_temperature, float msl_pressure, float msl_temperature, float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, kalman_x0);
- _mav_put_float(buf, 12, kalman_x1);
- _mav_put_float(buf, 16, kalman_x2);
- _mav_put_float(buf, 20, vertical_speed);
- _mav_put_float(buf, 24, msl_altitude);
- _mav_put_float(buf, 28, ref_pressure);
- _mav_put_float(buf, 32, ref_altitude);
- _mav_put_float(buf, 36, ref_temperature);
- _mav_put_float(buf, 40, msl_pressure);
- _mav_put_float(buf, 44, msl_temperature);
- _mav_put_float(buf, 48, dpl_altitude);
- _mav_put_uint8_t(buf, 52, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, buf, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#else
- mavlink_ada_tm_t *packet = (mavlink_ada_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->kalman_x0 = kalman_x0;
- packet->kalman_x1 = kalman_x1;
- packet->kalman_x2 = kalman_x2;
- packet->vertical_speed = vertical_speed;
- packet->msl_altitude = msl_altitude;
- packet->ref_pressure = ref_pressure;
- packet->ref_altitude = ref_altitude;
- packet->ref_temperature = ref_temperature;
- packet->msl_pressure = msl_pressure;
- packet->msl_temperature = msl_temperature;
- packet->dpl_altitude = dpl_altitude;
- packet->state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, (const char *)packet, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ADA_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from ada_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_ada_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field state from ada_tm message
- *
- * @return ADA current state
- */
-static inline uint8_t mavlink_msg_ada_tm_get_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 52);
-}
-
-/**
- * @brief Get field kalman_x0 from ada_tm message
- *
- * @return Kalman state variable 0 (pressure)
- */
-static inline float mavlink_msg_ada_tm_get_kalman_x0(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field kalman_x1 from ada_tm message
- *
- * @return Kalman state variable 1 (pressure velocity)
- */
-static inline float mavlink_msg_ada_tm_get_kalman_x1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field kalman_x2 from ada_tm message
- *
- * @return Kalman state variable 2 (pressure acceleration)
- */
-static inline float mavlink_msg_ada_tm_get_kalman_x2(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field vertical_speed from ada_tm message
- *
- * @return [m/s] Vertical speed computed by the ADA
- */
-static inline float mavlink_msg_ada_tm_get_vertical_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field msl_altitude from ada_tm message
- *
- * @return [m] Altitude w.r.t. mean sea level
- */
-static inline float mavlink_msg_ada_tm_get_msl_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field ref_pressure from ada_tm message
- *
- * @return [Pa] Calibration pressure
- */
-static inline float mavlink_msg_ada_tm_get_ref_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field ref_altitude from ada_tm message
- *
- * @return [m] Calibration altitude
- */
-static inline float mavlink_msg_ada_tm_get_ref_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field ref_temperature from ada_tm message
- *
- * @return [degC] Calibration temperature
- */
-static inline float mavlink_msg_ada_tm_get_ref_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field msl_pressure from ada_tm message
- *
- * @return [Pa] Expected pressure at mean sea level
- */
-static inline float mavlink_msg_ada_tm_get_msl_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field msl_temperature from ada_tm message
- *
- * @return [degC] Expected temperature at mean sea level
- */
-static inline float mavlink_msg_ada_tm_get_msl_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field dpl_altitude from ada_tm message
- *
- * @return [m] Main parachute deployment altituyde
- */
-static inline float mavlink_msg_ada_tm_get_dpl_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Decode a ada_tm message into a struct
- *
- * @param msg The message to decode
- * @param ada_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ada_tm_decode(const mavlink_message_t* msg, mavlink_ada_tm_t* ada_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ada_tm->timestamp = mavlink_msg_ada_tm_get_timestamp(msg);
- ada_tm->kalman_x0 = mavlink_msg_ada_tm_get_kalman_x0(msg);
- ada_tm->kalman_x1 = mavlink_msg_ada_tm_get_kalman_x1(msg);
- ada_tm->kalman_x2 = mavlink_msg_ada_tm_get_kalman_x2(msg);
- ada_tm->vertical_speed = mavlink_msg_ada_tm_get_vertical_speed(msg);
- ada_tm->msl_altitude = mavlink_msg_ada_tm_get_msl_altitude(msg);
- ada_tm->ref_pressure = mavlink_msg_ada_tm_get_ref_pressure(msg);
- ada_tm->ref_altitude = mavlink_msg_ada_tm_get_ref_altitude(msg);
- ada_tm->ref_temperature = mavlink_msg_ada_tm_get_ref_temperature(msg);
- ada_tm->msl_pressure = mavlink_msg_ada_tm_get_msl_pressure(msg);
- ada_tm->msl_temperature = mavlink_msg_ada_tm_get_msl_temperature(msg);
- ada_tm->dpl_altitude = mavlink_msg_ada_tm_get_dpl_altitude(msg);
- ada_tm->state = mavlink_msg_ada_tm_get_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ADA_TM_LEN? msg->len : MAVLINK_MSG_ID_ADA_TM_LEN;
- memset(ada_tm, 0, MAVLINK_MSG_ID_ADA_TM_LEN);
- memcpy(ada_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_adc_tm.h b/mavlink_lib/lyra/mavlink_msg_adc_tm.h
deleted file mode 100644
index 04c7612852769618318043c1a36059b224ba9a18..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_adc_tm.h
+++ /dev/null
@@ -1,430 +0,0 @@
-#pragma once
-// MESSAGE ADC_TM PACKING
-
-#define MAVLINK_MSG_ID_ADC_TM 105
-
-
-typedef struct __mavlink_adc_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float channel_0; /*< [V] ADC voltage measured on channel 0*/
- float channel_1; /*< [V] ADC voltage measured on channel 1*/
- float channel_2; /*< [V] ADC voltage measured on channel 2*/
- float channel_3; /*< [V] ADC voltage measured on channel 3*/
- float channel_4; /*< [V] ADC voltage measured on channel 4*/
- float channel_5; /*< [V] ADC voltage measured on channel 5*/
- float channel_6; /*< [V] ADC voltage measured on channel 6*/
- float channel_7; /*< [V] ADC voltage measured on channel 7*/
- char sensor_name[20]; /*< Sensor name*/
-} mavlink_adc_tm_t;
-
-#define MAVLINK_MSG_ID_ADC_TM_LEN 60
-#define MAVLINK_MSG_ID_ADC_TM_MIN_LEN 60
-#define MAVLINK_MSG_ID_105_LEN 60
-#define MAVLINK_MSG_ID_105_MIN_LEN 60
-
-#define MAVLINK_MSG_ID_ADC_TM_CRC 229
-#define MAVLINK_MSG_ID_105_CRC 229
-
-#define MAVLINK_MSG_ADC_TM_FIELD_SENSOR_NAME_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ADC_TM { \
- 105, \
- "ADC_TM", \
- 10, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_adc_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 40, offsetof(mavlink_adc_tm_t, sensor_name) }, \
- { "channel_0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_adc_tm_t, channel_0) }, \
- { "channel_1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_adc_tm_t, channel_1) }, \
- { "channel_2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_adc_tm_t, channel_2) }, \
- { "channel_3", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_adc_tm_t, channel_3) }, \
- { "channel_4", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_adc_tm_t, channel_4) }, \
- { "channel_5", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_adc_tm_t, channel_5) }, \
- { "channel_6", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_adc_tm_t, channel_6) }, \
- { "channel_7", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_adc_tm_t, channel_7) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ADC_TM { \
- "ADC_TM", \
- 10, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_adc_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 40, offsetof(mavlink_adc_tm_t, sensor_name) }, \
- { "channel_0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_adc_tm_t, channel_0) }, \
- { "channel_1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_adc_tm_t, channel_1) }, \
- { "channel_2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_adc_tm_t, channel_2) }, \
- { "channel_3", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_adc_tm_t, channel_3) }, \
- { "channel_4", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_adc_tm_t, channel_4) }, \
- { "channel_5", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_adc_tm_t, channel_5) }, \
- { "channel_6", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_adc_tm_t, channel_6) }, \
- { "channel_7", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_adc_tm_t, channel_7) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a adc_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param channel_0 [V] ADC voltage measured on channel 0
- * @param channel_1 [V] ADC voltage measured on channel 1
- * @param channel_2 [V] ADC voltage measured on channel 2
- * @param channel_3 [V] ADC voltage measured on channel 3
- * @param channel_4 [V] ADC voltage measured on channel 4
- * @param channel_5 [V] ADC voltage measured on channel 5
- * @param channel_6 [V] ADC voltage measured on channel 6
- * @param channel_7 [V] ADC voltage measured on channel 7
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_adc_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_name, float channel_0, float channel_1, float channel_2, float channel_3, float channel_4, float channel_5, float channel_6, float channel_7)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, channel_0);
- _mav_put_float(buf, 12, channel_1);
- _mav_put_float(buf, 16, channel_2);
- _mav_put_float(buf, 20, channel_3);
- _mav_put_float(buf, 24, channel_4);
- _mav_put_float(buf, 28, channel_5);
- _mav_put_float(buf, 32, channel_6);
- _mav_put_float(buf, 36, channel_7);
- _mav_put_char_array(buf, 40, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADC_TM_LEN);
-#else
- mavlink_adc_tm_t packet;
- packet.timestamp = timestamp;
- packet.channel_0 = channel_0;
- packet.channel_1 = channel_1;
- packet.channel_2 = channel_2;
- packet.channel_3 = channel_3;
- packet.channel_4 = channel_4;
- packet.channel_5 = channel_5;
- packet.channel_6 = channel_6;
- packet.channel_7 = channel_7;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADC_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADC_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-}
-
-/**
- * @brief Pack a adc_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param channel_0 [V] ADC voltage measured on channel 0
- * @param channel_1 [V] ADC voltage measured on channel 1
- * @param channel_2 [V] ADC voltage measured on channel 2
- * @param channel_3 [V] ADC voltage measured on channel 3
- * @param channel_4 [V] ADC voltage measured on channel 4
- * @param channel_5 [V] ADC voltage measured on channel 5
- * @param channel_6 [V] ADC voltage measured on channel 6
- * @param channel_7 [V] ADC voltage measured on channel 7
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_adc_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_name,float channel_0,float channel_1,float channel_2,float channel_3,float channel_4,float channel_5,float channel_6,float channel_7)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, channel_0);
- _mav_put_float(buf, 12, channel_1);
- _mav_put_float(buf, 16, channel_2);
- _mav_put_float(buf, 20, channel_3);
- _mav_put_float(buf, 24, channel_4);
- _mav_put_float(buf, 28, channel_5);
- _mav_put_float(buf, 32, channel_6);
- _mav_put_float(buf, 36, channel_7);
- _mav_put_char_array(buf, 40, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADC_TM_LEN);
-#else
- mavlink_adc_tm_t packet;
- packet.timestamp = timestamp;
- packet.channel_0 = channel_0;
- packet.channel_1 = channel_1;
- packet.channel_2 = channel_2;
- packet.channel_3 = channel_3;
- packet.channel_4 = channel_4;
- packet.channel_5 = channel_5;
- packet.channel_6 = channel_6;
- packet.channel_7 = channel_7;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADC_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADC_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-}
-
-/**
- * @brief Encode a adc_tm 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 adc_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_adc_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_adc_tm_t* adc_tm)
-{
- return mavlink_msg_adc_tm_pack(system_id, component_id, msg, adc_tm->timestamp, adc_tm->sensor_name, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3, adc_tm->channel_4, adc_tm->channel_5, adc_tm->channel_6, adc_tm->channel_7);
-}
-
-/**
- * @brief Encode a adc_tm 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 adc_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_adc_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_adc_tm_t* adc_tm)
-{
- return mavlink_msg_adc_tm_pack_chan(system_id, component_id, chan, msg, adc_tm->timestamp, adc_tm->sensor_name, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3, adc_tm->channel_4, adc_tm->channel_5, adc_tm->channel_6, adc_tm->channel_7);
-}
-
-/**
- * @brief Send a adc_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_name Sensor name
- * @param channel_0 [V] ADC voltage measured on channel 0
- * @param channel_1 [V] ADC voltage measured on channel 1
- * @param channel_2 [V] ADC voltage measured on channel 2
- * @param channel_3 [V] ADC voltage measured on channel 3
- * @param channel_4 [V] ADC voltage measured on channel 4
- * @param channel_5 [V] ADC voltage measured on channel 5
- * @param channel_6 [V] ADC voltage measured on channel 6
- * @param channel_7 [V] ADC voltage measured on channel 7
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_adc_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float channel_0, float channel_1, float channel_2, float channel_3, float channel_4, float channel_5, float channel_6, float channel_7)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, channel_0);
- _mav_put_float(buf, 12, channel_1);
- _mav_put_float(buf, 16, channel_2);
- _mav_put_float(buf, 20, channel_3);
- _mav_put_float(buf, 24, channel_4);
- _mav_put_float(buf, 28, channel_5);
- _mav_put_float(buf, 32, channel_6);
- _mav_put_float(buf, 36, channel_7);
- _mav_put_char_array(buf, 40, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, buf, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#else
- mavlink_adc_tm_t packet;
- packet.timestamp = timestamp;
- packet.channel_0 = channel_0;
- packet.channel_1 = channel_1;
- packet.channel_2 = channel_2;
- packet.channel_3 = channel_3;
- packet.channel_4 = channel_4;
- packet.channel_5 = channel_5;
- packet.channel_6 = channel_6;
- packet.channel_7 = channel_7;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)&packet, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a adc_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_adc_tm_send_struct(mavlink_channel_t chan, const mavlink_adc_tm_t* adc_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_adc_tm_send(chan, adc_tm->timestamp, adc_tm->sensor_name, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3, adc_tm->channel_4, adc_tm->channel_5, adc_tm->channel_6, adc_tm->channel_7);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)adc_tm, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ADC_TM_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_adc_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float channel_0, float channel_1, float channel_2, float channel_3, float channel_4, float channel_5, float channel_6, float channel_7)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, channel_0);
- _mav_put_float(buf, 12, channel_1);
- _mav_put_float(buf, 16, channel_2);
- _mav_put_float(buf, 20, channel_3);
- _mav_put_float(buf, 24, channel_4);
- _mav_put_float(buf, 28, channel_5);
- _mav_put_float(buf, 32, channel_6);
- _mav_put_float(buf, 36, channel_7);
- _mav_put_char_array(buf, 40, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, buf, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#else
- mavlink_adc_tm_t *packet = (mavlink_adc_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->channel_0 = channel_0;
- packet->channel_1 = channel_1;
- packet->channel_2 = channel_2;
- packet->channel_3 = channel_3;
- packet->channel_4 = channel_4;
- packet->channel_5 = channel_5;
- packet->channel_6 = channel_6;
- packet->channel_7 = channel_7;
- mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)packet, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ADC_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from adc_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_adc_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_name from adc_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_adc_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
-{
- return _MAV_RETURN_char_array(msg, sensor_name, 20, 40);
-}
-
-/**
- * @brief Get field channel_0 from adc_tm message
- *
- * @return [V] ADC voltage measured on channel 0
- */
-static inline float mavlink_msg_adc_tm_get_channel_0(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field channel_1 from adc_tm message
- *
- * @return [V] ADC voltage measured on channel 1
- */
-static inline float mavlink_msg_adc_tm_get_channel_1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field channel_2 from adc_tm message
- *
- * @return [V] ADC voltage measured on channel 2
- */
-static inline float mavlink_msg_adc_tm_get_channel_2(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field channel_3 from adc_tm message
- *
- * @return [V] ADC voltage measured on channel 3
- */
-static inline float mavlink_msg_adc_tm_get_channel_3(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field channel_4 from adc_tm message
- *
- * @return [V] ADC voltage measured on channel 4
- */
-static inline float mavlink_msg_adc_tm_get_channel_4(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field channel_5 from adc_tm message
- *
- * @return [V] ADC voltage measured on channel 5
- */
-static inline float mavlink_msg_adc_tm_get_channel_5(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field channel_6 from adc_tm message
- *
- * @return [V] ADC voltage measured on channel 6
- */
-static inline float mavlink_msg_adc_tm_get_channel_6(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field channel_7 from adc_tm message
- *
- * @return [V] ADC voltage measured on channel 7
- */
-static inline float mavlink_msg_adc_tm_get_channel_7(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Decode a adc_tm message into a struct
- *
- * @param msg The message to decode
- * @param adc_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_adc_tm_decode(const mavlink_message_t* msg, mavlink_adc_tm_t* adc_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- adc_tm->timestamp = mavlink_msg_adc_tm_get_timestamp(msg);
- adc_tm->channel_0 = mavlink_msg_adc_tm_get_channel_0(msg);
- adc_tm->channel_1 = mavlink_msg_adc_tm_get_channel_1(msg);
- adc_tm->channel_2 = mavlink_msg_adc_tm_get_channel_2(msg);
- adc_tm->channel_3 = mavlink_msg_adc_tm_get_channel_3(msg);
- adc_tm->channel_4 = mavlink_msg_adc_tm_get_channel_4(msg);
- adc_tm->channel_5 = mavlink_msg_adc_tm_get_channel_5(msg);
- adc_tm->channel_6 = mavlink_msg_adc_tm_get_channel_6(msg);
- adc_tm->channel_7 = mavlink_msg_adc_tm_get_channel_7(msg);
- mavlink_msg_adc_tm_get_sensor_name(msg, adc_tm->sensor_name);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ADC_TM_LEN? msg->len : MAVLINK_MSG_ID_ADC_TM_LEN;
- memset(adc_tm, 0, MAVLINK_MSG_ID_ADC_TM_LEN);
- memcpy(adc_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_arp_tm.h b/mavlink_lib/lyra/mavlink_msg_arp_tm.h
deleted file mode 100644
index 0a20a8023588f8961ac5fdb386c407d53d138200..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_arp_tm.h
+++ /dev/null
@@ -1,838 +0,0 @@
-#pragma once
-// MESSAGE ARP_TM PACKING
-
-#define MAVLINK_MSG_ID_ARP_TM 169
-
-
-typedef struct __mavlink_arp_tm_t {
- uint64_t timestamp; /*< [us] Timestamp*/
- float yaw; /*< [deg] Current Yaw*/
- float pitch; /*< [deg] Current Pitch*/
- float roll; /*< [deg] Current Roll*/
- float target_yaw; /*< [deg] Target Yaw*/
- float target_pitch; /*< [deg] Target Pitch*/
- float stepperX_pos; /*< [deg] StepperX current position wrt the boot position*/
- float stepperX_delta; /*< [deg] StepperX last actuated delta angle*/
- float stepperX_speed; /*< [rps] StepperX current speed*/
- float stepperY_pos; /*< [deg] StepperY current position wrt the boot position*/
- float stepperY_delta; /*< [deg] StepperY last actuated delta angle*/
- float stepperY_speed; /*< [rps] StepperY current Speed*/
- float gps_latitude; /*< [deg] Latitude*/
- float gps_longitude; /*< [deg] Longitude*/
- float gps_height; /*< [m] Altitude*/
- float main_rx_rssi; /*< [dBm] Receive RSSI*/
- float battery_voltage; /*< [V] Battery voltage*/
- uint16_t main_packet_tx_error_count; /*< Number of errors during send*/
- uint16_t main_tx_bitrate; /*< [b/s] Send bitrate*/
- uint16_t main_packet_rx_success_count; /*< Number of succesfull received mavlink packets*/
- uint16_t main_packet_rx_drop_count; /*< Number of dropped mavlink packets*/
- uint16_t main_rx_bitrate; /*< [b/s] Receive bitrate*/
- uint8_t gps_fix; /*< Wether the GPS has a FIX*/
- uint8_t main_radio_present; /*< Boolean indicating the presence of the main radio*/
- uint8_t ethernet_present; /*< Boolean indicating the presence of the ethernet module*/
- uint8_t ethernet_status; /*< Status flag indicating the status of the ethernet PHY*/
-} mavlink_arp_tm_t;
-
-#define MAVLINK_MSG_ID_ARP_TM_LEN 86
-#define MAVLINK_MSG_ID_ARP_TM_MIN_LEN 86
-#define MAVLINK_MSG_ID_169_LEN 86
-#define MAVLINK_MSG_ID_169_MIN_LEN 86
-
-#define MAVLINK_MSG_ID_ARP_TM_CRC 2
-#define MAVLINK_MSG_ID_169_CRC 2
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ARP_TM { \
- 169, \
- "ARP_TM", \
- 26, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_arp_tm_t, timestamp) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_arp_tm_t, yaw) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_arp_tm_t, pitch) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_arp_tm_t, roll) }, \
- { "target_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_arp_tm_t, target_yaw) }, \
- { "target_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_arp_tm_t, target_pitch) }, \
- { "stepperX_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_arp_tm_t, stepperX_pos) }, \
- { "stepperX_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_arp_tm_t, stepperX_delta) }, \
- { "stepperX_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_arp_tm_t, stepperX_speed) }, \
- { "stepperY_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_arp_tm_t, stepperY_pos) }, \
- { "stepperY_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_arp_tm_t, stepperY_delta) }, \
- { "stepperY_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_arp_tm_t, stepperY_speed) }, \
- { "gps_latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_arp_tm_t, gps_latitude) }, \
- { "gps_longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_arp_tm_t, gps_longitude) }, \
- { "gps_height", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_arp_tm_t, gps_height) }, \
- { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 82, offsetof(mavlink_arp_tm_t, gps_fix) }, \
- { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 83, offsetof(mavlink_arp_tm_t, main_radio_present) }, \
- { "main_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 72, offsetof(mavlink_arp_tm_t, main_packet_tx_error_count) }, \
- { "main_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 74, offsetof(mavlink_arp_tm_t, main_tx_bitrate) }, \
- { "main_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 76, offsetof(mavlink_arp_tm_t, main_packet_rx_success_count) }, \
- { "main_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 78, offsetof(mavlink_arp_tm_t, main_packet_rx_drop_count) }, \
- { "main_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 80, offsetof(mavlink_arp_tm_t, main_rx_bitrate) }, \
- { "main_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_arp_tm_t, main_rx_rssi) }, \
- { "ethernet_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 84, offsetof(mavlink_arp_tm_t, ethernet_present) }, \
- { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 85, offsetof(mavlink_arp_tm_t, ethernet_status) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_arp_tm_t, battery_voltage) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ARP_TM { \
- "ARP_TM", \
- 26, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_arp_tm_t, timestamp) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_arp_tm_t, yaw) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_arp_tm_t, pitch) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_arp_tm_t, roll) }, \
- { "target_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_arp_tm_t, target_yaw) }, \
- { "target_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_arp_tm_t, target_pitch) }, \
- { "stepperX_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_arp_tm_t, stepperX_pos) }, \
- { "stepperX_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_arp_tm_t, stepperX_delta) }, \
- { "stepperX_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_arp_tm_t, stepperX_speed) }, \
- { "stepperY_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_arp_tm_t, stepperY_pos) }, \
- { "stepperY_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_arp_tm_t, stepperY_delta) }, \
- { "stepperY_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_arp_tm_t, stepperY_speed) }, \
- { "gps_latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_arp_tm_t, gps_latitude) }, \
- { "gps_longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_arp_tm_t, gps_longitude) }, \
- { "gps_height", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_arp_tm_t, gps_height) }, \
- { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 82, offsetof(mavlink_arp_tm_t, gps_fix) }, \
- { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 83, offsetof(mavlink_arp_tm_t, main_radio_present) }, \
- { "main_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 72, offsetof(mavlink_arp_tm_t, main_packet_tx_error_count) }, \
- { "main_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 74, offsetof(mavlink_arp_tm_t, main_tx_bitrate) }, \
- { "main_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 76, offsetof(mavlink_arp_tm_t, main_packet_rx_success_count) }, \
- { "main_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 78, offsetof(mavlink_arp_tm_t, main_packet_rx_drop_count) }, \
- { "main_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 80, offsetof(mavlink_arp_tm_t, main_rx_bitrate) }, \
- { "main_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_arp_tm_t, main_rx_rssi) }, \
- { "ethernet_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 84, offsetof(mavlink_arp_tm_t, ethernet_present) }, \
- { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 85, offsetof(mavlink_arp_tm_t, ethernet_status) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_arp_tm_t, battery_voltage) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a arp_tm 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
- * @param yaw [deg] Current Yaw
- * @param pitch [deg] Current Pitch
- * @param roll [deg] Current Roll
- * @param target_yaw [deg] Target Yaw
- * @param target_pitch [deg] Target Pitch
- * @param stepperX_pos [deg] StepperX current position wrt the boot position
- * @param stepperX_delta [deg] StepperX last actuated delta angle
- * @param stepperX_speed [rps] StepperX current speed
- * @param stepperY_pos [deg] StepperY current position wrt the boot position
- * @param stepperY_delta [deg] StepperY last actuated delta angle
- * @param stepperY_speed [rps] StepperY current Speed
- * @param gps_latitude [deg] Latitude
- * @param gps_longitude [deg] Longitude
- * @param gps_height [m] Altitude
- * @param gps_fix Wether the GPS has a FIX
- * @param main_radio_present Boolean indicating the presence of the main radio
- * @param main_packet_tx_error_count Number of errors during send
- * @param main_tx_bitrate [b/s] Send bitrate
- * @param main_packet_rx_success_count Number of succesfull received mavlink packets
- * @param main_packet_rx_drop_count Number of dropped mavlink packets
- * @param main_rx_bitrate [b/s] Receive bitrate
- * @param main_rx_rssi [dBm] Receive RSSI
- * @param ethernet_present Boolean indicating the presence of the ethernet module
- * @param ethernet_status Status flag indicating the status of the ethernet PHY
- * @param battery_voltage [V] Battery voltage
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_arp_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ARP_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, yaw);
- _mav_put_float(buf, 12, pitch);
- _mav_put_float(buf, 16, roll);
- _mav_put_float(buf, 20, target_yaw);
- _mav_put_float(buf, 24, target_pitch);
- _mav_put_float(buf, 28, stepperX_pos);
- _mav_put_float(buf, 32, stepperX_delta);
- _mav_put_float(buf, 36, stepperX_speed);
- _mav_put_float(buf, 40, stepperY_pos);
- _mav_put_float(buf, 44, stepperY_delta);
- _mav_put_float(buf, 48, stepperY_speed);
- _mav_put_float(buf, 52, gps_latitude);
- _mav_put_float(buf, 56, gps_longitude);
- _mav_put_float(buf, 60, gps_height);
- _mav_put_float(buf, 64, main_rx_rssi);
- _mav_put_float(buf, 68, battery_voltage);
- _mav_put_uint16_t(buf, 72, main_packet_tx_error_count);
- _mav_put_uint16_t(buf, 74, main_tx_bitrate);
- _mav_put_uint16_t(buf, 76, main_packet_rx_success_count);
- _mav_put_uint16_t(buf, 78, main_packet_rx_drop_count);
- _mav_put_uint16_t(buf, 80, main_rx_bitrate);
- _mav_put_uint8_t(buf, 82, gps_fix);
- _mav_put_uint8_t(buf, 83, main_radio_present);
- _mav_put_uint8_t(buf, 84, ethernet_present);
- _mav_put_uint8_t(buf, 85, ethernet_status);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARP_TM_LEN);
-#else
- mavlink_arp_tm_t packet;
- packet.timestamp = timestamp;
- packet.yaw = yaw;
- packet.pitch = pitch;
- packet.roll = roll;
- packet.target_yaw = target_yaw;
- packet.target_pitch = target_pitch;
- packet.stepperX_pos = stepperX_pos;
- packet.stepperX_delta = stepperX_delta;
- packet.stepperX_speed = stepperX_speed;
- packet.stepperY_pos = stepperY_pos;
- packet.stepperY_delta = stepperY_delta;
- packet.stepperY_speed = stepperY_speed;
- packet.gps_latitude = gps_latitude;
- packet.gps_longitude = gps_longitude;
- packet.gps_height = gps_height;
- packet.main_rx_rssi = main_rx_rssi;
- packet.battery_voltage = battery_voltage;
- packet.main_packet_tx_error_count = main_packet_tx_error_count;
- packet.main_tx_bitrate = main_tx_bitrate;
- packet.main_packet_rx_success_count = main_packet_rx_success_count;
- packet.main_packet_rx_drop_count = main_packet_rx_drop_count;
- packet.main_rx_bitrate = main_rx_bitrate;
- packet.gps_fix = gps_fix;
- packet.main_radio_present = main_radio_present;
- packet.ethernet_present = ethernet_present;
- packet.ethernet_status = ethernet_status;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ARP_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ARP_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC);
-}
-
-/**
- * @brief Pack a arp_tm 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
- * @param yaw [deg] Current Yaw
- * @param pitch [deg] Current Pitch
- * @param roll [deg] Current Roll
- * @param target_yaw [deg] Target Yaw
- * @param target_pitch [deg] Target Pitch
- * @param stepperX_pos [deg] StepperX current position wrt the boot position
- * @param stepperX_delta [deg] StepperX last actuated delta angle
- * @param stepperX_speed [rps] StepperX current speed
- * @param stepperY_pos [deg] StepperY current position wrt the boot position
- * @param stepperY_delta [deg] StepperY last actuated delta angle
- * @param stepperY_speed [rps] StepperY current Speed
- * @param gps_latitude [deg] Latitude
- * @param gps_longitude [deg] Longitude
- * @param gps_height [m] Altitude
- * @param gps_fix Wether the GPS has a FIX
- * @param main_radio_present Boolean indicating the presence of the main radio
- * @param main_packet_tx_error_count Number of errors during send
- * @param main_tx_bitrate [b/s] Send bitrate
- * @param main_packet_rx_success_count Number of succesfull received mavlink packets
- * @param main_packet_rx_drop_count Number of dropped mavlink packets
- * @param main_rx_bitrate [b/s] Receive bitrate
- * @param main_rx_rssi [dBm] Receive RSSI
- * @param ethernet_present Boolean indicating the presence of the ethernet module
- * @param ethernet_status Status flag indicating the status of the ethernet PHY
- * @param battery_voltage [V] Battery voltage
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_arp_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,float yaw,float pitch,float roll,float target_yaw,float target_pitch,float stepperX_pos,float stepperX_delta,float stepperX_speed,float stepperY_pos,float stepperY_delta,float stepperY_speed,float gps_latitude,float gps_longitude,float gps_height,uint8_t gps_fix,uint8_t main_radio_present,uint16_t main_packet_tx_error_count,uint16_t main_tx_bitrate,uint16_t main_packet_rx_success_count,uint16_t main_packet_rx_drop_count,uint16_t main_rx_bitrate,float main_rx_rssi,uint8_t ethernet_present,uint8_t ethernet_status,float battery_voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ARP_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, yaw);
- _mav_put_float(buf, 12, pitch);
- _mav_put_float(buf, 16, roll);
- _mav_put_float(buf, 20, target_yaw);
- _mav_put_float(buf, 24, target_pitch);
- _mav_put_float(buf, 28, stepperX_pos);
- _mav_put_float(buf, 32, stepperX_delta);
- _mav_put_float(buf, 36, stepperX_speed);
- _mav_put_float(buf, 40, stepperY_pos);
- _mav_put_float(buf, 44, stepperY_delta);
- _mav_put_float(buf, 48, stepperY_speed);
- _mav_put_float(buf, 52, gps_latitude);
- _mav_put_float(buf, 56, gps_longitude);
- _mav_put_float(buf, 60, gps_height);
- _mav_put_float(buf, 64, main_rx_rssi);
- _mav_put_float(buf, 68, battery_voltage);
- _mav_put_uint16_t(buf, 72, main_packet_tx_error_count);
- _mav_put_uint16_t(buf, 74, main_tx_bitrate);
- _mav_put_uint16_t(buf, 76, main_packet_rx_success_count);
- _mav_put_uint16_t(buf, 78, main_packet_rx_drop_count);
- _mav_put_uint16_t(buf, 80, main_rx_bitrate);
- _mav_put_uint8_t(buf, 82, gps_fix);
- _mav_put_uint8_t(buf, 83, main_radio_present);
- _mav_put_uint8_t(buf, 84, ethernet_present);
- _mav_put_uint8_t(buf, 85, ethernet_status);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARP_TM_LEN);
-#else
- mavlink_arp_tm_t packet;
- packet.timestamp = timestamp;
- packet.yaw = yaw;
- packet.pitch = pitch;
- packet.roll = roll;
- packet.target_yaw = target_yaw;
- packet.target_pitch = target_pitch;
- packet.stepperX_pos = stepperX_pos;
- packet.stepperX_delta = stepperX_delta;
- packet.stepperX_speed = stepperX_speed;
- packet.stepperY_pos = stepperY_pos;
- packet.stepperY_delta = stepperY_delta;
- packet.stepperY_speed = stepperY_speed;
- packet.gps_latitude = gps_latitude;
- packet.gps_longitude = gps_longitude;
- packet.gps_height = gps_height;
- packet.main_rx_rssi = main_rx_rssi;
- packet.battery_voltage = battery_voltage;
- packet.main_packet_tx_error_count = main_packet_tx_error_count;
- packet.main_tx_bitrate = main_tx_bitrate;
- packet.main_packet_rx_success_count = main_packet_rx_success_count;
- packet.main_packet_rx_drop_count = main_packet_rx_drop_count;
- packet.main_rx_bitrate = main_rx_bitrate;
- packet.gps_fix = gps_fix;
- packet.main_radio_present = main_radio_present;
- packet.ethernet_present = ethernet_present;
- packet.ethernet_status = ethernet_status;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ARP_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ARP_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC);
-}
-
-/**
- * @brief Encode a arp_tm 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 arp_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_arp_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_arp_tm_t* arp_tm)
-{
- return mavlink_msg_arp_tm_pack(system_id, component_id, msg, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix, arp_tm->main_radio_present, arp_tm->main_packet_tx_error_count, arp_tm->main_tx_bitrate, arp_tm->main_packet_rx_success_count, arp_tm->main_packet_rx_drop_count, arp_tm->main_rx_bitrate, arp_tm->main_rx_rssi, arp_tm->ethernet_present, arp_tm->ethernet_status, arp_tm->battery_voltage);
-}
-
-/**
- * @brief Encode a arp_tm 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 arp_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_arp_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_arp_tm_t* arp_tm)
-{
- return mavlink_msg_arp_tm_pack_chan(system_id, component_id, chan, msg, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix, arp_tm->main_radio_present, arp_tm->main_packet_tx_error_count, arp_tm->main_tx_bitrate, arp_tm->main_packet_rx_success_count, arp_tm->main_packet_rx_drop_count, arp_tm->main_rx_bitrate, arp_tm->main_rx_rssi, arp_tm->ethernet_present, arp_tm->ethernet_status, arp_tm->battery_voltage);
-}
-
-/**
- * @brief Send a arp_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp
- * @param yaw [deg] Current Yaw
- * @param pitch [deg] Current Pitch
- * @param roll [deg] Current Roll
- * @param target_yaw [deg] Target Yaw
- * @param target_pitch [deg] Target Pitch
- * @param stepperX_pos [deg] StepperX current position wrt the boot position
- * @param stepperX_delta [deg] StepperX last actuated delta angle
- * @param stepperX_speed [rps] StepperX current speed
- * @param stepperY_pos [deg] StepperY current position wrt the boot position
- * @param stepperY_delta [deg] StepperY last actuated delta angle
- * @param stepperY_speed [rps] StepperY current Speed
- * @param gps_latitude [deg] Latitude
- * @param gps_longitude [deg] Longitude
- * @param gps_height [m] Altitude
- * @param gps_fix Wether the GPS has a FIX
- * @param main_radio_present Boolean indicating the presence of the main radio
- * @param main_packet_tx_error_count Number of errors during send
- * @param main_tx_bitrate [b/s] Send bitrate
- * @param main_packet_rx_success_count Number of succesfull received mavlink packets
- * @param main_packet_rx_drop_count Number of dropped mavlink packets
- * @param main_rx_bitrate [b/s] Receive bitrate
- * @param main_rx_rssi [dBm] Receive RSSI
- * @param ethernet_present Boolean indicating the presence of the ethernet module
- * @param ethernet_status Status flag indicating the status of the ethernet PHY
- * @param battery_voltage [V] Battery voltage
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_arp_tm_send(mavlink_channel_t chan, uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ARP_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, yaw);
- _mav_put_float(buf, 12, pitch);
- _mav_put_float(buf, 16, roll);
- _mav_put_float(buf, 20, target_yaw);
- _mav_put_float(buf, 24, target_pitch);
- _mav_put_float(buf, 28, stepperX_pos);
- _mav_put_float(buf, 32, stepperX_delta);
- _mav_put_float(buf, 36, stepperX_speed);
- _mav_put_float(buf, 40, stepperY_pos);
- _mav_put_float(buf, 44, stepperY_delta);
- _mav_put_float(buf, 48, stepperY_speed);
- _mav_put_float(buf, 52, gps_latitude);
- _mav_put_float(buf, 56, gps_longitude);
- _mav_put_float(buf, 60, gps_height);
- _mav_put_float(buf, 64, main_rx_rssi);
- _mav_put_float(buf, 68, battery_voltage);
- _mav_put_uint16_t(buf, 72, main_packet_tx_error_count);
- _mav_put_uint16_t(buf, 74, main_tx_bitrate);
- _mav_put_uint16_t(buf, 76, main_packet_rx_success_count);
- _mav_put_uint16_t(buf, 78, main_packet_rx_drop_count);
- _mav_put_uint16_t(buf, 80, main_rx_bitrate);
- _mav_put_uint8_t(buf, 82, gps_fix);
- _mav_put_uint8_t(buf, 83, main_radio_present);
- _mav_put_uint8_t(buf, 84, ethernet_present);
- _mav_put_uint8_t(buf, 85, ethernet_status);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_TM, buf, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC);
-#else
- mavlink_arp_tm_t packet;
- packet.timestamp = timestamp;
- packet.yaw = yaw;
- packet.pitch = pitch;
- packet.roll = roll;
- packet.target_yaw = target_yaw;
- packet.target_pitch = target_pitch;
- packet.stepperX_pos = stepperX_pos;
- packet.stepperX_delta = stepperX_delta;
- packet.stepperX_speed = stepperX_speed;
- packet.stepperY_pos = stepperY_pos;
- packet.stepperY_delta = stepperY_delta;
- packet.stepperY_speed = stepperY_speed;
- packet.gps_latitude = gps_latitude;
- packet.gps_longitude = gps_longitude;
- packet.gps_height = gps_height;
- packet.main_rx_rssi = main_rx_rssi;
- packet.battery_voltage = battery_voltage;
- packet.main_packet_tx_error_count = main_packet_tx_error_count;
- packet.main_tx_bitrate = main_tx_bitrate;
- packet.main_packet_rx_success_count = main_packet_rx_success_count;
- packet.main_packet_rx_drop_count = main_packet_rx_drop_count;
- packet.main_rx_bitrate = main_rx_bitrate;
- packet.gps_fix = gps_fix;
- packet.main_radio_present = main_radio_present;
- packet.ethernet_present = ethernet_present;
- packet.ethernet_status = ethernet_status;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_TM, (const char *)&packet, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a arp_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_arp_tm_send_struct(mavlink_channel_t chan, const mavlink_arp_tm_t* arp_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_arp_tm_send(chan, arp_tm->timestamp, arp_tm->yaw, arp_tm->pitch, arp_tm->roll, arp_tm->target_yaw, arp_tm->target_pitch, arp_tm->stepperX_pos, arp_tm->stepperX_delta, arp_tm->stepperX_speed, arp_tm->stepperY_pos, arp_tm->stepperY_delta, arp_tm->stepperY_speed, arp_tm->gps_latitude, arp_tm->gps_longitude, arp_tm->gps_height, arp_tm->gps_fix, arp_tm->main_radio_present, arp_tm->main_packet_tx_error_count, arp_tm->main_tx_bitrate, arp_tm->main_packet_rx_success_count, arp_tm->main_packet_rx_drop_count, arp_tm->main_rx_bitrate, arp_tm->main_rx_rssi, arp_tm->ethernet_present, arp_tm->ethernet_status, arp_tm->battery_voltage);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_TM, (const char *)arp_tm, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ARP_TM_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_arp_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float yaw, float pitch, float roll, float target_yaw, float target_pitch, float stepperX_pos, float stepperX_delta, float stepperX_speed, float stepperY_pos, float stepperY_delta, float stepperY_speed, float gps_latitude, float gps_longitude, float gps_height, uint8_t gps_fix, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, yaw);
- _mav_put_float(buf, 12, pitch);
- _mav_put_float(buf, 16, roll);
- _mav_put_float(buf, 20, target_yaw);
- _mav_put_float(buf, 24, target_pitch);
- _mav_put_float(buf, 28, stepperX_pos);
- _mav_put_float(buf, 32, stepperX_delta);
- _mav_put_float(buf, 36, stepperX_speed);
- _mav_put_float(buf, 40, stepperY_pos);
- _mav_put_float(buf, 44, stepperY_delta);
- _mav_put_float(buf, 48, stepperY_speed);
- _mav_put_float(buf, 52, gps_latitude);
- _mav_put_float(buf, 56, gps_longitude);
- _mav_put_float(buf, 60, gps_height);
- _mav_put_float(buf, 64, main_rx_rssi);
- _mav_put_float(buf, 68, battery_voltage);
- _mav_put_uint16_t(buf, 72, main_packet_tx_error_count);
- _mav_put_uint16_t(buf, 74, main_tx_bitrate);
- _mav_put_uint16_t(buf, 76, main_packet_rx_success_count);
- _mav_put_uint16_t(buf, 78, main_packet_rx_drop_count);
- _mav_put_uint16_t(buf, 80, main_rx_bitrate);
- _mav_put_uint8_t(buf, 82, gps_fix);
- _mav_put_uint8_t(buf, 83, main_radio_present);
- _mav_put_uint8_t(buf, 84, ethernet_present);
- _mav_put_uint8_t(buf, 85, ethernet_status);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_TM, buf, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC);
-#else
- mavlink_arp_tm_t *packet = (mavlink_arp_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->yaw = yaw;
- packet->pitch = pitch;
- packet->roll = roll;
- packet->target_yaw = target_yaw;
- packet->target_pitch = target_pitch;
- packet->stepperX_pos = stepperX_pos;
- packet->stepperX_delta = stepperX_delta;
- packet->stepperX_speed = stepperX_speed;
- packet->stepperY_pos = stepperY_pos;
- packet->stepperY_delta = stepperY_delta;
- packet->stepperY_speed = stepperY_speed;
- packet->gps_latitude = gps_latitude;
- packet->gps_longitude = gps_longitude;
- packet->gps_height = gps_height;
- packet->main_rx_rssi = main_rx_rssi;
- packet->battery_voltage = battery_voltage;
- packet->main_packet_tx_error_count = main_packet_tx_error_count;
- packet->main_tx_bitrate = main_tx_bitrate;
- packet->main_packet_rx_success_count = main_packet_rx_success_count;
- packet->main_packet_rx_drop_count = main_packet_rx_drop_count;
- packet->main_rx_bitrate = main_rx_bitrate;
- packet->gps_fix = gps_fix;
- packet->main_radio_present = main_radio_present;
- packet->ethernet_present = ethernet_present;
- packet->ethernet_status = ethernet_status;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_TM, (const char *)packet, MAVLINK_MSG_ID_ARP_TM_MIN_LEN, MAVLINK_MSG_ID_ARP_TM_LEN, MAVLINK_MSG_ID_ARP_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ARP_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from arp_tm message
- *
- * @return [us] Timestamp
- */
-static inline uint64_t mavlink_msg_arp_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field yaw from arp_tm message
- *
- * @return [deg] Current Yaw
- */
-static inline float mavlink_msg_arp_tm_get_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field pitch from arp_tm message
- *
- * @return [deg] Current Pitch
- */
-static inline float mavlink_msg_arp_tm_get_pitch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field roll from arp_tm message
- *
- * @return [deg] Current Roll
- */
-static inline float mavlink_msg_arp_tm_get_roll(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field target_yaw from arp_tm message
- *
- * @return [deg] Target Yaw
- */
-static inline float mavlink_msg_arp_tm_get_target_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field target_pitch from arp_tm message
- *
- * @return [deg] Target Pitch
- */
-static inline float mavlink_msg_arp_tm_get_target_pitch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field stepperX_pos from arp_tm message
- *
- * @return [deg] StepperX current position wrt the boot position
- */
-static inline float mavlink_msg_arp_tm_get_stepperX_pos(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field stepperX_delta from arp_tm message
- *
- * @return [deg] StepperX last actuated delta angle
- */
-static inline float mavlink_msg_arp_tm_get_stepperX_delta(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field stepperX_speed from arp_tm message
- *
- * @return [rps] StepperX current speed
- */
-static inline float mavlink_msg_arp_tm_get_stepperX_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field stepperY_pos from arp_tm message
- *
- * @return [deg] StepperY current position wrt the boot position
- */
-static inline float mavlink_msg_arp_tm_get_stepperY_pos(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field stepperY_delta from arp_tm message
- *
- * @return [deg] StepperY last actuated delta angle
- */
-static inline float mavlink_msg_arp_tm_get_stepperY_delta(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field stepperY_speed from arp_tm message
- *
- * @return [rps] StepperY current Speed
- */
-static inline float mavlink_msg_arp_tm_get_stepperY_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field gps_latitude from arp_tm message
- *
- * @return [deg] Latitude
- */
-static inline float mavlink_msg_arp_tm_get_gps_latitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field gps_longitude from arp_tm message
- *
- * @return [deg] Longitude
- */
-static inline float mavlink_msg_arp_tm_get_gps_longitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field gps_height from arp_tm message
- *
- * @return [m] Altitude
- */
-static inline float mavlink_msg_arp_tm_get_gps_height(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field gps_fix from arp_tm message
- *
- * @return Wether the GPS has a FIX
- */
-static inline uint8_t mavlink_msg_arp_tm_get_gps_fix(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 82);
-}
-
-/**
- * @brief Get field main_radio_present from arp_tm message
- *
- * @return Boolean indicating the presence of the main radio
- */
-static inline uint8_t mavlink_msg_arp_tm_get_main_radio_present(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 83);
-}
-
-/**
- * @brief Get field main_packet_tx_error_count from arp_tm message
- *
- * @return Number of errors during send
- */
-static inline uint16_t mavlink_msg_arp_tm_get_main_packet_tx_error_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 72);
-}
-
-/**
- * @brief Get field main_tx_bitrate from arp_tm message
- *
- * @return [b/s] Send bitrate
- */
-static inline uint16_t mavlink_msg_arp_tm_get_main_tx_bitrate(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 74);
-}
-
-/**
- * @brief Get field main_packet_rx_success_count from arp_tm message
- *
- * @return Number of succesfull received mavlink packets
- */
-static inline uint16_t mavlink_msg_arp_tm_get_main_packet_rx_success_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 76);
-}
-
-/**
- * @brief Get field main_packet_rx_drop_count from arp_tm message
- *
- * @return Number of dropped mavlink packets
- */
-static inline uint16_t mavlink_msg_arp_tm_get_main_packet_rx_drop_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 78);
-}
-
-/**
- * @brief Get field main_rx_bitrate from arp_tm message
- *
- * @return [b/s] Receive bitrate
- */
-static inline uint16_t mavlink_msg_arp_tm_get_main_rx_bitrate(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 80);
-}
-
-/**
- * @brief Get field main_rx_rssi from arp_tm message
- *
- * @return [dBm] Receive RSSI
- */
-static inline float mavlink_msg_arp_tm_get_main_rx_rssi(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field ethernet_present from arp_tm message
- *
- * @return Boolean indicating the presence of the ethernet module
- */
-static inline uint8_t mavlink_msg_arp_tm_get_ethernet_present(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 84);
-}
-
-/**
- * @brief Get field ethernet_status from arp_tm message
- *
- * @return Status flag indicating the status of the ethernet PHY
- */
-static inline uint8_t mavlink_msg_arp_tm_get_ethernet_status(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 85);
-}
-
-/**
- * @brief Get field battery_voltage from arp_tm message
- *
- * @return [V] Battery voltage
- */
-static inline float mavlink_msg_arp_tm_get_battery_voltage(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Decode a arp_tm message into a struct
- *
- * @param msg The message to decode
- * @param arp_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_arp_tm_decode(const mavlink_message_t* msg, mavlink_arp_tm_t* arp_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- arp_tm->timestamp = mavlink_msg_arp_tm_get_timestamp(msg);
- arp_tm->yaw = mavlink_msg_arp_tm_get_yaw(msg);
- arp_tm->pitch = mavlink_msg_arp_tm_get_pitch(msg);
- arp_tm->roll = mavlink_msg_arp_tm_get_roll(msg);
- arp_tm->target_yaw = mavlink_msg_arp_tm_get_target_yaw(msg);
- arp_tm->target_pitch = mavlink_msg_arp_tm_get_target_pitch(msg);
- arp_tm->stepperX_pos = mavlink_msg_arp_tm_get_stepperX_pos(msg);
- arp_tm->stepperX_delta = mavlink_msg_arp_tm_get_stepperX_delta(msg);
- arp_tm->stepperX_speed = mavlink_msg_arp_tm_get_stepperX_speed(msg);
- arp_tm->stepperY_pos = mavlink_msg_arp_tm_get_stepperY_pos(msg);
- arp_tm->stepperY_delta = mavlink_msg_arp_tm_get_stepperY_delta(msg);
- arp_tm->stepperY_speed = mavlink_msg_arp_tm_get_stepperY_speed(msg);
- arp_tm->gps_latitude = mavlink_msg_arp_tm_get_gps_latitude(msg);
- arp_tm->gps_longitude = mavlink_msg_arp_tm_get_gps_longitude(msg);
- arp_tm->gps_height = mavlink_msg_arp_tm_get_gps_height(msg);
- arp_tm->main_rx_rssi = mavlink_msg_arp_tm_get_main_rx_rssi(msg);
- arp_tm->battery_voltage = mavlink_msg_arp_tm_get_battery_voltage(msg);
- arp_tm->main_packet_tx_error_count = mavlink_msg_arp_tm_get_main_packet_tx_error_count(msg);
- arp_tm->main_tx_bitrate = mavlink_msg_arp_tm_get_main_tx_bitrate(msg);
- arp_tm->main_packet_rx_success_count = mavlink_msg_arp_tm_get_main_packet_rx_success_count(msg);
- arp_tm->main_packet_rx_drop_count = mavlink_msg_arp_tm_get_main_packet_rx_drop_count(msg);
- arp_tm->main_rx_bitrate = mavlink_msg_arp_tm_get_main_rx_bitrate(msg);
- arp_tm->gps_fix = mavlink_msg_arp_tm_get_gps_fix(msg);
- arp_tm->main_radio_present = mavlink_msg_arp_tm_get_main_radio_present(msg);
- arp_tm->ethernet_present = mavlink_msg_arp_tm_get_ethernet_present(msg);
- arp_tm->ethernet_status = mavlink_msg_arp_tm_get_ethernet_status(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ARP_TM_LEN? msg->len : MAVLINK_MSG_ID_ARP_TM_LEN;
- memset(arp_tm, 0, MAVLINK_MSG_ID_ARP_TM_LEN);
- memcpy(arp_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_attitude_tm.h b/mavlink_lib/lyra/mavlink_msg_attitude_tm.h
deleted file mode 100644
index c16dba2fd216b82c35caba889893c630eb261145..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_attitude_tm.h
+++ /dev/null
@@ -1,405 +0,0 @@
-#pragma once
-// MESSAGE ATTITUDE_TM PACKING
-
-#define MAVLINK_MSG_ID_ATTITUDE_TM 110
-
-
-typedef struct __mavlink_attitude_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float roll; /*< [deg] Roll angle*/
- float pitch; /*< [deg] Pitch angle*/
- float yaw; /*< [deg] Yaw angle*/
- float quat_x; /*< Quaternion x component*/
- float quat_y; /*< Quaternion y component*/
- float quat_z; /*< Quaternion z component*/
- float quat_w; /*< Quaternion w component*/
- char sensor_name[20]; /*< Sensor name*/
-} mavlink_attitude_tm_t;
-
-#define MAVLINK_MSG_ID_ATTITUDE_TM_LEN 56
-#define MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN 56
-#define MAVLINK_MSG_ID_110_LEN 56
-#define MAVLINK_MSG_ID_110_MIN_LEN 56
-
-#define MAVLINK_MSG_ID_ATTITUDE_TM_CRC 6
-#define MAVLINK_MSG_ID_110_CRC 6
-
-#define MAVLINK_MSG_ATTITUDE_TM_FIELD_SENSOR_NAME_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ATTITUDE_TM { \
- 110, \
- "ATTITUDE_TM", \
- 9, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_attitude_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 36, offsetof(mavlink_attitude_tm_t, sensor_name) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_tm_t, roll) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_tm_t, pitch) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_tm_t, yaw) }, \
- { "quat_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_tm_t, quat_x) }, \
- { "quat_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_tm_t, quat_y) }, \
- { "quat_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_tm_t, quat_z) }, \
- { "quat_w", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_tm_t, quat_w) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ATTITUDE_TM { \
- "ATTITUDE_TM", \
- 9, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_attitude_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 36, offsetof(mavlink_attitude_tm_t, sensor_name) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_tm_t, roll) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_tm_t, pitch) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_tm_t, yaw) }, \
- { "quat_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_tm_t, quat_x) }, \
- { "quat_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_tm_t, quat_y) }, \
- { "quat_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_tm_t, quat_z) }, \
- { "quat_w", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_tm_t, quat_w) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a attitude_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param roll [deg] Roll angle
- * @param pitch [deg] Pitch angle
- * @param yaw [deg] Yaw angle
- * @param quat_x Quaternion x component
- * @param quat_y Quaternion y component
- * @param quat_z Quaternion z component
- * @param quat_w Quaternion w component
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_attitude_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_name, float roll, float pitch, float yaw, float quat_x, float quat_y, float quat_z, float quat_w)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ATTITUDE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, roll);
- _mav_put_float(buf, 12, pitch);
- _mav_put_float(buf, 16, yaw);
- _mav_put_float(buf, 20, quat_x);
- _mav_put_float(buf, 24, quat_y);
- _mav_put_float(buf, 28, quat_z);
- _mav_put_float(buf, 32, quat_w);
- _mav_put_char_array(buf, 36, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TM_LEN);
-#else
- mavlink_attitude_tm_t packet;
- packet.timestamp = timestamp;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.quat_x = quat_x;
- packet.quat_y = quat_y;
- packet.quat_z = quat_z;
- packet.quat_w = quat_w;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-}
-
-/**
- * @brief Pack a attitude_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param roll [deg] Roll angle
- * @param pitch [deg] Pitch angle
- * @param yaw [deg] Yaw angle
- * @param quat_x Quaternion x component
- * @param quat_y Quaternion y component
- * @param quat_z Quaternion z component
- * @param quat_w Quaternion w component
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_attitude_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_name,float roll,float pitch,float yaw,float quat_x,float quat_y,float quat_z,float quat_w)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ATTITUDE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, roll);
- _mav_put_float(buf, 12, pitch);
- _mav_put_float(buf, 16, yaw);
- _mav_put_float(buf, 20, quat_x);
- _mav_put_float(buf, 24, quat_y);
- _mav_put_float(buf, 28, quat_z);
- _mav_put_float(buf, 32, quat_w);
- _mav_put_char_array(buf, 36, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TM_LEN);
-#else
- mavlink_attitude_tm_t packet;
- packet.timestamp = timestamp;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.quat_x = quat_x;
- packet.quat_y = quat_y;
- packet.quat_z = quat_z;
- packet.quat_w = quat_w;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-}
-
-/**
- * @brief Encode a attitude_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_attitude_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_tm_t* attitude_tm)
-{
- return mavlink_msg_attitude_tm_pack(system_id, component_id, msg, attitude_tm->timestamp, attitude_tm->sensor_name, attitude_tm->roll, attitude_tm->pitch, attitude_tm->yaw, attitude_tm->quat_x, attitude_tm->quat_y, attitude_tm->quat_z, attitude_tm->quat_w);
-}
-
-/**
- * @brief Encode a attitude_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_attitude_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_tm_t* attitude_tm)
-{
- return mavlink_msg_attitude_tm_pack_chan(system_id, component_id, chan, msg, attitude_tm->timestamp, attitude_tm->sensor_name, attitude_tm->roll, attitude_tm->pitch, attitude_tm->yaw, attitude_tm->quat_x, attitude_tm->quat_y, attitude_tm->quat_z, attitude_tm->quat_w);
-}
-
-/**
- * @brief Send a attitude_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_name Sensor name
- * @param roll [deg] Roll angle
- * @param pitch [deg] Pitch angle
- * @param yaw [deg] Yaw angle
- * @param quat_x Quaternion x component
- * @param quat_y Quaternion y component
- * @param quat_z Quaternion z component
- * @param quat_w Quaternion w component
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_attitude_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float roll, float pitch, float yaw, float quat_x, float quat_y, float quat_z, float quat_w)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ATTITUDE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, roll);
- _mav_put_float(buf, 12, pitch);
- _mav_put_float(buf, 16, yaw);
- _mav_put_float(buf, 20, quat_x);
- _mav_put_float(buf, 24, quat_y);
- _mav_put_float(buf, 28, quat_z);
- _mav_put_float(buf, 32, quat_w);
- _mav_put_char_array(buf, 36, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TM, buf, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-#else
- mavlink_attitude_tm_t packet;
- packet.timestamp = timestamp;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.quat_x = quat_x;
- packet.quat_y = quat_y;
- packet.quat_z = quat_z;
- packet.quat_w = quat_w;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TM, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a attitude_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_attitude_tm_send_struct(mavlink_channel_t chan, const mavlink_attitude_tm_t* attitude_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_attitude_tm_send(chan, attitude_tm->timestamp, attitude_tm->sensor_name, attitude_tm->roll, attitude_tm->pitch, attitude_tm->yaw, attitude_tm->quat_x, attitude_tm->quat_y, attitude_tm->quat_z, attitude_tm->quat_w);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TM, (const char *)attitude_tm, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ATTITUDE_TM_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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float roll, float pitch, float yaw, float quat_x, float quat_y, float quat_z, float quat_w)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, roll);
- _mav_put_float(buf, 12, pitch);
- _mav_put_float(buf, 16, yaw);
- _mav_put_float(buf, 20, quat_x);
- _mav_put_float(buf, 24, quat_y);
- _mav_put_float(buf, 28, quat_z);
- _mav_put_float(buf, 32, quat_w);
- _mav_put_char_array(buf, 36, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TM, buf, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-#else
- mavlink_attitude_tm_t *packet = (mavlink_attitude_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->roll = roll;
- packet->pitch = pitch;
- packet->yaw = yaw;
- packet->quat_x = quat_x;
- packet->quat_y = quat_y;
- packet->quat_z = quat_z;
- packet->quat_w = quat_w;
- mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TM, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ATTITUDE_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from attitude_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_attitude_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_name from attitude_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_attitude_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
-{
- return _MAV_RETURN_char_array(msg, sensor_name, 20, 36);
-}
-
-/**
- * @brief Get field roll from attitude_tm message
- *
- * @return [deg] Roll angle
- */
-static inline float mavlink_msg_attitude_tm_get_roll(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field pitch from attitude_tm message
- *
- * @return [deg] Pitch angle
- */
-static inline float mavlink_msg_attitude_tm_get_pitch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field yaw from attitude_tm message
- *
- * @return [deg] Yaw angle
- */
-static inline float mavlink_msg_attitude_tm_get_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field quat_x from attitude_tm message
- *
- * @return Quaternion x component
- */
-static inline float mavlink_msg_attitude_tm_get_quat_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field quat_y from attitude_tm message
- *
- * @return Quaternion y component
- */
-static inline float mavlink_msg_attitude_tm_get_quat_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field quat_z from attitude_tm message
- *
- * @return Quaternion z component
- */
-static inline float mavlink_msg_attitude_tm_get_quat_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field quat_w from attitude_tm message
- *
- * @return Quaternion w component
- */
-static inline float mavlink_msg_attitude_tm_get_quat_w(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Decode a attitude_tm message into a struct
- *
- * @param msg The message to decode
- * @param attitude_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_attitude_tm_decode(const mavlink_message_t* msg, mavlink_attitude_tm_t* attitude_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- attitude_tm->timestamp = mavlink_msg_attitude_tm_get_timestamp(msg);
- attitude_tm->roll = mavlink_msg_attitude_tm_get_roll(msg);
- attitude_tm->pitch = mavlink_msg_attitude_tm_get_pitch(msg);
- attitude_tm->yaw = mavlink_msg_attitude_tm_get_yaw(msg);
- attitude_tm->quat_x = mavlink_msg_attitude_tm_get_quat_x(msg);
- attitude_tm->quat_y = mavlink_msg_attitude_tm_get_quat_y(msg);
- attitude_tm->quat_z = mavlink_msg_attitude_tm_get_quat_z(msg);
- attitude_tm->quat_w = mavlink_msg_attitude_tm_get_quat_w(msg);
- mavlink_msg_attitude_tm_get_sensor_name(msg, attitude_tm->sensor_name);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_TM_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_TM_LEN;
- memset(attitude_tm, 0, MAVLINK_MSG_ID_ATTITUDE_TM_LEN);
- memcpy(attitude_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_command_tc.h b/mavlink_lib/lyra/mavlink_msg_command_tc.h
deleted file mode 100644
index a4d0886b3f67df648cfd4ed0b8debc059ecfa272..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_command_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE COMMAND_TC PACKING
-
-#define MAVLINK_MSG_ID_COMMAND_TC 2
-
-
-typedef struct __mavlink_command_tc_t {
- uint8_t command_id; /*< A member of the MavCommandList enum*/
-} mavlink_command_tc_t;
-
-#define MAVLINK_MSG_ID_COMMAND_TC_LEN 1
-#define MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_2_LEN 1
-#define MAVLINK_MSG_ID_2_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_COMMAND_TC_CRC 198
-#define MAVLINK_MSG_ID_2_CRC 198
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_COMMAND_TC { \
- 2, \
- "COMMAND_TC", \
- 1, \
- { { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_command_tc_t, command_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_COMMAND_TC { \
- "COMMAND_TC", \
- 1, \
- { { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_command_tc_t, command_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a command_tc 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_id A member of the MavCommandList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_command_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_COMMAND_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_TC_LEN);
-#else
- mavlink_command_tc_t packet;
- packet.command_id = command_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_COMMAND_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-}
-
-/**
- * @brief Pack a command_tc 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_id A member of the MavCommandList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_command_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_COMMAND_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_TC_LEN);
-#else
- mavlink_command_tc_t packet;
- packet.command_id = command_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_COMMAND_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-}
-
-/**
- * @brief Encode a command_tc 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_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_command_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_tc_t* command_tc)
-{
- return mavlink_msg_command_tc_pack(system_id, component_id, msg, command_tc->command_id);
-}
-
-/**
- * @brief Encode a command_tc 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_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_command_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_tc_t* command_tc)
-{
- return mavlink_msg_command_tc_pack_chan(system_id, component_id, chan, msg, command_tc->command_id);
-}
-
-/**
- * @brief Send a command_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param command_id A member of the MavCommandList enum
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_command_tc_send(mavlink_channel_t chan, uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_COMMAND_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_TC, buf, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-#else
- mavlink_command_tc_t packet;
- packet.command_id = command_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_TC, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a command_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_command_tc_send_struct(mavlink_channel_t chan, const mavlink_command_tc_t* command_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_command_tc_send(chan, command_tc->command_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_TC, (const char *)command_tc, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_COMMAND_TC_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_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, command_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_TC, buf, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-#else
- mavlink_command_tc_t *packet = (mavlink_command_tc_t *)msgbuf;
- packet->command_id = command_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_TC, (const char *)packet, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE COMMAND_TC UNPACKING
-
-
-/**
- * @brief Get field command_id from command_tc message
- *
- * @return A member of the MavCommandList enum
- */
-static inline uint8_t mavlink_msg_command_tc_get_command_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a command_tc message into a struct
- *
- * @param msg The message to decode
- * @param command_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_command_tc_decode(const mavlink_message_t* msg, mavlink_command_tc_t* command_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- command_tc->command_id = mavlink_msg_command_tc_get_command_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_TC_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_TC_LEN;
- memset(command_tc, 0, MAVLINK_MSG_ID_COMMAND_TC_LEN);
- memcpy(command_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_conrig_state_tc.h b/mavlink_lib/lyra/mavlink_msg_conrig_state_tc.h
deleted file mode 100644
index 9f1ada850a2a7f233ba5f5e9ae41e55121488da2..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_conrig_state_tc.h
+++ /dev/null
@@ -1,363 +0,0 @@
-#pragma once
-// MESSAGE CONRIG_STATE_TC PACKING
-
-#define MAVLINK_MSG_ID_CONRIG_STATE_TC 19
-
-
-typedef struct __mavlink_conrig_state_tc_t {
- uint8_t ignition_btn; /*< Ignition button pressed*/
- uint8_t filling_valve_btn; /*< Open filling valve pressed*/
- uint8_t venting_valve_btn; /*< Open venting valve pressed*/
- uint8_t release_pressure_btn; /*< Release filling line pressure pressed*/
- uint8_t quick_connector_btn; /*< Detach quick connector pressed*/
- uint8_t start_tars_btn; /*< Startup TARS pressed*/
- uint8_t arm_switch; /*< Arming switch state*/
-} mavlink_conrig_state_tc_t;
-
-#define MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN 7
-#define MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN 7
-#define MAVLINK_MSG_ID_19_LEN 7
-#define MAVLINK_MSG_ID_19_MIN_LEN 7
-
-#define MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC 65
-#define MAVLINK_MSG_ID_19_CRC 65
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC { \
- 19, \
- "CONRIG_STATE_TC", \
- 7, \
- { { "ignition_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_conrig_state_tc_t, ignition_btn) }, \
- { "filling_valve_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_conrig_state_tc_t, filling_valve_btn) }, \
- { "venting_valve_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_conrig_state_tc_t, venting_valve_btn) }, \
- { "release_pressure_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_conrig_state_tc_t, release_pressure_btn) }, \
- { "quick_connector_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_conrig_state_tc_t, quick_connector_btn) }, \
- { "start_tars_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_conrig_state_tc_t, start_tars_btn) }, \
- { "arm_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_conrig_state_tc_t, arm_switch) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC { \
- "CONRIG_STATE_TC", \
- 7, \
- { { "ignition_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_conrig_state_tc_t, ignition_btn) }, \
- { "filling_valve_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_conrig_state_tc_t, filling_valve_btn) }, \
- { "venting_valve_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_conrig_state_tc_t, venting_valve_btn) }, \
- { "release_pressure_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_conrig_state_tc_t, release_pressure_btn) }, \
- { "quick_connector_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_conrig_state_tc_t, quick_connector_btn) }, \
- { "start_tars_btn", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_conrig_state_tc_t, start_tars_btn) }, \
- { "arm_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_conrig_state_tc_t, arm_switch) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a conrig_state_tc 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 ignition_btn Ignition button pressed
- * @param filling_valve_btn Open filling valve pressed
- * @param venting_valve_btn Open venting valve pressed
- * @param release_pressure_btn Release filling line pressure pressed
- * @param quick_connector_btn Detach quick connector pressed
- * @param start_tars_btn Startup TARS pressed
- * @param arm_switch Arming switch state
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_conrig_state_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t ignition_btn, uint8_t filling_valve_btn, uint8_t venting_valve_btn, uint8_t release_pressure_btn, uint8_t quick_connector_btn, uint8_t start_tars_btn, uint8_t arm_switch)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN];
- _mav_put_uint8_t(buf, 0, ignition_btn);
- _mav_put_uint8_t(buf, 1, filling_valve_btn);
- _mav_put_uint8_t(buf, 2, venting_valve_btn);
- _mav_put_uint8_t(buf, 3, release_pressure_btn);
- _mav_put_uint8_t(buf, 4, quick_connector_btn);
- _mav_put_uint8_t(buf, 5, start_tars_btn);
- _mav_put_uint8_t(buf, 6, arm_switch);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN);
-#else
- mavlink_conrig_state_tc_t packet;
- packet.ignition_btn = ignition_btn;
- packet.filling_valve_btn = filling_valve_btn;
- packet.venting_valve_btn = venting_valve_btn;
- packet.release_pressure_btn = release_pressure_btn;
- packet.quick_connector_btn = quick_connector_btn;
- packet.start_tars_btn = start_tars_btn;
- packet.arm_switch = arm_switch;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_CONRIG_STATE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC);
-}
-
-/**
- * @brief Pack a conrig_state_tc 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 ignition_btn Ignition button pressed
- * @param filling_valve_btn Open filling valve pressed
- * @param venting_valve_btn Open venting valve pressed
- * @param release_pressure_btn Release filling line pressure pressed
- * @param quick_connector_btn Detach quick connector pressed
- * @param start_tars_btn Startup TARS pressed
- * @param arm_switch Arming switch state
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_conrig_state_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t ignition_btn,uint8_t filling_valve_btn,uint8_t venting_valve_btn,uint8_t release_pressure_btn,uint8_t quick_connector_btn,uint8_t start_tars_btn,uint8_t arm_switch)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN];
- _mav_put_uint8_t(buf, 0, ignition_btn);
- _mav_put_uint8_t(buf, 1, filling_valve_btn);
- _mav_put_uint8_t(buf, 2, venting_valve_btn);
- _mav_put_uint8_t(buf, 3, release_pressure_btn);
- _mav_put_uint8_t(buf, 4, quick_connector_btn);
- _mav_put_uint8_t(buf, 5, start_tars_btn);
- _mav_put_uint8_t(buf, 6, arm_switch);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN);
-#else
- mavlink_conrig_state_tc_t packet;
- packet.ignition_btn = ignition_btn;
- packet.filling_valve_btn = filling_valve_btn;
- packet.venting_valve_btn = venting_valve_btn;
- packet.release_pressure_btn = release_pressure_btn;
- packet.quick_connector_btn = quick_connector_btn;
- packet.start_tars_btn = start_tars_btn;
- packet.arm_switch = arm_switch;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_CONRIG_STATE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC);
-}
-
-/**
- * @brief Encode a conrig_state_tc 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 conrig_state_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_conrig_state_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_conrig_state_tc_t* conrig_state_tc)
-{
- return mavlink_msg_conrig_state_tc_pack(system_id, component_id, msg, conrig_state_tc->ignition_btn, conrig_state_tc->filling_valve_btn, conrig_state_tc->venting_valve_btn, conrig_state_tc->release_pressure_btn, conrig_state_tc->quick_connector_btn, conrig_state_tc->start_tars_btn, conrig_state_tc->arm_switch);
-}
-
-/**
- * @brief Encode a conrig_state_tc 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 conrig_state_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_conrig_state_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_conrig_state_tc_t* conrig_state_tc)
-{
- return mavlink_msg_conrig_state_tc_pack_chan(system_id, component_id, chan, msg, conrig_state_tc->ignition_btn, conrig_state_tc->filling_valve_btn, conrig_state_tc->venting_valve_btn, conrig_state_tc->release_pressure_btn, conrig_state_tc->quick_connector_btn, conrig_state_tc->start_tars_btn, conrig_state_tc->arm_switch);
-}
-
-/**
- * @brief Send a conrig_state_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param ignition_btn Ignition button pressed
- * @param filling_valve_btn Open filling valve pressed
- * @param venting_valve_btn Open venting valve pressed
- * @param release_pressure_btn Release filling line pressure pressed
- * @param quick_connector_btn Detach quick connector pressed
- * @param start_tars_btn Startup TARS pressed
- * @param arm_switch Arming switch state
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_conrig_state_tc_send(mavlink_channel_t chan, uint8_t ignition_btn, uint8_t filling_valve_btn, uint8_t venting_valve_btn, uint8_t release_pressure_btn, uint8_t quick_connector_btn, uint8_t start_tars_btn, uint8_t arm_switch)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN];
- _mav_put_uint8_t(buf, 0, ignition_btn);
- _mav_put_uint8_t(buf, 1, filling_valve_btn);
- _mav_put_uint8_t(buf, 2, venting_valve_btn);
- _mav_put_uint8_t(buf, 3, release_pressure_btn);
- _mav_put_uint8_t(buf, 4, quick_connector_btn);
- _mav_put_uint8_t(buf, 5, start_tars_btn);
- _mav_put_uint8_t(buf, 6, arm_switch);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONRIG_STATE_TC, buf, MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC);
-#else
- mavlink_conrig_state_tc_t packet;
- packet.ignition_btn = ignition_btn;
- packet.filling_valve_btn = filling_valve_btn;
- packet.venting_valve_btn = venting_valve_btn;
- packet.release_pressure_btn = release_pressure_btn;
- packet.quick_connector_btn = quick_connector_btn;
- packet.start_tars_btn = start_tars_btn;
- packet.arm_switch = arm_switch;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONRIG_STATE_TC, (const char *)&packet, MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a conrig_state_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_conrig_state_tc_send_struct(mavlink_channel_t chan, const mavlink_conrig_state_tc_t* conrig_state_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_conrig_state_tc_send(chan, conrig_state_tc->ignition_btn, conrig_state_tc->filling_valve_btn, conrig_state_tc->venting_valve_btn, conrig_state_tc->release_pressure_btn, conrig_state_tc->quick_connector_btn, conrig_state_tc->start_tars_btn, conrig_state_tc->arm_switch);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONRIG_STATE_TC, (const char *)conrig_state_tc, MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_CONRIG_STATE_TC_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_conrig_state_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t ignition_btn, uint8_t filling_valve_btn, uint8_t venting_valve_btn, uint8_t release_pressure_btn, uint8_t quick_connector_btn, uint8_t start_tars_btn, uint8_t arm_switch)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, ignition_btn);
- _mav_put_uint8_t(buf, 1, filling_valve_btn);
- _mav_put_uint8_t(buf, 2, venting_valve_btn);
- _mav_put_uint8_t(buf, 3, release_pressure_btn);
- _mav_put_uint8_t(buf, 4, quick_connector_btn);
- _mav_put_uint8_t(buf, 5, start_tars_btn);
- _mav_put_uint8_t(buf, 6, arm_switch);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONRIG_STATE_TC, buf, MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC);
-#else
- mavlink_conrig_state_tc_t *packet = (mavlink_conrig_state_tc_t *)msgbuf;
- packet->ignition_btn = ignition_btn;
- packet->filling_valve_btn = filling_valve_btn;
- packet->venting_valve_btn = venting_valve_btn;
- packet->release_pressure_btn = release_pressure_btn;
- packet->quick_connector_btn = quick_connector_btn;
- packet->start_tars_btn = start_tars_btn;
- packet->arm_switch = arm_switch;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONRIG_STATE_TC, (const char *)packet, MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN, MAVLINK_MSG_ID_CONRIG_STATE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE CONRIG_STATE_TC UNPACKING
-
-
-/**
- * @brief Get field ignition_btn from conrig_state_tc message
- *
- * @return Ignition button pressed
- */
-static inline uint8_t mavlink_msg_conrig_state_tc_get_ignition_btn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field filling_valve_btn from conrig_state_tc message
- *
- * @return Open filling valve pressed
- */
-static inline uint8_t mavlink_msg_conrig_state_tc_get_filling_valve_btn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Get field venting_valve_btn from conrig_state_tc message
- *
- * @return Open venting valve pressed
- */
-static inline uint8_t mavlink_msg_conrig_state_tc_get_venting_valve_btn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 2);
-}
-
-/**
- * @brief Get field release_pressure_btn from conrig_state_tc message
- *
- * @return Release filling line pressure pressed
- */
-static inline uint8_t mavlink_msg_conrig_state_tc_get_release_pressure_btn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 3);
-}
-
-/**
- * @brief Get field quick_connector_btn from conrig_state_tc message
- *
- * @return Detach quick connector pressed
- */
-static inline uint8_t mavlink_msg_conrig_state_tc_get_quick_connector_btn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 4);
-}
-
-/**
- * @brief Get field start_tars_btn from conrig_state_tc message
- *
- * @return Startup TARS pressed
- */
-static inline uint8_t mavlink_msg_conrig_state_tc_get_start_tars_btn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 5);
-}
-
-/**
- * @brief Get field arm_switch from conrig_state_tc message
- *
- * @return Arming switch state
- */
-static inline uint8_t mavlink_msg_conrig_state_tc_get_arm_switch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 6);
-}
-
-/**
- * @brief Decode a conrig_state_tc message into a struct
- *
- * @param msg The message to decode
- * @param conrig_state_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_conrig_state_tc_decode(const mavlink_message_t* msg, mavlink_conrig_state_tc_t* conrig_state_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- conrig_state_tc->ignition_btn = mavlink_msg_conrig_state_tc_get_ignition_btn(msg);
- conrig_state_tc->filling_valve_btn = mavlink_msg_conrig_state_tc_get_filling_valve_btn(msg);
- conrig_state_tc->venting_valve_btn = mavlink_msg_conrig_state_tc_get_venting_valve_btn(msg);
- conrig_state_tc->release_pressure_btn = mavlink_msg_conrig_state_tc_get_release_pressure_btn(msg);
- conrig_state_tc->quick_connector_btn = mavlink_msg_conrig_state_tc_get_quick_connector_btn(msg);
- conrig_state_tc->start_tars_btn = mavlink_msg_conrig_state_tc_get_start_tars_btn(msg);
- conrig_state_tc->arm_switch = mavlink_msg_conrig_state_tc_get_arm_switch(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN? msg->len : MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN;
- memset(conrig_state_tc, 0, MAVLINK_MSG_ID_CONRIG_STATE_TC_LEN);
- memcpy(conrig_state_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_current_tm.h b/mavlink_lib/lyra/mavlink_msg_current_tm.h
deleted file mode 100644
index a63460b470e330fb90ada85f4cf61a1ec67401b2..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_current_tm.h
+++ /dev/null
@@ -1,255 +0,0 @@
-#pragma once
-// MESSAGE CURRENT_TM PACKING
-
-#define MAVLINK_MSG_ID_CURRENT_TM 107
-
-
-typedef struct __mavlink_current_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float current; /*< [A] Current*/
- char sensor_name[20]; /*< Sensor name*/
-} mavlink_current_tm_t;
-
-#define MAVLINK_MSG_ID_CURRENT_TM_LEN 32
-#define MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_107_LEN 32
-#define MAVLINK_MSG_ID_107_MIN_LEN 32
-
-#define MAVLINK_MSG_ID_CURRENT_TM_CRC 212
-#define MAVLINK_MSG_ID_107_CRC 212
-
-#define MAVLINK_MSG_CURRENT_TM_FIELD_SENSOR_NAME_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_CURRENT_TM { \
- 107, \
- "CURRENT_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_current_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_current_tm_t, sensor_name) }, \
- { "current", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_current_tm_t, current) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_CURRENT_TM { \
- "CURRENT_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_current_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_current_tm_t, sensor_name) }, \
- { "current", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_current_tm_t, current) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a current_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param current [A] Current
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_current_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_name, float current)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CURRENT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, current);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CURRENT_TM_LEN);
-#else
- mavlink_current_tm_t packet;
- packet.timestamp = timestamp;
- packet.current = current;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CURRENT_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_CURRENT_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-}
-
-/**
- * @brief Pack a current_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param current [A] Current
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_current_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_name,float current)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CURRENT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, current);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CURRENT_TM_LEN);
-#else
- mavlink_current_tm_t packet;
- packet.timestamp = timestamp;
- packet.current = current;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CURRENT_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_CURRENT_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-}
-
-/**
- * @brief Encode a current_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_current_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_current_tm_t* current_tm)
-{
- return mavlink_msg_current_tm_pack(system_id, component_id, msg, current_tm->timestamp, current_tm->sensor_name, current_tm->current);
-}
-
-/**
- * @brief Encode a current_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_current_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_current_tm_t* current_tm)
-{
- return mavlink_msg_current_tm_pack_chan(system_id, component_id, chan, msg, current_tm->timestamp, current_tm->sensor_name, current_tm->current);
-}
-
-/**
- * @brief Send a current_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_name Sensor name
- * @param current [A] Current
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_current_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float current)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CURRENT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, current);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CURRENT_TM, buf, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-#else
- mavlink_current_tm_t packet;
- packet.timestamp = timestamp;
- packet.current = current;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CURRENT_TM, (const char *)&packet, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a current_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_current_tm_send_struct(mavlink_channel_t chan, const mavlink_current_tm_t* current_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_current_tm_send(chan, current_tm->timestamp, current_tm->sensor_name, current_tm->current);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CURRENT_TM, (const char *)current_tm, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_CURRENT_TM_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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float current)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, current);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CURRENT_TM, buf, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-#else
- mavlink_current_tm_t *packet = (mavlink_current_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->current = current;
- mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CURRENT_TM, (const char *)packet, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE CURRENT_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from current_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_current_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_name from current_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_current_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
-{
- return _MAV_RETURN_char_array(msg, sensor_name, 20, 12);
-}
-
-/**
- * @brief Get field current from current_tm message
- *
- * @return [A] Current
- */
-static inline float mavlink_msg_current_tm_get_current(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Decode a current_tm message into a struct
- *
- * @param msg The message to decode
- * @param current_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_current_tm_decode(const mavlink_message_t* msg, mavlink_current_tm_t* current_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- current_tm->timestamp = mavlink_msg_current_tm_get_timestamp(msg);
- current_tm->current = mavlink_msg_current_tm_get_current(msg);
- mavlink_msg_current_tm_get_sensor_name(msg, current_tm->sensor_name);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_CURRENT_TM_LEN? msg->len : MAVLINK_MSG_ID_CURRENT_TM_LEN;
- memset(current_tm, 0, MAVLINK_MSG_ID_CURRENT_TM_LEN);
- memcpy(current_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_fsm_tm.h b/mavlink_lib/lyra/mavlink_msg_fsm_tm.h
deleted file mode 100644
index cc60afc359614defcc489ad0497c01e43dfc908a..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_fsm_tm.h
+++ /dev/null
@@ -1,363 +0,0 @@
-#pragma once
-// MESSAGE FSM_TM PACKING
-
-#define MAVLINK_MSG_ID_FSM_TM 201
-
-
-typedef struct __mavlink_fsm_tm_t {
- uint64_t timestamp; /*< [us] Timestamp*/
- uint8_t ada_state; /*< Apogee Detection Algorithm state*/
- uint8_t abk_state; /*< Air Brakes state*/
- uint8_t dpl_state; /*< Deployment state*/
- uint8_t fmm_state; /*< Flight Mode Manager state*/
- uint8_t nas_state; /*< Navigation and Attitude System state*/
- uint8_t wes_state; /*< Wind Estimation System state*/
-} mavlink_fsm_tm_t;
-
-#define MAVLINK_MSG_ID_FSM_TM_LEN 14
-#define MAVLINK_MSG_ID_FSM_TM_MIN_LEN 14
-#define MAVLINK_MSG_ID_201_LEN 14
-#define MAVLINK_MSG_ID_201_MIN_LEN 14
-
-#define MAVLINK_MSG_ID_FSM_TM_CRC 242
-#define MAVLINK_MSG_ID_201_CRC 242
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_FSM_TM { \
- 201, \
- "FSM_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_fsm_tm_t, timestamp) }, \
- { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fsm_tm_t, ada_state) }, \
- { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_fsm_tm_t, abk_state) }, \
- { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_fsm_tm_t, dpl_state) }, \
- { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_fsm_tm_t, fmm_state) }, \
- { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_fsm_tm_t, nas_state) }, \
- { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_fsm_tm_t, wes_state) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_FSM_TM { \
- "FSM_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_fsm_tm_t, timestamp) }, \
- { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fsm_tm_t, ada_state) }, \
- { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_fsm_tm_t, abk_state) }, \
- { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_fsm_tm_t, dpl_state) }, \
- { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_fsm_tm_t, fmm_state) }, \
- { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_fsm_tm_t, nas_state) }, \
- { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_fsm_tm_t, wes_state) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a fsm_tm 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
- * @param ada_state Apogee Detection Algorithm state
- * @param abk_state Air Brakes state
- * @param dpl_state Deployment state
- * @param fmm_state Flight Mode Manager state
- * @param nas_state Navigation and Attitude System state
- * @param wes_state Wind Estimation System state
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_fsm_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t ada_state, uint8_t abk_state, uint8_t dpl_state, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_FSM_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, ada_state);
- _mav_put_uint8_t(buf, 9, abk_state);
- _mav_put_uint8_t(buf, 10, dpl_state);
- _mav_put_uint8_t(buf, 11, fmm_state);
- _mav_put_uint8_t(buf, 12, nas_state);
- _mav_put_uint8_t(buf, 13, wes_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FSM_TM_LEN);
-#else
- mavlink_fsm_tm_t packet;
- packet.timestamp = timestamp;
- packet.ada_state = ada_state;
- packet.abk_state = abk_state;
- packet.dpl_state = dpl_state;
- packet.fmm_state = fmm_state;
- packet.nas_state = nas_state;
- packet.wes_state = wes_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FSM_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_FSM_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-}
-
-/**
- * @brief Pack a fsm_tm 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
- * @param ada_state Apogee Detection Algorithm state
- * @param abk_state Air Brakes state
- * @param dpl_state Deployment state
- * @param fmm_state Flight Mode Manager state
- * @param nas_state Navigation and Attitude System state
- * @param wes_state Wind Estimation System state
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_fsm_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t ada_state,uint8_t abk_state,uint8_t dpl_state,uint8_t fmm_state,uint8_t nas_state,uint8_t wes_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_FSM_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, ada_state);
- _mav_put_uint8_t(buf, 9, abk_state);
- _mav_put_uint8_t(buf, 10, dpl_state);
- _mav_put_uint8_t(buf, 11, fmm_state);
- _mav_put_uint8_t(buf, 12, nas_state);
- _mav_put_uint8_t(buf, 13, wes_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FSM_TM_LEN);
-#else
- mavlink_fsm_tm_t packet;
- packet.timestamp = timestamp;
- packet.ada_state = ada_state;
- packet.abk_state = abk_state;
- packet.dpl_state = dpl_state;
- packet.fmm_state = fmm_state;
- packet.nas_state = nas_state;
- packet.wes_state = wes_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FSM_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_FSM_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-}
-
-/**
- * @brief Encode a fsm_tm 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 fsm_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_fsm_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fsm_tm_t* fsm_tm)
-{
- return mavlink_msg_fsm_tm_pack(system_id, component_id, msg, fsm_tm->timestamp, fsm_tm->ada_state, fsm_tm->abk_state, fsm_tm->dpl_state, fsm_tm->fmm_state, fsm_tm->nas_state, fsm_tm->wes_state);
-}
-
-/**
- * @brief Encode a fsm_tm 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 fsm_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_fsm_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fsm_tm_t* fsm_tm)
-{
- return mavlink_msg_fsm_tm_pack_chan(system_id, component_id, chan, msg, fsm_tm->timestamp, fsm_tm->ada_state, fsm_tm->abk_state, fsm_tm->dpl_state, fsm_tm->fmm_state, fsm_tm->nas_state, fsm_tm->wes_state);
-}
-
-/**
- * @brief Send a fsm_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp
- * @param ada_state Apogee Detection Algorithm state
- * @param abk_state Air Brakes state
- * @param dpl_state Deployment state
- * @param fmm_state Flight Mode Manager state
- * @param nas_state Navigation and Attitude System state
- * @param wes_state Wind Estimation System state
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_fsm_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t abk_state, uint8_t dpl_state, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_FSM_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, ada_state);
- _mav_put_uint8_t(buf, 9, abk_state);
- _mav_put_uint8_t(buf, 10, dpl_state);
- _mav_put_uint8_t(buf, 11, fmm_state);
- _mav_put_uint8_t(buf, 12, nas_state);
- _mav_put_uint8_t(buf, 13, wes_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, buf, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-#else
- mavlink_fsm_tm_t packet;
- packet.timestamp = timestamp;
- packet.ada_state = ada_state;
- packet.abk_state = abk_state;
- packet.dpl_state = dpl_state;
- packet.fmm_state = fmm_state;
- packet.nas_state = nas_state;
- packet.wes_state = wes_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, (const char *)&packet, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a fsm_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_fsm_tm_send_struct(mavlink_channel_t chan, const mavlink_fsm_tm_t* fsm_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_fsm_tm_send(chan, fsm_tm->timestamp, fsm_tm->ada_state, fsm_tm->abk_state, fsm_tm->dpl_state, fsm_tm->fmm_state, fsm_tm->nas_state, fsm_tm->wes_state);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, (const char *)fsm_tm, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_FSM_TM_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_fsm_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t abk_state, uint8_t dpl_state, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, ada_state);
- _mav_put_uint8_t(buf, 9, abk_state);
- _mav_put_uint8_t(buf, 10, dpl_state);
- _mav_put_uint8_t(buf, 11, fmm_state);
- _mav_put_uint8_t(buf, 12, nas_state);
- _mav_put_uint8_t(buf, 13, wes_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, buf, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-#else
- mavlink_fsm_tm_t *packet = (mavlink_fsm_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->ada_state = ada_state;
- packet->abk_state = abk_state;
- packet->dpl_state = dpl_state;
- packet->fmm_state = fmm_state;
- packet->nas_state = nas_state;
- packet->wes_state = wes_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, (const char *)packet, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE FSM_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from fsm_tm message
- *
- * @return [us] Timestamp
- */
-static inline uint64_t mavlink_msg_fsm_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field ada_state from fsm_tm message
- *
- * @return Apogee Detection Algorithm state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_ada_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 8);
-}
-
-/**
- * @brief Get field abk_state from fsm_tm message
- *
- * @return Air Brakes state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_abk_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 9);
-}
-
-/**
- * @brief Get field dpl_state from fsm_tm message
- *
- * @return Deployment state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_dpl_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 10);
-}
-
-/**
- * @brief Get field fmm_state from fsm_tm message
- *
- * @return Flight Mode Manager state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_fmm_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 11);
-}
-
-/**
- * @brief Get field nas_state from fsm_tm message
- *
- * @return Navigation and Attitude System state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_nas_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 12);
-}
-
-/**
- * @brief Get field wes_state from fsm_tm message
- *
- * @return Wind Estimation System state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_wes_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 13);
-}
-
-/**
- * @brief Decode a fsm_tm message into a struct
- *
- * @param msg The message to decode
- * @param fsm_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_fsm_tm_decode(const mavlink_message_t* msg, mavlink_fsm_tm_t* fsm_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- fsm_tm->timestamp = mavlink_msg_fsm_tm_get_timestamp(msg);
- fsm_tm->ada_state = mavlink_msg_fsm_tm_get_ada_state(msg);
- fsm_tm->abk_state = mavlink_msg_fsm_tm_get_abk_state(msg);
- fsm_tm->dpl_state = mavlink_msg_fsm_tm_get_dpl_state(msg);
- fsm_tm->fmm_state = mavlink_msg_fsm_tm_get_fmm_state(msg);
- fsm_tm->nas_state = mavlink_msg_fsm_tm_get_nas_state(msg);
- fsm_tm->wes_state = mavlink_msg_fsm_tm_get_wes_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_FSM_TM_LEN? msg->len : MAVLINK_MSG_ID_FSM_TM_LEN;
- memset(fsm_tm, 0, MAVLINK_MSG_ID_FSM_TM_LEN);
- memcpy(fsm_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_gps_tm.h b/mavlink_lib/lyra/mavlink_msg_gps_tm.h
deleted file mode 100644
index 96f4891e5530a812d22ae2891cded1543bfddd74..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_gps_tm.h
+++ /dev/null
@@ -1,480 +0,0 @@
-#pragma once
-// MESSAGE GPS_TM PACKING
-
-#define MAVLINK_MSG_ID_GPS_TM 102
-
-
-typedef struct __mavlink_gps_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- double latitude; /*< [deg] Latitude*/
- double longitude; /*< [deg] Longitude*/
- double height; /*< [m] Altitude*/
- float vel_north; /*< [m/s] Velocity in NED frame (north)*/
- float vel_east; /*< [m/s] Velocity in NED frame (east)*/
- float vel_down; /*< [m/s] Velocity in NED frame (down)*/
- float speed; /*< [m/s] Speed*/
- float track; /*< [deg] Track*/
- char sensor_name[20]; /*< Sensor name*/
- uint8_t fix; /*< Wether the GPS has a FIX*/
- uint8_t n_satellites; /*< Number of connected satellites*/
-} mavlink_gps_tm_t;
-
-#define MAVLINK_MSG_ID_GPS_TM_LEN 74
-#define MAVLINK_MSG_ID_GPS_TM_MIN_LEN 74
-#define MAVLINK_MSG_ID_102_LEN 74
-#define MAVLINK_MSG_ID_102_MIN_LEN 74
-
-#define MAVLINK_MSG_ID_GPS_TM_CRC 57
-#define MAVLINK_MSG_ID_102_CRC 57
-
-#define MAVLINK_MSG_GPS_TM_FIELD_SENSOR_NAME_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_GPS_TM { \
- 102, \
- "GPS_TM", \
- 12, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 52, offsetof(mavlink_gps_tm_t, sensor_name) }, \
- { "fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 72, offsetof(mavlink_gps_tm_t, fix) }, \
- { "latitude", NULL, MAVLINK_TYPE_DOUBLE, 0, 8, offsetof(mavlink_gps_tm_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_DOUBLE, 0, 16, offsetof(mavlink_gps_tm_t, longitude) }, \
- { "height", NULL, MAVLINK_TYPE_DOUBLE, 0, 24, offsetof(mavlink_gps_tm_t, height) }, \
- { "vel_north", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_tm_t, vel_north) }, \
- { "vel_east", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gps_tm_t, vel_east) }, \
- { "vel_down", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gps_tm_t, vel_down) }, \
- { "speed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_tm_t, speed) }, \
- { "track", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_tm_t, track) }, \
- { "n_satellites", NULL, MAVLINK_TYPE_UINT8_T, 0, 73, offsetof(mavlink_gps_tm_t, n_satellites) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_GPS_TM { \
- "GPS_TM", \
- 12, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 52, offsetof(mavlink_gps_tm_t, sensor_name) }, \
- { "fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 72, offsetof(mavlink_gps_tm_t, fix) }, \
- { "latitude", NULL, MAVLINK_TYPE_DOUBLE, 0, 8, offsetof(mavlink_gps_tm_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_DOUBLE, 0, 16, offsetof(mavlink_gps_tm_t, longitude) }, \
- { "height", NULL, MAVLINK_TYPE_DOUBLE, 0, 24, offsetof(mavlink_gps_tm_t, height) }, \
- { "vel_north", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_tm_t, vel_north) }, \
- { "vel_east", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gps_tm_t, vel_east) }, \
- { "vel_down", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gps_tm_t, vel_down) }, \
- { "speed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_tm_t, speed) }, \
- { "track", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_tm_t, track) }, \
- { "n_satellites", NULL, MAVLINK_TYPE_UINT8_T, 0, 73, offsetof(mavlink_gps_tm_t, n_satellites) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a gps_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param fix Wether the GPS has a FIX
- * @param latitude [deg] Latitude
- * @param longitude [deg] Longitude
- * @param height [m] Altitude
- * @param vel_north [m/s] Velocity in NED frame (north)
- * @param vel_east [m/s] Velocity in NED frame (east)
- * @param vel_down [m/s] Velocity in NED frame (down)
- * @param speed [m/s] Speed
- * @param track [deg] Track
- * @param n_satellites Number of connected satellites
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_gps_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_name, uint8_t fix, double latitude, double longitude, double height, float vel_north, float vel_east, float vel_down, float speed, float track, uint8_t n_satellites)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GPS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, latitude);
- _mav_put_double(buf, 16, longitude);
- _mav_put_double(buf, 24, height);
- _mav_put_float(buf, 32, vel_north);
- _mav_put_float(buf, 36, vel_east);
- _mav_put_float(buf, 40, vel_down);
- _mav_put_float(buf, 44, speed);
- _mav_put_float(buf, 48, track);
- _mav_put_uint8_t(buf, 72, fix);
- _mav_put_uint8_t(buf, 73, n_satellites);
- _mav_put_char_array(buf, 52, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_TM_LEN);
-#else
- mavlink_gps_tm_t packet;
- packet.timestamp = timestamp;
- packet.latitude = latitude;
- packet.longitude = longitude;
- packet.height = height;
- packet.vel_north = vel_north;
- packet.vel_east = vel_east;
- packet.vel_down = vel_down;
- packet.speed = speed;
- packet.track = track;
- packet.fix = fix;
- packet.n_satellites = n_satellites;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_GPS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-}
-
-/**
- * @brief Pack a gps_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param fix Wether the GPS has a FIX
- * @param latitude [deg] Latitude
- * @param longitude [deg] Longitude
- * @param height [m] Altitude
- * @param vel_north [m/s] Velocity in NED frame (north)
- * @param vel_east [m/s] Velocity in NED frame (east)
- * @param vel_down [m/s] Velocity in NED frame (down)
- * @param speed [m/s] Speed
- * @param track [deg] Track
- * @param n_satellites Number of connected satellites
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_gps_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_name,uint8_t fix,double latitude,double longitude,double height,float vel_north,float vel_east,float vel_down,float speed,float track,uint8_t n_satellites)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GPS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, latitude);
- _mav_put_double(buf, 16, longitude);
- _mav_put_double(buf, 24, height);
- _mav_put_float(buf, 32, vel_north);
- _mav_put_float(buf, 36, vel_east);
- _mav_put_float(buf, 40, vel_down);
- _mav_put_float(buf, 44, speed);
- _mav_put_float(buf, 48, track);
- _mav_put_uint8_t(buf, 72, fix);
- _mav_put_uint8_t(buf, 73, n_satellites);
- _mav_put_char_array(buf, 52, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_TM_LEN);
-#else
- mavlink_gps_tm_t packet;
- packet.timestamp = timestamp;
- packet.latitude = latitude;
- packet.longitude = longitude;
- packet.height = height;
- packet.vel_north = vel_north;
- packet.vel_east = vel_east;
- packet.vel_down = vel_down;
- packet.speed = speed;
- packet.track = track;
- packet.fix = fix;
- packet.n_satellites = n_satellites;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_GPS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-}
-
-/**
- * @brief Encode a gps_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_gps_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_tm_t* gps_tm)
-{
- return mavlink_msg_gps_tm_pack(system_id, component_id, msg, gps_tm->timestamp, gps_tm->sensor_name, gps_tm->fix, gps_tm->latitude, gps_tm->longitude, gps_tm->height, gps_tm->vel_north, gps_tm->vel_east, gps_tm->vel_down, gps_tm->speed, gps_tm->track, gps_tm->n_satellites);
-}
-
-/**
- * @brief Encode a gps_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_gps_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_tm_t* gps_tm)
-{
- return mavlink_msg_gps_tm_pack_chan(system_id, component_id, chan, msg, gps_tm->timestamp, gps_tm->sensor_name, gps_tm->fix, gps_tm->latitude, gps_tm->longitude, gps_tm->height, gps_tm->vel_north, gps_tm->vel_east, gps_tm->vel_down, gps_tm->speed, gps_tm->track, gps_tm->n_satellites);
-}
-
-/**
- * @brief Send a gps_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_name Sensor name
- * @param fix Wether the GPS has a FIX
- * @param latitude [deg] Latitude
- * @param longitude [deg] Longitude
- * @param height [m] Altitude
- * @param vel_north [m/s] Velocity in NED frame (north)
- * @param vel_east [m/s] Velocity in NED frame (east)
- * @param vel_down [m/s] Velocity in NED frame (down)
- * @param speed [m/s] Speed
- * @param track [deg] Track
- * @param n_satellites Number of connected satellites
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_gps_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, uint8_t fix, double latitude, double longitude, double height, float vel_north, float vel_east, float vel_down, float speed, float track, uint8_t n_satellites)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GPS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, latitude);
- _mav_put_double(buf, 16, longitude);
- _mav_put_double(buf, 24, height);
- _mav_put_float(buf, 32, vel_north);
- _mav_put_float(buf, 36, vel_east);
- _mav_put_float(buf, 40, vel_down);
- _mav_put_float(buf, 44, speed);
- _mav_put_float(buf, 48, track);
- _mav_put_uint8_t(buf, 72, fix);
- _mav_put_uint8_t(buf, 73, n_satellites);
- _mav_put_char_array(buf, 52, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, buf, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#else
- mavlink_gps_tm_t packet;
- packet.timestamp = timestamp;
- packet.latitude = latitude;
- packet.longitude = longitude;
- packet.height = height;
- packet.vel_north = vel_north;
- packet.vel_east = vel_east;
- packet.vel_down = vel_down;
- packet.speed = speed;
- packet.track = track;
- packet.fix = fix;
- packet.n_satellites = n_satellites;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, (const char *)&packet, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a gps_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_gps_tm_send_struct(mavlink_channel_t chan, const mavlink_gps_tm_t* gps_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_gps_tm_send(chan, gps_tm->timestamp, gps_tm->sensor_name, gps_tm->fix, gps_tm->latitude, gps_tm->longitude, gps_tm->height, gps_tm->vel_north, gps_tm->vel_east, gps_tm->vel_down, gps_tm->speed, gps_tm->track, gps_tm->n_satellites);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, (const char *)gps_tm, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_GPS_TM_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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, uint8_t fix, double latitude, double longitude, double height, float vel_north, float vel_east, float vel_down, float speed, float track, uint8_t n_satellites)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, latitude);
- _mav_put_double(buf, 16, longitude);
- _mav_put_double(buf, 24, height);
- _mav_put_float(buf, 32, vel_north);
- _mav_put_float(buf, 36, vel_east);
- _mav_put_float(buf, 40, vel_down);
- _mav_put_float(buf, 44, speed);
- _mav_put_float(buf, 48, track);
- _mav_put_uint8_t(buf, 72, fix);
- _mav_put_uint8_t(buf, 73, n_satellites);
- _mav_put_char_array(buf, 52, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, buf, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#else
- mavlink_gps_tm_t *packet = (mavlink_gps_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->latitude = latitude;
- packet->longitude = longitude;
- packet->height = height;
- packet->vel_north = vel_north;
- packet->vel_east = vel_east;
- packet->vel_down = vel_down;
- packet->speed = speed;
- packet->track = track;
- packet->fix = fix;
- packet->n_satellites = n_satellites;
- mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, (const char *)packet, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE GPS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from gps_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_gps_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_name from gps_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_gps_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
-{
- return _MAV_RETURN_char_array(msg, sensor_name, 20, 52);
-}
-
-/**
- * @brief Get field fix from gps_tm message
- *
- * @return Wether the GPS has a FIX
- */
-static inline uint8_t mavlink_msg_gps_tm_get_fix(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 72);
-}
-
-/**
- * @brief Get field latitude from gps_tm message
- *
- * @return [deg] Latitude
- */
-static inline double mavlink_msg_gps_tm_get_latitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_double(msg, 8);
-}
-
-/**
- * @brief Get field longitude from gps_tm message
- *
- * @return [deg] Longitude
- */
-static inline double mavlink_msg_gps_tm_get_longitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_double(msg, 16);
-}
-
-/**
- * @brief Get field height from gps_tm message
- *
- * @return [m] Altitude
- */
-static inline double mavlink_msg_gps_tm_get_height(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_double(msg, 24);
-}
-
-/**
- * @brief Get field vel_north from gps_tm message
- *
- * @return [m/s] Velocity in NED frame (north)
- */
-static inline float mavlink_msg_gps_tm_get_vel_north(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field vel_east from gps_tm message
- *
- * @return [m/s] Velocity in NED frame (east)
- */
-static inline float mavlink_msg_gps_tm_get_vel_east(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field vel_down from gps_tm message
- *
- * @return [m/s] Velocity in NED frame (down)
- */
-static inline float mavlink_msg_gps_tm_get_vel_down(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field speed from gps_tm message
- *
- * @return [m/s] Speed
- */
-static inline float mavlink_msg_gps_tm_get_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field track from gps_tm message
- *
- * @return [deg] Track
- */
-static inline float mavlink_msg_gps_tm_get_track(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field n_satellites from gps_tm message
- *
- * @return Number of connected satellites
- */
-static inline uint8_t mavlink_msg_gps_tm_get_n_satellites(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 73);
-}
-
-/**
- * @brief Decode a gps_tm message into a struct
- *
- * @param msg The message to decode
- * @param gps_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_gps_tm_decode(const mavlink_message_t* msg, mavlink_gps_tm_t* gps_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- gps_tm->timestamp = mavlink_msg_gps_tm_get_timestamp(msg);
- gps_tm->latitude = mavlink_msg_gps_tm_get_latitude(msg);
- gps_tm->longitude = mavlink_msg_gps_tm_get_longitude(msg);
- gps_tm->height = mavlink_msg_gps_tm_get_height(msg);
- gps_tm->vel_north = mavlink_msg_gps_tm_get_vel_north(msg);
- gps_tm->vel_east = mavlink_msg_gps_tm_get_vel_east(msg);
- gps_tm->vel_down = mavlink_msg_gps_tm_get_vel_down(msg);
- gps_tm->speed = mavlink_msg_gps_tm_get_speed(msg);
- gps_tm->track = mavlink_msg_gps_tm_get_track(msg);
- mavlink_msg_gps_tm_get_sensor_name(msg, gps_tm->sensor_name);
- gps_tm->fix = mavlink_msg_gps_tm_get_fix(msg);
- gps_tm->n_satellites = mavlink_msg_gps_tm_get_n_satellites(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_TM_LEN? msg->len : MAVLINK_MSG_ID_GPS_TM_LEN;
- memset(gps_tm, 0, MAVLINK_MSG_ID_GPS_TM_LEN);
- memcpy(gps_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_gse_tm.h b/mavlink_lib/lyra/mavlink_msg_gse_tm.h
deleted file mode 100644
index 5b5742e639f0cc49886bd5df0396e8821a9075b3..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_gse_tm.h
+++ /dev/null
@@ -1,613 +0,0 @@
-#pragma once
-// MESSAGE GSE_TM PACKING
-
-#define MAVLINK_MSG_ID_GSE_TM 212
-
-
-typedef struct __mavlink_gse_tm_t {
- uint64_t timestamp; /*< [us] Timestamp in microseconds*/
- float loadcell_rocket; /*< [kg] Rocket weight*/
- float loadcell_vessel; /*< [kg] External tank weight*/
- float filling_pressure; /*< [Bar] Refueling line pressure*/
- float vessel_pressure; /*< [Bar] Vessel tank pressure*/
- float battery_voltage; /*< Battery voltage*/
- float current_consumption; /*< RIG current */
- uint8_t arming_state; /*< 1 If the rocket is armed*/
- uint8_t filling_valve_state; /*< 1 If the filling valve is open*/
- uint8_t venting_valve_state; /*< 1 If the venting valve is open*/
- uint8_t release_valve_state; /*< 1 If the release valve is open*/
- uint8_t main_valve_state; /*< 1 If the main valve is open */
- uint8_t ignition_state; /*< 1 If the RIG is in ignition process*/
- uint8_t tars_state; /*< 1 If the TARS algorithm is running*/
- uint8_t main_board_status; /*< MAIN board status [0: not present, 1: online, 2: armed]*/
- uint8_t payload_board_status; /*< PAYLOAD board status [0: not present, 1: online, 2: armed]*/
- uint8_t motor_board_status; /*< MOTOR board status [0: not present, 1: online, 2: armed]*/
-} mavlink_gse_tm_t;
-
-#define MAVLINK_MSG_ID_GSE_TM_LEN 42
-#define MAVLINK_MSG_ID_GSE_TM_MIN_LEN 42
-#define MAVLINK_MSG_ID_212_LEN 42
-#define MAVLINK_MSG_ID_212_MIN_LEN 42
-
-#define MAVLINK_MSG_ID_GSE_TM_CRC 63
-#define MAVLINK_MSG_ID_212_CRC 63
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_GSE_TM { \
- 212, \
- "GSE_TM", \
- 17, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gse_tm_t, timestamp) }, \
- { "loadcell_rocket", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gse_tm_t, loadcell_rocket) }, \
- { "loadcell_vessel", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gse_tm_t, loadcell_vessel) }, \
- { "filling_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gse_tm_t, filling_pressure) }, \
- { "vessel_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gse_tm_t, vessel_pressure) }, \
- { "arming_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gse_tm_t, arming_state) }, \
- { "filling_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gse_tm_t, filling_valve_state) }, \
- { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gse_tm_t, venting_valve_state) }, \
- { "release_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_gse_tm_t, release_valve_state) }, \
- { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_gse_tm_t, main_valve_state) }, \
- { "ignition_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_gse_tm_t, ignition_state) }, \
- { "tars_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_gse_tm_t, tars_state) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gse_tm_t, battery_voltage) }, \
- { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gse_tm_t, current_consumption) }, \
- { "main_board_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_gse_tm_t, main_board_status) }, \
- { "payload_board_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_gse_tm_t, payload_board_status) }, \
- { "motor_board_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_gse_tm_t, motor_board_status) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_GSE_TM { \
- "GSE_TM", \
- 17, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gse_tm_t, timestamp) }, \
- { "loadcell_rocket", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gse_tm_t, loadcell_rocket) }, \
- { "loadcell_vessel", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gse_tm_t, loadcell_vessel) }, \
- { "filling_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gse_tm_t, filling_pressure) }, \
- { "vessel_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gse_tm_t, vessel_pressure) }, \
- { "arming_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gse_tm_t, arming_state) }, \
- { "filling_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gse_tm_t, filling_valve_state) }, \
- { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gse_tm_t, venting_valve_state) }, \
- { "release_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_gse_tm_t, release_valve_state) }, \
- { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_gse_tm_t, main_valve_state) }, \
- { "ignition_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_gse_tm_t, ignition_state) }, \
- { "tars_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_gse_tm_t, tars_state) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gse_tm_t, battery_voltage) }, \
- { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gse_tm_t, current_consumption) }, \
- { "main_board_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_gse_tm_t, main_board_status) }, \
- { "payload_board_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_gse_tm_t, payload_board_status) }, \
- { "motor_board_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_gse_tm_t, motor_board_status) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a gse_tm 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 in microseconds
- * @param loadcell_rocket [kg] Rocket weight
- * @param loadcell_vessel [kg] External tank weight
- * @param filling_pressure [Bar] Refueling line pressure
- * @param vessel_pressure [Bar] Vessel tank pressure
- * @param arming_state 1 If the rocket is armed
- * @param filling_valve_state 1 If the filling valve is open
- * @param venting_valve_state 1 If the venting valve is open
- * @param release_valve_state 1 If the release valve is open
- * @param main_valve_state 1 If the main valve is open
- * @param ignition_state 1 If the RIG is in ignition process
- * @param tars_state 1 If the TARS algorithm is running
- * @param battery_voltage Battery voltage
- * @param current_consumption RIG current
- * @param main_board_status MAIN board status [0: not present, 1: online, 2: armed]
- * @param payload_board_status PAYLOAD board status [0: not present, 1: online, 2: armed]
- * @param motor_board_status MOTOR board status [0: not present, 1: online, 2: armed]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_gse_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, float loadcell_rocket, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t ignition_state, uint8_t tars_state, float battery_voltage, float current_consumption, uint8_t main_board_status, uint8_t payload_board_status, uint8_t motor_board_status)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GSE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, loadcell_rocket);
- _mav_put_float(buf, 12, loadcell_vessel);
- _mav_put_float(buf, 16, filling_pressure);
- _mav_put_float(buf, 20, vessel_pressure);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_float(buf, 28, current_consumption);
- _mav_put_uint8_t(buf, 32, arming_state);
- _mav_put_uint8_t(buf, 33, filling_valve_state);
- _mav_put_uint8_t(buf, 34, venting_valve_state);
- _mav_put_uint8_t(buf, 35, release_valve_state);
- _mav_put_uint8_t(buf, 36, main_valve_state);
- _mav_put_uint8_t(buf, 37, ignition_state);
- _mav_put_uint8_t(buf, 38, tars_state);
- _mav_put_uint8_t(buf, 39, main_board_status);
- _mav_put_uint8_t(buf, 40, payload_board_status);
- _mav_put_uint8_t(buf, 41, motor_board_status);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GSE_TM_LEN);
-#else
- mavlink_gse_tm_t packet;
- packet.timestamp = timestamp;
- packet.loadcell_rocket = loadcell_rocket;
- packet.loadcell_vessel = loadcell_vessel;
- packet.filling_pressure = filling_pressure;
- packet.vessel_pressure = vessel_pressure;
- packet.battery_voltage = battery_voltage;
- packet.current_consumption = current_consumption;
- packet.arming_state = arming_state;
- packet.filling_valve_state = filling_valve_state;
- packet.venting_valve_state = venting_valve_state;
- packet.release_valve_state = release_valve_state;
- packet.main_valve_state = main_valve_state;
- packet.ignition_state = ignition_state;
- packet.tars_state = tars_state;
- packet.main_board_status = main_board_status;
- packet.payload_board_status = payload_board_status;
- packet.motor_board_status = motor_board_status;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GSE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_GSE_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
-}
-
-/**
- * @brief Pack a gse_tm 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 in microseconds
- * @param loadcell_rocket [kg] Rocket weight
- * @param loadcell_vessel [kg] External tank weight
- * @param filling_pressure [Bar] Refueling line pressure
- * @param vessel_pressure [Bar] Vessel tank pressure
- * @param arming_state 1 If the rocket is armed
- * @param filling_valve_state 1 If the filling valve is open
- * @param venting_valve_state 1 If the venting valve is open
- * @param release_valve_state 1 If the release valve is open
- * @param main_valve_state 1 If the main valve is open
- * @param ignition_state 1 If the RIG is in ignition process
- * @param tars_state 1 If the TARS algorithm is running
- * @param battery_voltage Battery voltage
- * @param current_consumption RIG current
- * @param main_board_status MAIN board status [0: not present, 1: online, 2: armed]
- * @param payload_board_status PAYLOAD board status [0: not present, 1: online, 2: armed]
- * @param motor_board_status MOTOR board status [0: not present, 1: online, 2: armed]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_gse_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,float loadcell_rocket,float loadcell_vessel,float filling_pressure,float vessel_pressure,uint8_t arming_state,uint8_t filling_valve_state,uint8_t venting_valve_state,uint8_t release_valve_state,uint8_t main_valve_state,uint8_t ignition_state,uint8_t tars_state,float battery_voltage,float current_consumption,uint8_t main_board_status,uint8_t payload_board_status,uint8_t motor_board_status)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GSE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, loadcell_rocket);
- _mav_put_float(buf, 12, loadcell_vessel);
- _mav_put_float(buf, 16, filling_pressure);
- _mav_put_float(buf, 20, vessel_pressure);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_float(buf, 28, current_consumption);
- _mav_put_uint8_t(buf, 32, arming_state);
- _mav_put_uint8_t(buf, 33, filling_valve_state);
- _mav_put_uint8_t(buf, 34, venting_valve_state);
- _mav_put_uint8_t(buf, 35, release_valve_state);
- _mav_put_uint8_t(buf, 36, main_valve_state);
- _mav_put_uint8_t(buf, 37, ignition_state);
- _mav_put_uint8_t(buf, 38, tars_state);
- _mav_put_uint8_t(buf, 39, main_board_status);
- _mav_put_uint8_t(buf, 40, payload_board_status);
- _mav_put_uint8_t(buf, 41, motor_board_status);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GSE_TM_LEN);
-#else
- mavlink_gse_tm_t packet;
- packet.timestamp = timestamp;
- packet.loadcell_rocket = loadcell_rocket;
- packet.loadcell_vessel = loadcell_vessel;
- packet.filling_pressure = filling_pressure;
- packet.vessel_pressure = vessel_pressure;
- packet.battery_voltage = battery_voltage;
- packet.current_consumption = current_consumption;
- packet.arming_state = arming_state;
- packet.filling_valve_state = filling_valve_state;
- packet.venting_valve_state = venting_valve_state;
- packet.release_valve_state = release_valve_state;
- packet.main_valve_state = main_valve_state;
- packet.ignition_state = ignition_state;
- packet.tars_state = tars_state;
- packet.main_board_status = main_board_status;
- packet.payload_board_status = payload_board_status;
- packet.motor_board_status = motor_board_status;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GSE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_GSE_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
-}
-
-/**
- * @brief Encode a gse_tm 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 gse_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_gse_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gse_tm_t* gse_tm)
-{
- return mavlink_msg_gse_tm_pack(system_id, component_id, msg, gse_tm->timestamp, gse_tm->loadcell_rocket, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->ignition_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->main_board_status, gse_tm->payload_board_status, gse_tm->motor_board_status);
-}
-
-/**
- * @brief Encode a gse_tm 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 gse_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_gse_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gse_tm_t* gse_tm)
-{
- return mavlink_msg_gse_tm_pack_chan(system_id, component_id, chan, msg, gse_tm->timestamp, gse_tm->loadcell_rocket, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->ignition_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->main_board_status, gse_tm->payload_board_status, gse_tm->motor_board_status);
-}
-
-/**
- * @brief Send a gse_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp in microseconds
- * @param loadcell_rocket [kg] Rocket weight
- * @param loadcell_vessel [kg] External tank weight
- * @param filling_pressure [Bar] Refueling line pressure
- * @param vessel_pressure [Bar] Vessel tank pressure
- * @param arming_state 1 If the rocket is armed
- * @param filling_valve_state 1 If the filling valve is open
- * @param venting_valve_state 1 If the venting valve is open
- * @param release_valve_state 1 If the release valve is open
- * @param main_valve_state 1 If the main valve is open
- * @param ignition_state 1 If the RIG is in ignition process
- * @param tars_state 1 If the TARS algorithm is running
- * @param battery_voltage Battery voltage
- * @param current_consumption RIG current
- * @param main_board_status MAIN board status [0: not present, 1: online, 2: armed]
- * @param payload_board_status PAYLOAD board status [0: not present, 1: online, 2: armed]
- * @param motor_board_status MOTOR board status [0: not present, 1: online, 2: armed]
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_gse_tm_send(mavlink_channel_t chan, uint64_t timestamp, float loadcell_rocket, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t ignition_state, uint8_t tars_state, float battery_voltage, float current_consumption, uint8_t main_board_status, uint8_t payload_board_status, uint8_t motor_board_status)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GSE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, loadcell_rocket);
- _mav_put_float(buf, 12, loadcell_vessel);
- _mav_put_float(buf, 16, filling_pressure);
- _mav_put_float(buf, 20, vessel_pressure);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_float(buf, 28, current_consumption);
- _mav_put_uint8_t(buf, 32, arming_state);
- _mav_put_uint8_t(buf, 33, filling_valve_state);
- _mav_put_uint8_t(buf, 34, venting_valve_state);
- _mav_put_uint8_t(buf, 35, release_valve_state);
- _mav_put_uint8_t(buf, 36, main_valve_state);
- _mav_put_uint8_t(buf, 37, ignition_state);
- _mav_put_uint8_t(buf, 38, tars_state);
- _mav_put_uint8_t(buf, 39, main_board_status);
- _mav_put_uint8_t(buf, 40, payload_board_status);
- _mav_put_uint8_t(buf, 41, motor_board_status);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_TM, buf, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
-#else
- mavlink_gse_tm_t packet;
- packet.timestamp = timestamp;
- packet.loadcell_rocket = loadcell_rocket;
- packet.loadcell_vessel = loadcell_vessel;
- packet.filling_pressure = filling_pressure;
- packet.vessel_pressure = vessel_pressure;
- packet.battery_voltage = battery_voltage;
- packet.current_consumption = current_consumption;
- packet.arming_state = arming_state;
- packet.filling_valve_state = filling_valve_state;
- packet.venting_valve_state = venting_valve_state;
- packet.release_valve_state = release_valve_state;
- packet.main_valve_state = main_valve_state;
- packet.ignition_state = ignition_state;
- packet.tars_state = tars_state;
- packet.main_board_status = main_board_status;
- packet.payload_board_status = payload_board_status;
- packet.motor_board_status = motor_board_status;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_TM, (const char *)&packet, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a gse_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_gse_tm_send_struct(mavlink_channel_t chan, const mavlink_gse_tm_t* gse_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_gse_tm_send(chan, gse_tm->timestamp, gse_tm->loadcell_rocket, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->ignition_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption, gse_tm->main_board_status, gse_tm->payload_board_status, gse_tm->motor_board_status);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_TM, (const char *)gse_tm, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_GSE_TM_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_gse_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float loadcell_rocket, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t ignition_state, uint8_t tars_state, float battery_voltage, float current_consumption, uint8_t main_board_status, uint8_t payload_board_status, uint8_t motor_board_status)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, loadcell_rocket);
- _mav_put_float(buf, 12, loadcell_vessel);
- _mav_put_float(buf, 16, filling_pressure);
- _mav_put_float(buf, 20, vessel_pressure);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_float(buf, 28, current_consumption);
- _mav_put_uint8_t(buf, 32, arming_state);
- _mav_put_uint8_t(buf, 33, filling_valve_state);
- _mav_put_uint8_t(buf, 34, venting_valve_state);
- _mav_put_uint8_t(buf, 35, release_valve_state);
- _mav_put_uint8_t(buf, 36, main_valve_state);
- _mav_put_uint8_t(buf, 37, ignition_state);
- _mav_put_uint8_t(buf, 38, tars_state);
- _mav_put_uint8_t(buf, 39, main_board_status);
- _mav_put_uint8_t(buf, 40, payload_board_status);
- _mav_put_uint8_t(buf, 41, motor_board_status);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_TM, buf, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
-#else
- mavlink_gse_tm_t *packet = (mavlink_gse_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->loadcell_rocket = loadcell_rocket;
- packet->loadcell_vessel = loadcell_vessel;
- packet->filling_pressure = filling_pressure;
- packet->vessel_pressure = vessel_pressure;
- packet->battery_voltage = battery_voltage;
- packet->current_consumption = current_consumption;
- packet->arming_state = arming_state;
- packet->filling_valve_state = filling_valve_state;
- packet->venting_valve_state = venting_valve_state;
- packet->release_valve_state = release_valve_state;
- packet->main_valve_state = main_valve_state;
- packet->ignition_state = ignition_state;
- packet->tars_state = tars_state;
- packet->main_board_status = main_board_status;
- packet->payload_board_status = payload_board_status;
- packet->motor_board_status = motor_board_status;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_TM, (const char *)packet, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE GSE_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from gse_tm message
- *
- * @return [us] Timestamp in microseconds
- */
-static inline uint64_t mavlink_msg_gse_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field loadcell_rocket from gse_tm message
- *
- * @return [kg] Rocket weight
- */
-static inline float mavlink_msg_gse_tm_get_loadcell_rocket(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field loadcell_vessel from gse_tm message
- *
- * @return [kg] External tank weight
- */
-static inline float mavlink_msg_gse_tm_get_loadcell_vessel(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field filling_pressure from gse_tm message
- *
- * @return [Bar] Refueling line pressure
- */
-static inline float mavlink_msg_gse_tm_get_filling_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field vessel_pressure from gse_tm message
- *
- * @return [Bar] Vessel tank pressure
- */
-static inline float mavlink_msg_gse_tm_get_vessel_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field arming_state from gse_tm message
- *
- * @return 1 If the rocket is armed
- */
-static inline uint8_t mavlink_msg_gse_tm_get_arming_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 32);
-}
-
-/**
- * @brief Get field filling_valve_state from gse_tm message
- *
- * @return 1 If the filling valve is open
- */
-static inline uint8_t mavlink_msg_gse_tm_get_filling_valve_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 33);
-}
-
-/**
- * @brief Get field venting_valve_state from gse_tm message
- *
- * @return 1 If the venting valve is open
- */
-static inline uint8_t mavlink_msg_gse_tm_get_venting_valve_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 34);
-}
-
-/**
- * @brief Get field release_valve_state from gse_tm message
- *
- * @return 1 If the release valve is open
- */
-static inline uint8_t mavlink_msg_gse_tm_get_release_valve_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 35);
-}
-
-/**
- * @brief Get field main_valve_state from gse_tm message
- *
- * @return 1 If the main valve is open
- */
-static inline uint8_t mavlink_msg_gse_tm_get_main_valve_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 36);
-}
-
-/**
- * @brief Get field ignition_state from gse_tm message
- *
- * @return 1 If the RIG is in ignition process
- */
-static inline uint8_t mavlink_msg_gse_tm_get_ignition_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 37);
-}
-
-/**
- * @brief Get field tars_state from gse_tm message
- *
- * @return 1 If the TARS algorithm is running
- */
-static inline uint8_t mavlink_msg_gse_tm_get_tars_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 38);
-}
-
-/**
- * @brief Get field battery_voltage from gse_tm message
- *
- * @return Battery voltage
- */
-static inline float mavlink_msg_gse_tm_get_battery_voltage(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field current_consumption from gse_tm message
- *
- * @return RIG current
- */
-static inline float mavlink_msg_gse_tm_get_current_consumption(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field main_board_status from gse_tm message
- *
- * @return MAIN board status [0: not present, 1: online, 2: armed]
- */
-static inline uint8_t mavlink_msg_gse_tm_get_main_board_status(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 39);
-}
-
-/**
- * @brief Get field payload_board_status from gse_tm message
- *
- * @return PAYLOAD board status [0: not present, 1: online, 2: armed]
- */
-static inline uint8_t mavlink_msg_gse_tm_get_payload_board_status(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 40);
-}
-
-/**
- * @brief Get field motor_board_status from gse_tm message
- *
- * @return MOTOR board status [0: not present, 1: online, 2: armed]
- */
-static inline uint8_t mavlink_msg_gse_tm_get_motor_board_status(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 41);
-}
-
-/**
- * @brief Decode a gse_tm message into a struct
- *
- * @param msg The message to decode
- * @param gse_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_gse_tm_decode(const mavlink_message_t* msg, mavlink_gse_tm_t* gse_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- gse_tm->timestamp = mavlink_msg_gse_tm_get_timestamp(msg);
- gse_tm->loadcell_rocket = mavlink_msg_gse_tm_get_loadcell_rocket(msg);
- gse_tm->loadcell_vessel = mavlink_msg_gse_tm_get_loadcell_vessel(msg);
- gse_tm->filling_pressure = mavlink_msg_gse_tm_get_filling_pressure(msg);
- gse_tm->vessel_pressure = mavlink_msg_gse_tm_get_vessel_pressure(msg);
- gse_tm->battery_voltage = mavlink_msg_gse_tm_get_battery_voltage(msg);
- gse_tm->current_consumption = mavlink_msg_gse_tm_get_current_consumption(msg);
- gse_tm->arming_state = mavlink_msg_gse_tm_get_arming_state(msg);
- gse_tm->filling_valve_state = mavlink_msg_gse_tm_get_filling_valve_state(msg);
- gse_tm->venting_valve_state = mavlink_msg_gse_tm_get_venting_valve_state(msg);
- gse_tm->release_valve_state = mavlink_msg_gse_tm_get_release_valve_state(msg);
- gse_tm->main_valve_state = mavlink_msg_gse_tm_get_main_valve_state(msg);
- gse_tm->ignition_state = mavlink_msg_gse_tm_get_ignition_state(msg);
- gse_tm->tars_state = mavlink_msg_gse_tm_get_tars_state(msg);
- gse_tm->main_board_status = mavlink_msg_gse_tm_get_main_board_status(msg);
- gse_tm->payload_board_status = mavlink_msg_gse_tm_get_payload_board_status(msg);
- gse_tm->motor_board_status = mavlink_msg_gse_tm_get_motor_board_status(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_GSE_TM_LEN? msg->len : MAVLINK_MSG_ID_GSE_TM_LEN;
- memset(gse_tm, 0, MAVLINK_MSG_ID_GSE_TM_LEN);
- memcpy(gse_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_imu_tm.h b/mavlink_lib/lyra/mavlink_msg_imu_tm.h
deleted file mode 100644
index 23c4739ce795a498ca8a3df799443719c003547b..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_imu_tm.h
+++ /dev/null
@@ -1,455 +0,0 @@
-#pragma once
-// MESSAGE IMU_TM PACKING
-
-#define MAVLINK_MSG_ID_IMU_TM 103
-
-
-typedef struct __mavlink_imu_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float acc_x; /*< [m/s2] X axis acceleration*/
- float acc_y; /*< [m/s2] Y axis acceleration*/
- float acc_z; /*< [m/s2] Z axis acceleration*/
- float gyro_x; /*< [rad/s] X axis gyro*/
- float gyro_y; /*< [rad/s] Y axis gyro*/
- float gyro_z; /*< [rad/s] Z axis gyro*/
- float mag_x; /*< [uT] X axis compass*/
- float mag_y; /*< [uT] Y axis compass*/
- float mag_z; /*< [uT] Z axis compass*/
- char sensor_name[20]; /*< Sensor name*/
-} mavlink_imu_tm_t;
-
-#define MAVLINK_MSG_ID_IMU_TM_LEN 64
-#define MAVLINK_MSG_ID_IMU_TM_MIN_LEN 64
-#define MAVLINK_MSG_ID_103_LEN 64
-#define MAVLINK_MSG_ID_103_MIN_LEN 64
-
-#define MAVLINK_MSG_ID_IMU_TM_CRC 72
-#define MAVLINK_MSG_ID_103_CRC 72
-
-#define MAVLINK_MSG_IMU_TM_FIELD_SENSOR_NAME_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_IMU_TM { \
- 103, \
- "IMU_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_imu_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 44, offsetof(mavlink_imu_tm_t, sensor_name) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_imu_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_imu_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_imu_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_imu_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_imu_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_imu_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_imu_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_imu_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_imu_tm_t, mag_z) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_IMU_TM { \
- "IMU_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_imu_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 44, offsetof(mavlink_imu_tm_t, sensor_name) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_imu_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_imu_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_imu_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_imu_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_imu_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_imu_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_imu_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_imu_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_imu_tm_t, mag_z) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a imu_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param acc_x [m/s2] X axis acceleration
- * @param acc_y [m/s2] Y axis acceleration
- * @param acc_z [m/s2] Z axis acceleration
- * @param gyro_x [rad/s] X axis gyro
- * @param gyro_y [rad/s] Y axis gyro
- * @param gyro_z [rad/s] Z axis gyro
- * @param mag_x [uT] X axis compass
- * @param mag_y [uT] Y axis compass
- * @param mag_z [uT] Z axis compass
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_imu_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_name, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_IMU_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, mag_x);
- _mav_put_float(buf, 36, mag_y);
- _mav_put_float(buf, 40, mag_z);
- _mav_put_char_array(buf, 44, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IMU_TM_LEN);
-#else
- mavlink_imu_tm_t packet;
- packet.timestamp = timestamp;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IMU_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_IMU_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-}
-
-/**
- * @brief Pack a imu_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param acc_x [m/s2] X axis acceleration
- * @param acc_y [m/s2] Y axis acceleration
- * @param acc_z [m/s2] Z axis acceleration
- * @param gyro_x [rad/s] X axis gyro
- * @param gyro_y [rad/s] Y axis gyro
- * @param gyro_z [rad/s] Z axis gyro
- * @param mag_x [uT] X axis compass
- * @param mag_y [uT] Y axis compass
- * @param mag_z [uT] Z axis compass
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_imu_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_name,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_IMU_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, mag_x);
- _mav_put_float(buf, 36, mag_y);
- _mav_put_float(buf, 40, mag_z);
- _mav_put_char_array(buf, 44, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IMU_TM_LEN);
-#else
- mavlink_imu_tm_t packet;
- packet.timestamp = timestamp;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IMU_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_IMU_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-}
-
-/**
- * @brief Encode a imu_tm 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 imu_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_imu_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_imu_tm_t* imu_tm)
-{
- return mavlink_msg_imu_tm_pack(system_id, component_id, msg, imu_tm->timestamp, imu_tm->sensor_name, imu_tm->acc_x, imu_tm->acc_y, imu_tm->acc_z, imu_tm->gyro_x, imu_tm->gyro_y, imu_tm->gyro_z, imu_tm->mag_x, imu_tm->mag_y, imu_tm->mag_z);
-}
-
-/**
- * @brief Encode a imu_tm 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 imu_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_imu_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_imu_tm_t* imu_tm)
-{
- return mavlink_msg_imu_tm_pack_chan(system_id, component_id, chan, msg, imu_tm->timestamp, imu_tm->sensor_name, imu_tm->acc_x, imu_tm->acc_y, imu_tm->acc_z, imu_tm->gyro_x, imu_tm->gyro_y, imu_tm->gyro_z, imu_tm->mag_x, imu_tm->mag_y, imu_tm->mag_z);
-}
-
-/**
- * @brief Send a imu_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_name Sensor name
- * @param acc_x [m/s2] X axis acceleration
- * @param acc_y [m/s2] Y axis acceleration
- * @param acc_z [m/s2] Z axis acceleration
- * @param gyro_x [rad/s] X axis gyro
- * @param gyro_y [rad/s] Y axis gyro
- * @param gyro_z [rad/s] Z axis gyro
- * @param mag_x [uT] X axis compass
- * @param mag_y [uT] Y axis compass
- * @param mag_z [uT] Z axis compass
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_imu_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_IMU_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, mag_x);
- _mav_put_float(buf, 36, mag_y);
- _mav_put_float(buf, 40, mag_z);
- _mav_put_char_array(buf, 44, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMU_TM, buf, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-#else
- mavlink_imu_tm_t packet;
- packet.timestamp = timestamp;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMU_TM, (const char *)&packet, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a imu_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_imu_tm_send_struct(mavlink_channel_t chan, const mavlink_imu_tm_t* imu_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_imu_tm_send(chan, imu_tm->timestamp, imu_tm->sensor_name, imu_tm->acc_x, imu_tm->acc_y, imu_tm->acc_z, imu_tm->gyro_x, imu_tm->gyro_y, imu_tm->gyro_z, imu_tm->mag_x, imu_tm->mag_y, imu_tm->mag_z);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMU_TM, (const char *)imu_tm, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_IMU_TM_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_imu_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, mag_x);
- _mav_put_float(buf, 36, mag_y);
- _mav_put_float(buf, 40, mag_z);
- _mav_put_char_array(buf, 44, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMU_TM, buf, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-#else
- mavlink_imu_tm_t *packet = (mavlink_imu_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->acc_x = acc_x;
- packet->acc_y = acc_y;
- packet->acc_z = acc_z;
- packet->gyro_x = gyro_x;
- packet->gyro_y = gyro_y;
- packet->gyro_z = gyro_z;
- packet->mag_x = mag_x;
- packet->mag_y = mag_y;
- packet->mag_z = mag_z;
- mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMU_TM, (const char *)packet, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE IMU_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from imu_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_imu_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_name from imu_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_imu_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
-{
- return _MAV_RETURN_char_array(msg, sensor_name, 20, 44);
-}
-
-/**
- * @brief Get field acc_x from imu_tm message
- *
- * @return [m/s2] X axis acceleration
- */
-static inline float mavlink_msg_imu_tm_get_acc_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field acc_y from imu_tm message
- *
- * @return [m/s2] Y axis acceleration
- */
-static inline float mavlink_msg_imu_tm_get_acc_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field acc_z from imu_tm message
- *
- * @return [m/s2] Z axis acceleration
- */
-static inline float mavlink_msg_imu_tm_get_acc_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field gyro_x from imu_tm message
- *
- * @return [rad/s] X axis gyro
- */
-static inline float mavlink_msg_imu_tm_get_gyro_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field gyro_y from imu_tm message
- *
- * @return [rad/s] Y axis gyro
- */
-static inline float mavlink_msg_imu_tm_get_gyro_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field gyro_z from imu_tm message
- *
- * @return [rad/s] Z axis gyro
- */
-static inline float mavlink_msg_imu_tm_get_gyro_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field mag_x from imu_tm message
- *
- * @return [uT] X axis compass
- */
-static inline float mavlink_msg_imu_tm_get_mag_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field mag_y from imu_tm message
- *
- * @return [uT] Y axis compass
- */
-static inline float mavlink_msg_imu_tm_get_mag_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field mag_z from imu_tm message
- *
- * @return [uT] Z axis compass
- */
-static inline float mavlink_msg_imu_tm_get_mag_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Decode a imu_tm message into a struct
- *
- * @param msg The message to decode
- * @param imu_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_imu_tm_decode(const mavlink_message_t* msg, mavlink_imu_tm_t* imu_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- imu_tm->timestamp = mavlink_msg_imu_tm_get_timestamp(msg);
- imu_tm->acc_x = mavlink_msg_imu_tm_get_acc_x(msg);
- imu_tm->acc_y = mavlink_msg_imu_tm_get_acc_y(msg);
- imu_tm->acc_z = mavlink_msg_imu_tm_get_acc_z(msg);
- imu_tm->gyro_x = mavlink_msg_imu_tm_get_gyro_x(msg);
- imu_tm->gyro_y = mavlink_msg_imu_tm_get_gyro_y(msg);
- imu_tm->gyro_z = mavlink_msg_imu_tm_get_gyro_z(msg);
- imu_tm->mag_x = mavlink_msg_imu_tm_get_mag_x(msg);
- imu_tm->mag_y = mavlink_msg_imu_tm_get_mag_y(msg);
- imu_tm->mag_z = mavlink_msg_imu_tm_get_mag_z(msg);
- mavlink_msg_imu_tm_get_sensor_name(msg, imu_tm->sensor_name);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_IMU_TM_LEN? msg->len : MAVLINK_MSG_ID_IMU_TM_LEN;
- memset(imu_tm, 0, MAVLINK_MSG_ID_IMU_TM_LEN);
- memcpy(imu_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_load_tm.h b/mavlink_lib/lyra/mavlink_msg_load_tm.h
deleted file mode 100644
index 27c578f3b208b1174ea5499a1e31a0497c925d07..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_load_tm.h
+++ /dev/null
@@ -1,255 +0,0 @@
-#pragma once
-// MESSAGE LOAD_TM PACKING
-
-#define MAVLINK_MSG_ID_LOAD_TM 109
-
-
-typedef struct __mavlink_load_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float load; /*< [kg] Load force*/
- char sensor_name[20]; /*< Sensor name*/
-} mavlink_load_tm_t;
-
-#define MAVLINK_MSG_ID_LOAD_TM_LEN 32
-#define MAVLINK_MSG_ID_LOAD_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_109_LEN 32
-#define MAVLINK_MSG_ID_109_MIN_LEN 32
-
-#define MAVLINK_MSG_ID_LOAD_TM_CRC 148
-#define MAVLINK_MSG_ID_109_CRC 148
-
-#define MAVLINK_MSG_LOAD_TM_FIELD_SENSOR_NAME_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_LOAD_TM { \
- 109, \
- "LOAD_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_load_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_load_tm_t, sensor_name) }, \
- { "load", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_load_tm_t, load) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_LOAD_TM { \
- "LOAD_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_load_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_load_tm_t, sensor_name) }, \
- { "load", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_load_tm_t, load) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a load_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param load [kg] Load force
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_load_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_name, float load)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOAD_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, load);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOAD_TM_LEN);
-#else
- mavlink_load_tm_t packet;
- packet.timestamp = timestamp;
- packet.load = load;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOAD_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LOAD_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-}
-
-/**
- * @brief Pack a load_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param load [kg] Load force
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_load_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_name,float load)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOAD_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, load);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOAD_TM_LEN);
-#else
- mavlink_load_tm_t packet;
- packet.timestamp = timestamp;
- packet.load = load;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOAD_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LOAD_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-}
-
-/**
- * @brief Encode a load_tm 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 load_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_load_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_load_tm_t* load_tm)
-{
- return mavlink_msg_load_tm_pack(system_id, component_id, msg, load_tm->timestamp, load_tm->sensor_name, load_tm->load);
-}
-
-/**
- * @brief Encode a load_tm 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 load_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_load_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_load_tm_t* load_tm)
-{
- return mavlink_msg_load_tm_pack_chan(system_id, component_id, chan, msg, load_tm->timestamp, load_tm->sensor_name, load_tm->load);
-}
-
-/**
- * @brief Send a load_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_name Sensor name
- * @param load [kg] Load force
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_load_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float load)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOAD_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, load);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOAD_TM, buf, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-#else
- mavlink_load_tm_t packet;
- packet.timestamp = timestamp;
- packet.load = load;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOAD_TM, (const char *)&packet, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a load_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_load_tm_send_struct(mavlink_channel_t chan, const mavlink_load_tm_t* load_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_load_tm_send(chan, load_tm->timestamp, load_tm->sensor_name, load_tm->load);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOAD_TM, (const char *)load_tm, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_LOAD_TM_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_load_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float load)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, load);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOAD_TM, buf, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-#else
- mavlink_load_tm_t *packet = (mavlink_load_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->load = load;
- mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOAD_TM, (const char *)packet, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE LOAD_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from load_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_load_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_name from load_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_load_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
-{
- return _MAV_RETURN_char_array(msg, sensor_name, 20, 12);
-}
-
-/**
- * @brief Get field load from load_tm message
- *
- * @return [kg] Load force
- */
-static inline float mavlink_msg_load_tm_get_load(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Decode a load_tm message into a struct
- *
- * @param msg The message to decode
- * @param load_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_load_tm_decode(const mavlink_message_t* msg, mavlink_load_tm_t* load_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- load_tm->timestamp = mavlink_msg_load_tm_get_timestamp(msg);
- load_tm->load = mavlink_msg_load_tm_get_load(msg);
- mavlink_msg_load_tm_get_sensor_name(msg, load_tm->sensor_name);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_LOAD_TM_LEN? msg->len : MAVLINK_MSG_ID_LOAD_TM_LEN;
- memset(load_tm, 0, MAVLINK_MSG_ID_LOAD_TM_LEN);
- memcpy(load_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_logger_tm.h b/mavlink_lib/lyra/mavlink_msg_logger_tm.h
deleted file mode 100644
index ac52b5a9d5faa26bb0047de6f0c67293ff6fe4f5..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_logger_tm.h
+++ /dev/null
@@ -1,463 +0,0 @@
-#pragma once
-// MESSAGE LOGGER_TM PACKING
-
-#define MAVLINK_MSG_ID_LOGGER_TM 202
-
-
-typedef struct __mavlink_logger_tm_t {
- uint64_t timestamp; /*< [us] Timestamp*/
- int32_t too_large_samples; /*< Number of dropped samples because too large*/
- int32_t dropped_samples; /*< Number of dropped samples due to fifo full*/
- int32_t queued_samples; /*< Number of samples written to buffer*/
- int32_t buffers_filled; /*< Number of buffers filled*/
- int32_t buffers_written; /*< Number of buffers written to disk*/
- int32_t writes_failed; /*< Number of fwrite() that failed*/
- int32_t last_write_error; /*< Error of the last fwrite() that failed*/
- int32_t average_write_time; /*< Average time to perform an fwrite() of a buffer*/
- int32_t max_write_time; /*< Max time to perform an fwrite() of a buffer*/
- int16_t log_number; /*< Currently active log file, -1 if the logger is inactive*/
-} mavlink_logger_tm_t;
-
-#define MAVLINK_MSG_ID_LOGGER_TM_LEN 46
-#define MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN 46
-#define MAVLINK_MSG_ID_202_LEN 46
-#define MAVLINK_MSG_ID_202_MIN_LEN 46
-
-#define MAVLINK_MSG_ID_LOGGER_TM_CRC 142
-#define MAVLINK_MSG_ID_202_CRC 142
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_LOGGER_TM { \
- 202, \
- "LOGGER_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_logger_tm_t, timestamp) }, \
- { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_logger_tm_t, log_number) }, \
- { "too_large_samples", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_logger_tm_t, too_large_samples) }, \
- { "dropped_samples", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_logger_tm_t, dropped_samples) }, \
- { "queued_samples", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_logger_tm_t, queued_samples) }, \
- { "buffers_filled", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_logger_tm_t, buffers_filled) }, \
- { "buffers_written", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_logger_tm_t, buffers_written) }, \
- { "writes_failed", NULL, MAVLINK_TYPE_INT32_T, 0, 28, offsetof(mavlink_logger_tm_t, writes_failed) }, \
- { "last_write_error", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_logger_tm_t, last_write_error) }, \
- { "average_write_time", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_logger_tm_t, average_write_time) }, \
- { "max_write_time", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_logger_tm_t, max_write_time) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_LOGGER_TM { \
- "LOGGER_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_logger_tm_t, timestamp) }, \
- { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_logger_tm_t, log_number) }, \
- { "too_large_samples", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_logger_tm_t, too_large_samples) }, \
- { "dropped_samples", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_logger_tm_t, dropped_samples) }, \
- { "queued_samples", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_logger_tm_t, queued_samples) }, \
- { "buffers_filled", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_logger_tm_t, buffers_filled) }, \
- { "buffers_written", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_logger_tm_t, buffers_written) }, \
- { "writes_failed", NULL, MAVLINK_TYPE_INT32_T, 0, 28, offsetof(mavlink_logger_tm_t, writes_failed) }, \
- { "last_write_error", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_logger_tm_t, last_write_error) }, \
- { "average_write_time", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_logger_tm_t, average_write_time) }, \
- { "max_write_time", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_logger_tm_t, max_write_time) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a logger_tm 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
- * @param log_number Currently active log file, -1 if the logger is inactive
- * @param too_large_samples Number of dropped samples because too large
- * @param dropped_samples Number of dropped samples due to fifo full
- * @param queued_samples Number of samples written to buffer
- * @param buffers_filled Number of buffers filled
- * @param buffers_written Number of buffers written to disk
- * @param writes_failed Number of fwrite() that failed
- * @param last_write_error Error of the last fwrite() that failed
- * @param average_write_time Average time to perform an fwrite() of a buffer
- * @param max_write_time Max time to perform an fwrite() of a buffer
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_logger_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, int16_t log_number, int32_t too_large_samples, int32_t dropped_samples, int32_t queued_samples, int32_t buffers_filled, int32_t buffers_written, int32_t writes_failed, int32_t last_write_error, int32_t average_write_time, int32_t max_write_time)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOGGER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 8, too_large_samples);
- _mav_put_int32_t(buf, 12, dropped_samples);
- _mav_put_int32_t(buf, 16, queued_samples);
- _mav_put_int32_t(buf, 20, buffers_filled);
- _mav_put_int32_t(buf, 24, buffers_written);
- _mav_put_int32_t(buf, 28, writes_failed);
- _mav_put_int32_t(buf, 32, last_write_error);
- _mav_put_int32_t(buf, 36, average_write_time);
- _mav_put_int32_t(buf, 40, max_write_time);
- _mav_put_int16_t(buf, 44, log_number);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGER_TM_LEN);
-#else
- mavlink_logger_tm_t packet;
- packet.timestamp = timestamp;
- packet.too_large_samples = too_large_samples;
- packet.dropped_samples = dropped_samples;
- packet.queued_samples = queued_samples;
- packet.buffers_filled = buffers_filled;
- packet.buffers_written = buffers_written;
- packet.writes_failed = writes_failed;
- packet.last_write_error = last_write_error;
- packet.average_write_time = average_write_time;
- packet.max_write_time = max_write_time;
- packet.log_number = log_number;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGER_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LOGGER_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-}
-
-/**
- * @brief Pack a logger_tm 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
- * @param log_number Currently active log file, -1 if the logger is inactive
- * @param too_large_samples Number of dropped samples because too large
- * @param dropped_samples Number of dropped samples due to fifo full
- * @param queued_samples Number of samples written to buffer
- * @param buffers_filled Number of buffers filled
- * @param buffers_written Number of buffers written to disk
- * @param writes_failed Number of fwrite() that failed
- * @param last_write_error Error of the last fwrite() that failed
- * @param average_write_time Average time to perform an fwrite() of a buffer
- * @param max_write_time Max time to perform an fwrite() of a buffer
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_logger_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,int16_t log_number,int32_t too_large_samples,int32_t dropped_samples,int32_t queued_samples,int32_t buffers_filled,int32_t buffers_written,int32_t writes_failed,int32_t last_write_error,int32_t average_write_time,int32_t max_write_time)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOGGER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 8, too_large_samples);
- _mav_put_int32_t(buf, 12, dropped_samples);
- _mav_put_int32_t(buf, 16, queued_samples);
- _mav_put_int32_t(buf, 20, buffers_filled);
- _mav_put_int32_t(buf, 24, buffers_written);
- _mav_put_int32_t(buf, 28, writes_failed);
- _mav_put_int32_t(buf, 32, last_write_error);
- _mav_put_int32_t(buf, 36, average_write_time);
- _mav_put_int32_t(buf, 40, max_write_time);
- _mav_put_int16_t(buf, 44, log_number);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGER_TM_LEN);
-#else
- mavlink_logger_tm_t packet;
- packet.timestamp = timestamp;
- packet.too_large_samples = too_large_samples;
- packet.dropped_samples = dropped_samples;
- packet.queued_samples = queued_samples;
- packet.buffers_filled = buffers_filled;
- packet.buffers_written = buffers_written;
- packet.writes_failed = writes_failed;
- packet.last_write_error = last_write_error;
- packet.average_write_time = average_write_time;
- packet.max_write_time = max_write_time;
- packet.log_number = log_number;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGER_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LOGGER_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-}
-
-/**
- * @brief Encode a logger_tm 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 logger_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_logger_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_logger_tm_t* logger_tm)
-{
- return mavlink_msg_logger_tm_pack(system_id, component_id, msg, logger_tm->timestamp, logger_tm->log_number, logger_tm->too_large_samples, logger_tm->dropped_samples, logger_tm->queued_samples, logger_tm->buffers_filled, logger_tm->buffers_written, logger_tm->writes_failed, logger_tm->last_write_error, logger_tm->average_write_time, logger_tm->max_write_time);
-}
-
-/**
- * @brief Encode a logger_tm 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 logger_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_logger_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_logger_tm_t* logger_tm)
-{
- return mavlink_msg_logger_tm_pack_chan(system_id, component_id, chan, msg, logger_tm->timestamp, logger_tm->log_number, logger_tm->too_large_samples, logger_tm->dropped_samples, logger_tm->queued_samples, logger_tm->buffers_filled, logger_tm->buffers_written, logger_tm->writes_failed, logger_tm->last_write_error, logger_tm->average_write_time, logger_tm->max_write_time);
-}
-
-/**
- * @brief Send a logger_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp
- * @param log_number Currently active log file, -1 if the logger is inactive
- * @param too_large_samples Number of dropped samples because too large
- * @param dropped_samples Number of dropped samples due to fifo full
- * @param queued_samples Number of samples written to buffer
- * @param buffers_filled Number of buffers filled
- * @param buffers_written Number of buffers written to disk
- * @param writes_failed Number of fwrite() that failed
- * @param last_write_error Error of the last fwrite() that failed
- * @param average_write_time Average time to perform an fwrite() of a buffer
- * @param max_write_time Max time to perform an fwrite() of a buffer
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_logger_tm_send(mavlink_channel_t chan, uint64_t timestamp, int16_t log_number, int32_t too_large_samples, int32_t dropped_samples, int32_t queued_samples, int32_t buffers_filled, int32_t buffers_written, int32_t writes_failed, int32_t last_write_error, int32_t average_write_time, int32_t max_write_time)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOGGER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 8, too_large_samples);
- _mav_put_int32_t(buf, 12, dropped_samples);
- _mav_put_int32_t(buf, 16, queued_samples);
- _mav_put_int32_t(buf, 20, buffers_filled);
- _mav_put_int32_t(buf, 24, buffers_written);
- _mav_put_int32_t(buf, 28, writes_failed);
- _mav_put_int32_t(buf, 32, last_write_error);
- _mav_put_int32_t(buf, 36, average_write_time);
- _mav_put_int32_t(buf, 40, max_write_time);
- _mav_put_int16_t(buf, 44, log_number);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, buf, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#else
- mavlink_logger_tm_t packet;
- packet.timestamp = timestamp;
- packet.too_large_samples = too_large_samples;
- packet.dropped_samples = dropped_samples;
- packet.queued_samples = queued_samples;
- packet.buffers_filled = buffers_filled;
- packet.buffers_written = buffers_written;
- packet.writes_failed = writes_failed;
- packet.last_write_error = last_write_error;
- packet.average_write_time = average_write_time;
- packet.max_write_time = max_write_time;
- packet.log_number = log_number;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, (const char *)&packet, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a logger_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_logger_tm_send_struct(mavlink_channel_t chan, const mavlink_logger_tm_t* logger_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_logger_tm_send(chan, logger_tm->timestamp, logger_tm->log_number, logger_tm->too_large_samples, logger_tm->dropped_samples, logger_tm->queued_samples, logger_tm->buffers_filled, logger_tm->buffers_written, logger_tm->writes_failed, logger_tm->last_write_error, logger_tm->average_write_time, logger_tm->max_write_time);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, (const char *)logger_tm, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_LOGGER_TM_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_logger_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, int16_t log_number, int32_t too_large_samples, int32_t dropped_samples, int32_t queued_samples, int32_t buffers_filled, int32_t buffers_written, int32_t writes_failed, int32_t last_write_error, int32_t average_write_time, int32_t max_write_time)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 8, too_large_samples);
- _mav_put_int32_t(buf, 12, dropped_samples);
- _mav_put_int32_t(buf, 16, queued_samples);
- _mav_put_int32_t(buf, 20, buffers_filled);
- _mav_put_int32_t(buf, 24, buffers_written);
- _mav_put_int32_t(buf, 28, writes_failed);
- _mav_put_int32_t(buf, 32, last_write_error);
- _mav_put_int32_t(buf, 36, average_write_time);
- _mav_put_int32_t(buf, 40, max_write_time);
- _mav_put_int16_t(buf, 44, log_number);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, buf, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#else
- mavlink_logger_tm_t *packet = (mavlink_logger_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->too_large_samples = too_large_samples;
- packet->dropped_samples = dropped_samples;
- packet->queued_samples = queued_samples;
- packet->buffers_filled = buffers_filled;
- packet->buffers_written = buffers_written;
- packet->writes_failed = writes_failed;
- packet->last_write_error = last_write_error;
- packet->average_write_time = average_write_time;
- packet->max_write_time = max_write_time;
- packet->log_number = log_number;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, (const char *)packet, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE LOGGER_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from logger_tm message
- *
- * @return [us] Timestamp
- */
-static inline uint64_t mavlink_msg_logger_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field log_number from logger_tm message
- *
- * @return Currently active log file, -1 if the logger is inactive
- */
-static inline int16_t mavlink_msg_logger_tm_get_log_number(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int16_t(msg, 44);
-}
-
-/**
- * @brief Get field too_large_samples from logger_tm message
- *
- * @return Number of dropped samples because too large
- */
-static inline int32_t mavlink_msg_logger_tm_get_too_large_samples(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 8);
-}
-
-/**
- * @brief Get field dropped_samples from logger_tm message
- *
- * @return Number of dropped samples due to fifo full
- */
-static inline int32_t mavlink_msg_logger_tm_get_dropped_samples(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 12);
-}
-
-/**
- * @brief Get field queued_samples from logger_tm message
- *
- * @return Number of samples written to buffer
- */
-static inline int32_t mavlink_msg_logger_tm_get_queued_samples(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 16);
-}
-
-/**
- * @brief Get field buffers_filled from logger_tm message
- *
- * @return Number of buffers filled
- */
-static inline int32_t mavlink_msg_logger_tm_get_buffers_filled(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 20);
-}
-
-/**
- * @brief Get field buffers_written from logger_tm message
- *
- * @return Number of buffers written to disk
- */
-static inline int32_t mavlink_msg_logger_tm_get_buffers_written(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 24);
-}
-
-/**
- * @brief Get field writes_failed from logger_tm message
- *
- * @return Number of fwrite() that failed
- */
-static inline int32_t mavlink_msg_logger_tm_get_writes_failed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 28);
-}
-
-/**
- * @brief Get field last_write_error from logger_tm message
- *
- * @return Error of the last fwrite() that failed
- */
-static inline int32_t mavlink_msg_logger_tm_get_last_write_error(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 32);
-}
-
-/**
- * @brief Get field average_write_time from logger_tm message
- *
- * @return Average time to perform an fwrite() of a buffer
- */
-static inline int32_t mavlink_msg_logger_tm_get_average_write_time(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 36);
-}
-
-/**
- * @brief Get field max_write_time from logger_tm message
- *
- * @return Max time to perform an fwrite() of a buffer
- */
-static inline int32_t mavlink_msg_logger_tm_get_max_write_time(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 40);
-}
-
-/**
- * @brief Decode a logger_tm message into a struct
- *
- * @param msg The message to decode
- * @param logger_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_logger_tm_decode(const mavlink_message_t* msg, mavlink_logger_tm_t* logger_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- logger_tm->timestamp = mavlink_msg_logger_tm_get_timestamp(msg);
- logger_tm->too_large_samples = mavlink_msg_logger_tm_get_too_large_samples(msg);
- logger_tm->dropped_samples = mavlink_msg_logger_tm_get_dropped_samples(msg);
- logger_tm->queued_samples = mavlink_msg_logger_tm_get_queued_samples(msg);
- logger_tm->buffers_filled = mavlink_msg_logger_tm_get_buffers_filled(msg);
- logger_tm->buffers_written = mavlink_msg_logger_tm_get_buffers_written(msg);
- logger_tm->writes_failed = mavlink_msg_logger_tm_get_writes_failed(msg);
- logger_tm->last_write_error = mavlink_msg_logger_tm_get_last_write_error(msg);
- logger_tm->average_write_time = mavlink_msg_logger_tm_get_average_write_time(msg);
- logger_tm->max_write_time = mavlink_msg_logger_tm_get_max_write_time(msg);
- logger_tm->log_number = mavlink_msg_logger_tm_get_log_number(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_LOGGER_TM_LEN? msg->len : MAVLINK_MSG_ID_LOGGER_TM_LEN;
- memset(logger_tm, 0, MAVLINK_MSG_ID_LOGGER_TM_LEN);
- memcpy(logger_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_mavlink_stats_tm.h b/mavlink_lib/lyra/mavlink_msg_mavlink_stats_tm.h
deleted file mode 100644
index ba89b5f0761bcadff4201e229880cd30f7b90358..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_mavlink_stats_tm.h
+++ /dev/null
@@ -1,513 +0,0 @@
-#pragma once
-// MESSAGE MAVLINK_STATS_TM PACKING
-
-#define MAVLINK_MSG_ID_MAVLINK_STATS_TM 203
-
-
-typedef struct __mavlink_mavlink_stats_tm_t {
- uint64_t timestamp; /*< [us] When was this logged */
- uint32_t parse_state; /*< Parsing state machine*/
- uint16_t n_send_queue; /*< Current len of the occupied portion of the queue*/
- uint16_t max_send_queue; /*< Max occupied len of the queue */
- uint16_t n_send_errors; /*< Number of packet not sent correctly by the TMTC*/
- uint16_t packet_rx_success_count; /*< Received packets*/
- uint16_t packet_rx_drop_count; /*< Number of packet drops */
- uint8_t msg_received; /*< Number of received messages*/
- uint8_t buffer_overrun; /*< Number of buffer overruns*/
- uint8_t parse_error; /*< Number of parse errors*/
- 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 */
-} mavlink_mavlink_stats_tm_t;
-
-#define MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN 28
-#define MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN 28
-#define MAVLINK_MSG_ID_203_LEN 28
-#define MAVLINK_MSG_ID_203_MIN_LEN 28
-
-#define MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC 108
-#define MAVLINK_MSG_ID_203_CRC 108
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM { \
- 203, \
- "MAVLINK_STATS_TM", \
- 13, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_mavlink_stats_tm_t, timestamp) }, \
- { "n_send_queue", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_mavlink_stats_tm_t, n_send_queue) }, \
- { "max_send_queue", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_mavlink_stats_tm_t, max_send_queue) }, \
- { "n_send_errors", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_mavlink_stats_tm_t, n_send_errors) }, \
- { "msg_received", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_mavlink_stats_tm_t, msg_received) }, \
- { "buffer_overrun", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_mavlink_stats_tm_t, buffer_overrun) }, \
- { "parse_error", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_mavlink_stats_tm_t, parse_error) }, \
- { "parse_state", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_mavlink_stats_tm_t, parse_state) }, \
- { "packet_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_mavlink_stats_tm_t, packet_idx) }, \
- { "current_rx_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_mavlink_stats_tm_t, current_rx_seq) }, \
- { "current_tx_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_mavlink_stats_tm_t, current_tx_seq) }, \
- { "packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_mavlink_stats_tm_t, packet_rx_success_count) }, \
- { "packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_mavlink_stats_tm_t, packet_rx_drop_count) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM { \
- "MAVLINK_STATS_TM", \
- 13, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_mavlink_stats_tm_t, timestamp) }, \
- { "n_send_queue", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_mavlink_stats_tm_t, n_send_queue) }, \
- { "max_send_queue", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_mavlink_stats_tm_t, max_send_queue) }, \
- { "n_send_errors", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_mavlink_stats_tm_t, n_send_errors) }, \
- { "msg_received", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_mavlink_stats_tm_t, msg_received) }, \
- { "buffer_overrun", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_mavlink_stats_tm_t, buffer_overrun) }, \
- { "parse_error", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_mavlink_stats_tm_t, parse_error) }, \
- { "parse_state", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_mavlink_stats_tm_t, parse_state) }, \
- { "packet_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_mavlink_stats_tm_t, packet_idx) }, \
- { "current_rx_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_mavlink_stats_tm_t, current_rx_seq) }, \
- { "current_tx_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_mavlink_stats_tm_t, current_tx_seq) }, \
- { "packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_mavlink_stats_tm_t, packet_rx_success_count) }, \
- { "packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_mavlink_stats_tm_t, packet_rx_drop_count) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a mavlink_stats_tm 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] When was this logged
- * @param n_send_queue Current len of the occupied portion of the queue
- * @param max_send_queue Max occupied len of the queue
- * @param n_send_errors Number of packet not sent correctly by the TMTC
- * @param msg_received Number of received messages
- * @param buffer_overrun Number of buffer overruns
- * @param parse_error Number of parse errors
- * @param parse_state Parsing state machine
- * @param packet_idx Index in current packet
- * @param current_rx_seq Sequence number of last packet received
- * @param current_tx_seq Sequence number of last packet sent
- * @param packet_rx_success_count Received packets
- * @param packet_rx_drop_count Number of packet drops
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint16_t n_send_queue, uint16_t max_send_queue, uint16_t n_send_errors, uint8_t msg_received, uint8_t buffer_overrun, uint8_t parse_error, uint32_t parse_state, uint8_t packet_idx, uint8_t current_rx_seq, uint8_t current_tx_seq, uint16_t packet_rx_success_count, uint16_t packet_rx_drop_count)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint32_t(buf, 8, parse_state);
- _mav_put_uint16_t(buf, 12, n_send_queue);
- _mav_put_uint16_t(buf, 14, max_send_queue);
- _mav_put_uint16_t(buf, 16, n_send_errors);
- _mav_put_uint16_t(buf, 18, packet_rx_success_count);
- _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
- _mav_put_uint8_t(buf, 22, msg_received);
- _mav_put_uint8_t(buf, 23, buffer_overrun);
- _mav_put_uint8_t(buf, 24, parse_error);
- _mav_put_uint8_t(buf, 25, packet_idx);
- _mav_put_uint8_t(buf, 26, current_rx_seq);
- _mav_put_uint8_t(buf, 27, current_tx_seq);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN);
-#else
- mavlink_mavlink_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.parse_state = parse_state;
- packet.n_send_queue = n_send_queue;
- packet.max_send_queue = max_send_queue;
- packet.n_send_errors = n_send_errors;
- packet.packet_rx_success_count = packet_rx_success_count;
- packet.packet_rx_drop_count = packet_rx_drop_count;
- packet.msg_received = msg_received;
- packet.buffer_overrun = buffer_overrun;
- packet.parse_error = parse_error;
- packet.packet_idx = packet_idx;
- packet.current_rx_seq = current_rx_seq;
- packet.current_tx_seq = current_tx_seq;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_MAVLINK_STATS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-}
-
-/**
- * @brief Pack a mavlink_stats_tm 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] When was this logged
- * @param n_send_queue Current len of the occupied portion of the queue
- * @param max_send_queue Max occupied len of the queue
- * @param n_send_errors Number of packet not sent correctly by the TMTC
- * @param msg_received Number of received messages
- * @param buffer_overrun Number of buffer overruns
- * @param parse_error Number of parse errors
- * @param parse_state Parsing state machine
- * @param packet_idx Index in current packet
- * @param current_rx_seq Sequence number of last packet received
- * @param current_tx_seq Sequence number of last packet sent
- * @param packet_rx_success_count Received packets
- * @param packet_rx_drop_count Number of packet drops
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint16_t n_send_queue,uint16_t max_send_queue,uint16_t n_send_errors,uint8_t msg_received,uint8_t buffer_overrun,uint8_t parse_error,uint32_t parse_state,uint8_t packet_idx,uint8_t current_rx_seq,uint8_t current_tx_seq,uint16_t packet_rx_success_count,uint16_t packet_rx_drop_count)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint32_t(buf, 8, parse_state);
- _mav_put_uint16_t(buf, 12, n_send_queue);
- _mav_put_uint16_t(buf, 14, max_send_queue);
- _mav_put_uint16_t(buf, 16, n_send_errors);
- _mav_put_uint16_t(buf, 18, packet_rx_success_count);
- _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
- _mav_put_uint8_t(buf, 22, msg_received);
- _mav_put_uint8_t(buf, 23, buffer_overrun);
- _mav_put_uint8_t(buf, 24, parse_error);
- _mav_put_uint8_t(buf, 25, packet_idx);
- _mav_put_uint8_t(buf, 26, current_rx_seq);
- _mav_put_uint8_t(buf, 27, current_tx_seq);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN);
-#else
- mavlink_mavlink_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.parse_state = parse_state;
- packet.n_send_queue = n_send_queue;
- packet.max_send_queue = max_send_queue;
- packet.n_send_errors = n_send_errors;
- packet.packet_rx_success_count = packet_rx_success_count;
- packet.packet_rx_drop_count = packet_rx_drop_count;
- packet.msg_received = msg_received;
- packet.buffer_overrun = buffer_overrun;
- packet.parse_error = parse_error;
- packet.packet_idx = packet_idx;
- packet.current_rx_seq = current_rx_seq;
- packet.current_tx_seq = current_tx_seq;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_MAVLINK_STATS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-}
-
-/**
- * @brief Encode a mavlink_stats_tm 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 mavlink_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mavlink_stats_tm_t* mavlink_stats_tm)
-{
- return mavlink_msg_mavlink_stats_tm_pack(system_id, component_id, msg, mavlink_stats_tm->timestamp, mavlink_stats_tm->n_send_queue, mavlink_stats_tm->max_send_queue, mavlink_stats_tm->n_send_errors, mavlink_stats_tm->msg_received, mavlink_stats_tm->buffer_overrun, mavlink_stats_tm->parse_error, mavlink_stats_tm->parse_state, mavlink_stats_tm->packet_idx, mavlink_stats_tm->current_rx_seq, mavlink_stats_tm->current_tx_seq, mavlink_stats_tm->packet_rx_success_count, mavlink_stats_tm->packet_rx_drop_count);
-}
-
-/**
- * @brief Encode a mavlink_stats_tm 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 mavlink_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mavlink_stats_tm_t* mavlink_stats_tm)
-{
- return mavlink_msg_mavlink_stats_tm_pack_chan(system_id, component_id, chan, msg, mavlink_stats_tm->timestamp, mavlink_stats_tm->n_send_queue, mavlink_stats_tm->max_send_queue, mavlink_stats_tm->n_send_errors, mavlink_stats_tm->msg_received, mavlink_stats_tm->buffer_overrun, mavlink_stats_tm->parse_error, mavlink_stats_tm->parse_state, mavlink_stats_tm->packet_idx, mavlink_stats_tm->current_rx_seq, mavlink_stats_tm->current_tx_seq, mavlink_stats_tm->packet_rx_success_count, mavlink_stats_tm->packet_rx_drop_count);
-}
-
-/**
- * @brief Send a mavlink_stats_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param n_send_queue Current len of the occupied portion of the queue
- * @param max_send_queue Max occupied len of the queue
- * @param n_send_errors Number of packet not sent correctly by the TMTC
- * @param msg_received Number of received messages
- * @param buffer_overrun Number of buffer overruns
- * @param parse_error Number of parse errors
- * @param parse_state Parsing state machine
- * @param packet_idx Index in current packet
- * @param current_rx_seq Sequence number of last packet received
- * @param current_tx_seq Sequence number of last packet sent
- * @param packet_rx_success_count Received packets
- * @param packet_rx_drop_count Number of packet drops
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_mavlink_stats_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint16_t n_send_queue, uint16_t max_send_queue, uint16_t n_send_errors, uint8_t msg_received, uint8_t buffer_overrun, uint8_t parse_error, uint32_t parse_state, uint8_t packet_idx, uint8_t current_rx_seq, uint8_t current_tx_seq, uint16_t packet_rx_success_count, uint16_t packet_rx_drop_count)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint32_t(buf, 8, parse_state);
- _mav_put_uint16_t(buf, 12, n_send_queue);
- _mav_put_uint16_t(buf, 14, max_send_queue);
- _mav_put_uint16_t(buf, 16, n_send_errors);
- _mav_put_uint16_t(buf, 18, packet_rx_success_count);
- _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
- _mav_put_uint8_t(buf, 22, msg_received);
- _mav_put_uint8_t(buf, 23, buffer_overrun);
- _mav_put_uint8_t(buf, 24, parse_error);
- _mav_put_uint8_t(buf, 25, packet_idx);
- _mav_put_uint8_t(buf, 26, current_rx_seq);
- _mav_put_uint8_t(buf, 27, current_tx_seq);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAVLINK_STATS_TM, buf, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-#else
- mavlink_mavlink_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.parse_state = parse_state;
- packet.n_send_queue = n_send_queue;
- packet.max_send_queue = max_send_queue;
- packet.n_send_errors = n_send_errors;
- packet.packet_rx_success_count = packet_rx_success_count;
- packet.packet_rx_drop_count = packet_rx_drop_count;
- packet.msg_received = msg_received;
- packet.buffer_overrun = buffer_overrun;
- packet.parse_error = parse_error;
- packet.packet_idx = packet_idx;
- packet.current_rx_seq = current_rx_seq;
- packet.current_tx_seq = current_tx_seq;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAVLINK_STATS_TM, (const char *)&packet, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a mavlink_stats_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_mavlink_stats_tm_send_struct(mavlink_channel_t chan, const mavlink_mavlink_stats_tm_t* mavlink_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_mavlink_stats_tm_send(chan, mavlink_stats_tm->timestamp, mavlink_stats_tm->n_send_queue, mavlink_stats_tm->max_send_queue, mavlink_stats_tm->n_send_errors, mavlink_stats_tm->msg_received, mavlink_stats_tm->buffer_overrun, mavlink_stats_tm->parse_error, mavlink_stats_tm->parse_state, mavlink_stats_tm->packet_idx, mavlink_stats_tm->current_rx_seq, mavlink_stats_tm->current_tx_seq, mavlink_stats_tm->packet_rx_success_count, mavlink_stats_tm->packet_rx_drop_count);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAVLINK_STATS_TM, (const char *)mavlink_stats_tm, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_MAVLINK_STATS_TM_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_mavlink_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint16_t n_send_queue, uint16_t max_send_queue, uint16_t n_send_errors, uint8_t msg_received, uint8_t buffer_overrun, uint8_t parse_error, uint32_t parse_state, uint8_t packet_idx, uint8_t current_rx_seq, uint8_t current_tx_seq, uint16_t packet_rx_success_count, uint16_t packet_rx_drop_count)
-{
-#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, parse_state);
- _mav_put_uint16_t(buf, 12, n_send_queue);
- _mav_put_uint16_t(buf, 14, max_send_queue);
- _mav_put_uint16_t(buf, 16, n_send_errors);
- _mav_put_uint16_t(buf, 18, packet_rx_success_count);
- _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
- _mav_put_uint8_t(buf, 22, msg_received);
- _mav_put_uint8_t(buf, 23, buffer_overrun);
- _mav_put_uint8_t(buf, 24, parse_error);
- _mav_put_uint8_t(buf, 25, packet_idx);
- _mav_put_uint8_t(buf, 26, current_rx_seq);
- _mav_put_uint8_t(buf, 27, current_tx_seq);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAVLINK_STATS_TM, buf, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-#else
- mavlink_mavlink_stats_tm_t *packet = (mavlink_mavlink_stats_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->parse_state = parse_state;
- packet->n_send_queue = n_send_queue;
- packet->max_send_queue = max_send_queue;
- packet->n_send_errors = n_send_errors;
- packet->packet_rx_success_count = packet_rx_success_count;
- packet->packet_rx_drop_count = packet_rx_drop_count;
- packet->msg_received = msg_received;
- packet->buffer_overrun = buffer_overrun;
- packet->parse_error = parse_error;
- packet->packet_idx = packet_idx;
- packet->current_rx_seq = current_rx_seq;
- packet->current_tx_seq = current_tx_seq;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAVLINK_STATS_TM, (const char *)packet, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE MAVLINK_STATS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from mavlink_stats_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_mavlink_stats_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field n_send_queue from mavlink_stats_tm message
- *
- * @return Current len of the occupied portion of the queue
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_get_n_send_queue(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 12);
-}
-
-/**
- * @brief Get field max_send_queue from mavlink_stats_tm message
- *
- * @return Max occupied len of the queue
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_get_max_send_queue(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 14);
-}
-
-/**
- * @brief Get field n_send_errors from mavlink_stats_tm message
- *
- * @return Number of packet not sent correctly by the TMTC
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_get_n_send_errors(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 16);
-}
-
-/**
- * @brief Get field msg_received from mavlink_stats_tm message
- *
- * @return Number of received messages
- */
-static inline uint8_t mavlink_msg_mavlink_stats_tm_get_msg_received(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 22);
-}
-
-/**
- * @brief Get field buffer_overrun from mavlink_stats_tm message
- *
- * @return Number of buffer overruns
- */
-static inline uint8_t mavlink_msg_mavlink_stats_tm_get_buffer_overrun(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 23);
-}
-
-/**
- * @brief Get field parse_error from mavlink_stats_tm message
- *
- * @return Number of parse errors
- */
-static inline uint8_t mavlink_msg_mavlink_stats_tm_get_parse_error(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 24);
-}
-
-/**
- * @brief Get field parse_state from mavlink_stats_tm message
- *
- * @return Parsing state machine
- */
-static inline uint32_t mavlink_msg_mavlink_stats_tm_get_parse_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 8);
-}
-
-/**
- * @brief Get field packet_idx from mavlink_stats_tm message
- *
- * @return Index in current packet
- */
-static inline uint8_t mavlink_msg_mavlink_stats_tm_get_packet_idx(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 25);
-}
-
-/**
- * @brief Get field current_rx_seq from mavlink_stats_tm message
- *
- * @return Sequence number of last packet received
- */
-static inline uint8_t mavlink_msg_mavlink_stats_tm_get_current_rx_seq(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 26);
-}
-
-/**
- * @brief Get field current_tx_seq from mavlink_stats_tm message
- *
- * @return Sequence number of last packet sent
- */
-static inline uint8_t mavlink_msg_mavlink_stats_tm_get_current_tx_seq(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 27);
-}
-
-/**
- * @brief Get field packet_rx_success_count from mavlink_stats_tm message
- *
- * @return Received packets
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_get_packet_rx_success_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 18);
-}
-
-/**
- * @brief Get field packet_rx_drop_count from mavlink_stats_tm message
- *
- * @return Number of packet drops
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_get_packet_rx_drop_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 20);
-}
-
-/**
- * @brief Decode a mavlink_stats_tm message into a struct
- *
- * @param msg The message to decode
- * @param mavlink_stats_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_mavlink_stats_tm_decode(const mavlink_message_t* msg, mavlink_mavlink_stats_tm_t* mavlink_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_stats_tm->timestamp = mavlink_msg_mavlink_stats_tm_get_timestamp(msg);
- mavlink_stats_tm->parse_state = mavlink_msg_mavlink_stats_tm_get_parse_state(msg);
- mavlink_stats_tm->n_send_queue = mavlink_msg_mavlink_stats_tm_get_n_send_queue(msg);
- mavlink_stats_tm->max_send_queue = mavlink_msg_mavlink_stats_tm_get_max_send_queue(msg);
- mavlink_stats_tm->n_send_errors = mavlink_msg_mavlink_stats_tm_get_n_send_errors(msg);
- mavlink_stats_tm->packet_rx_success_count = mavlink_msg_mavlink_stats_tm_get_packet_rx_success_count(msg);
- mavlink_stats_tm->packet_rx_drop_count = mavlink_msg_mavlink_stats_tm_get_packet_rx_drop_count(msg);
- mavlink_stats_tm->msg_received = mavlink_msg_mavlink_stats_tm_get_msg_received(msg);
- mavlink_stats_tm->buffer_overrun = mavlink_msg_mavlink_stats_tm_get_buffer_overrun(msg);
- mavlink_stats_tm->parse_error = mavlink_msg_mavlink_stats_tm_get_parse_error(msg);
- mavlink_stats_tm->packet_idx = mavlink_msg_mavlink_stats_tm_get_packet_idx(msg);
- mavlink_stats_tm->current_rx_seq = mavlink_msg_mavlink_stats_tm_get_current_rx_seq(msg);
- mavlink_stats_tm->current_tx_seq = mavlink_msg_mavlink_stats_tm_get_current_tx_seq(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN? msg->len : MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN;
- memset(mavlink_stats_tm, 0, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN);
- memcpy(mavlink_stats_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_mea_tm.h b/mavlink_lib/lyra/mavlink_msg_mea_tm.h
deleted file mode 100644
index a3887d7e6363b14616deca868632f1fc6c0d3b26..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_mea_tm.h
+++ /dev/null
@@ -1,363 +0,0 @@
-#pragma once
-// MESSAGE MEA_TM PACKING
-
-#define MAVLINK_MSG_ID_MEA_TM 207
-
-
-typedef struct __mavlink_mea_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float kalman_x0; /*< Kalman state variable 0 (corrected pressure)*/
- float kalman_x1; /*< Kalman state variable 1 */
- float kalman_x2; /*< Kalman state variable 2 (mass)*/
- float mass; /*< [kg] Mass estimated*/
- float corrected_pressure; /*< [kg] Corrected pressure*/
- uint8_t state; /*< MEA current state*/
-} mavlink_mea_tm_t;
-
-#define MAVLINK_MSG_ID_MEA_TM_LEN 29
-#define MAVLINK_MSG_ID_MEA_TM_MIN_LEN 29
-#define MAVLINK_MSG_ID_207_LEN 29
-#define MAVLINK_MSG_ID_207_MIN_LEN 29
-
-#define MAVLINK_MSG_ID_MEA_TM_CRC 11
-#define MAVLINK_MSG_ID_207_CRC 11
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_MEA_TM { \
- 207, \
- "MEA_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_mea_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_mea_tm_t, state) }, \
- { "kalman_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mea_tm_t, kalman_x0) }, \
- { "kalman_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mea_tm_t, kalman_x1) }, \
- { "kalman_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mea_tm_t, kalman_x2) }, \
- { "mass", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mea_tm_t, mass) }, \
- { "corrected_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mea_tm_t, corrected_pressure) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_MEA_TM { \
- "MEA_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_mea_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_mea_tm_t, state) }, \
- { "kalman_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mea_tm_t, kalman_x0) }, \
- { "kalman_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mea_tm_t, kalman_x1) }, \
- { "kalman_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mea_tm_t, kalman_x2) }, \
- { "mass", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mea_tm_t, mass) }, \
- { "corrected_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mea_tm_t, corrected_pressure) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a mea_tm 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] When was this logged
- * @param state MEA current state
- * @param kalman_x0 Kalman state variable 0 (corrected pressure)
- * @param kalman_x1 Kalman state variable 1
- * @param kalman_x2 Kalman state variable 2 (mass)
- * @param mass [kg] Mass estimated
- * @param corrected_pressure [kg] Corrected pressure
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_mea_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float mass, float corrected_pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MEA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, kalman_x0);
- _mav_put_float(buf, 12, kalman_x1);
- _mav_put_float(buf, 16, kalman_x2);
- _mav_put_float(buf, 20, mass);
- _mav_put_float(buf, 24, corrected_pressure);
- _mav_put_uint8_t(buf, 28, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEA_TM_LEN);
-#else
- mavlink_mea_tm_t packet;
- packet.timestamp = timestamp;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.mass = mass;
- packet.corrected_pressure = corrected_pressure;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEA_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_MEA_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
-}
-
-/**
- * @brief Pack a mea_tm 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] When was this logged
- * @param state MEA current state
- * @param kalman_x0 Kalman state variable 0 (corrected pressure)
- * @param kalman_x1 Kalman state variable 1
- * @param kalman_x2 Kalman state variable 2 (mass)
- * @param mass [kg] Mass estimated
- * @param corrected_pressure [kg] Corrected pressure
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_mea_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t state,float kalman_x0,float kalman_x1,float kalman_x2,float mass,float corrected_pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MEA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, kalman_x0);
- _mav_put_float(buf, 12, kalman_x1);
- _mav_put_float(buf, 16, kalman_x2);
- _mav_put_float(buf, 20, mass);
- _mav_put_float(buf, 24, corrected_pressure);
- _mav_put_uint8_t(buf, 28, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEA_TM_LEN);
-#else
- mavlink_mea_tm_t packet;
- packet.timestamp = timestamp;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.mass = mass;
- packet.corrected_pressure = corrected_pressure;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEA_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_MEA_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
-}
-
-/**
- * @brief Encode a mea_tm 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 mea_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_mea_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mea_tm_t* mea_tm)
-{
- return mavlink_msg_mea_tm_pack(system_id, component_id, msg, mea_tm->timestamp, mea_tm->state, mea_tm->kalman_x0, mea_tm->kalman_x1, mea_tm->kalman_x2, mea_tm->mass, mea_tm->corrected_pressure);
-}
-
-/**
- * @brief Encode a mea_tm 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 mea_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_mea_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mea_tm_t* mea_tm)
-{
- return mavlink_msg_mea_tm_pack_chan(system_id, component_id, chan, msg, mea_tm->timestamp, mea_tm->state, mea_tm->kalman_x0, mea_tm->kalman_x1, mea_tm->kalman_x2, mea_tm->mass, mea_tm->corrected_pressure);
-}
-
-/**
- * @brief Send a mea_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param state MEA current state
- * @param kalman_x0 Kalman state variable 0 (corrected pressure)
- * @param kalman_x1 Kalman state variable 1
- * @param kalman_x2 Kalman state variable 2 (mass)
- * @param mass [kg] Mass estimated
- * @param corrected_pressure [kg] Corrected pressure
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_mea_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float mass, float corrected_pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MEA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, kalman_x0);
- _mav_put_float(buf, 12, kalman_x1);
- _mav_put_float(buf, 16, kalman_x2);
- _mav_put_float(buf, 20, mass);
- _mav_put_float(buf, 24, corrected_pressure);
- _mav_put_uint8_t(buf, 28, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEA_TM, buf, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
-#else
- mavlink_mea_tm_t packet;
- packet.timestamp = timestamp;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.mass = mass;
- packet.corrected_pressure = corrected_pressure;
- packet.state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEA_TM, (const char *)&packet, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a mea_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_mea_tm_send_struct(mavlink_channel_t chan, const mavlink_mea_tm_t* mea_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_mea_tm_send(chan, mea_tm->timestamp, mea_tm->state, mea_tm->kalman_x0, mea_tm->kalman_x1, mea_tm->kalman_x2, mea_tm->mass, mea_tm->corrected_pressure);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEA_TM, (const char *)mea_tm, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_MEA_TM_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_mea_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float mass, float corrected_pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, kalman_x0);
- _mav_put_float(buf, 12, kalman_x1);
- _mav_put_float(buf, 16, kalman_x2);
- _mav_put_float(buf, 20, mass);
- _mav_put_float(buf, 24, corrected_pressure);
- _mav_put_uint8_t(buf, 28, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEA_TM, buf, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
-#else
- mavlink_mea_tm_t *packet = (mavlink_mea_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->kalman_x0 = kalman_x0;
- packet->kalman_x1 = kalman_x1;
- packet->kalman_x2 = kalman_x2;
- packet->mass = mass;
- packet->corrected_pressure = corrected_pressure;
- packet->state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEA_TM, (const char *)packet, MAVLINK_MSG_ID_MEA_TM_MIN_LEN, MAVLINK_MSG_ID_MEA_TM_LEN, MAVLINK_MSG_ID_MEA_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE MEA_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from mea_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_mea_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field state from mea_tm message
- *
- * @return MEA current state
- */
-static inline uint8_t mavlink_msg_mea_tm_get_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 28);
-}
-
-/**
- * @brief Get field kalman_x0 from mea_tm message
- *
- * @return Kalman state variable 0 (corrected pressure)
- */
-static inline float mavlink_msg_mea_tm_get_kalman_x0(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field kalman_x1 from mea_tm message
- *
- * @return Kalman state variable 1
- */
-static inline float mavlink_msg_mea_tm_get_kalman_x1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field kalman_x2 from mea_tm message
- *
- * @return Kalman state variable 2 (mass)
- */
-static inline float mavlink_msg_mea_tm_get_kalman_x2(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field mass from mea_tm message
- *
- * @return [kg] Mass estimated
- */
-static inline float mavlink_msg_mea_tm_get_mass(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field corrected_pressure from mea_tm message
- *
- * @return [kg] Corrected pressure
- */
-static inline float mavlink_msg_mea_tm_get_corrected_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Decode a mea_tm message into a struct
- *
- * @param msg The message to decode
- * @param mea_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_mea_tm_decode(const mavlink_message_t* msg, mavlink_mea_tm_t* mea_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mea_tm->timestamp = mavlink_msg_mea_tm_get_timestamp(msg);
- mea_tm->kalman_x0 = mavlink_msg_mea_tm_get_kalman_x0(msg);
- mea_tm->kalman_x1 = mavlink_msg_mea_tm_get_kalman_x1(msg);
- mea_tm->kalman_x2 = mavlink_msg_mea_tm_get_kalman_x2(msg);
- mea_tm->mass = mavlink_msg_mea_tm_get_mass(msg);
- mea_tm->corrected_pressure = mavlink_msg_mea_tm_get_corrected_pressure(msg);
- mea_tm->state = mavlink_msg_mea_tm_get_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_MEA_TM_LEN? msg->len : MAVLINK_MSG_ID_MEA_TM_LEN;
- memset(mea_tm, 0, MAVLINK_MSG_ID_MEA_TM_LEN);
- memcpy(mea_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_motor_tm.h b/mavlink_lib/lyra/mavlink_msg_motor_tm.h
deleted file mode 100644
index 25643d25c37da50e8d0f474b4649b81d103b7ab4..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_motor_tm.h
+++ /dev/null
@@ -1,438 +0,0 @@
-#pragma once
-// MESSAGE MOTOR_TM PACKING
-
-#define MAVLINK_MSG_ID_MOTOR_TM 213
-
-
-typedef struct __mavlink_motor_tm_t {
- uint64_t timestamp; /*< [us] Timestamp in microseconds*/
- float top_tank_pressure; /*< [Bar] Tank upper pressure*/
- float bottom_tank_pressure; /*< [Bar] Tank bottom pressure*/
- float combustion_chamber_pressure; /*< [Bar] Pressure inside the combustion chamber used for automatic shutdown*/
- float tank_temperature; /*< Tank temperature*/
- float battery_voltage; /*< [V] Battery voltage*/
- float current_consumption; /*< [A] Current drained from the battery*/
- uint8_t floating_level; /*< Floating level in tank*/
- uint8_t main_valve_state; /*< 1 If the main valve is open */
- uint8_t venting_valve_state; /*< 1 If the venting valve is open */
-} mavlink_motor_tm_t;
-
-#define MAVLINK_MSG_ID_MOTOR_TM_LEN 35
-#define MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN 35
-#define MAVLINK_MSG_ID_213_LEN 35
-#define MAVLINK_MSG_ID_213_MIN_LEN 35
-
-#define MAVLINK_MSG_ID_MOTOR_TM_CRC 79
-#define MAVLINK_MSG_ID_213_CRC 79
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_MOTOR_TM { \
- 213, \
- "MOTOR_TM", \
- 10, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_motor_tm_t, timestamp) }, \
- { "top_tank_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_motor_tm_t, top_tank_pressure) }, \
- { "bottom_tank_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_motor_tm_t, bottom_tank_pressure) }, \
- { "combustion_chamber_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_motor_tm_t, combustion_chamber_pressure) }, \
- { "floating_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_motor_tm_t, floating_level) }, \
- { "tank_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_motor_tm_t, tank_temperature) }, \
- { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_motor_tm_t, main_valve_state) }, \
- { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_motor_tm_t, venting_valve_state) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_motor_tm_t, battery_voltage) }, \
- { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_motor_tm_t, current_consumption) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_MOTOR_TM { \
- "MOTOR_TM", \
- 10, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_motor_tm_t, timestamp) }, \
- { "top_tank_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_motor_tm_t, top_tank_pressure) }, \
- { "bottom_tank_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_motor_tm_t, bottom_tank_pressure) }, \
- { "combustion_chamber_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_motor_tm_t, combustion_chamber_pressure) }, \
- { "floating_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_motor_tm_t, floating_level) }, \
- { "tank_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_motor_tm_t, tank_temperature) }, \
- { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_motor_tm_t, main_valve_state) }, \
- { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_motor_tm_t, venting_valve_state) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_motor_tm_t, battery_voltage) }, \
- { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_motor_tm_t, current_consumption) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a motor_tm 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 in microseconds
- * @param top_tank_pressure [Bar] Tank upper pressure
- * @param bottom_tank_pressure [Bar] Tank bottom pressure
- * @param combustion_chamber_pressure [Bar] Pressure inside the combustion chamber used for automatic shutdown
- * @param floating_level Floating level in tank
- * @param tank_temperature Tank temperature
- * @param main_valve_state 1 If the main valve is open
- * @param venting_valve_state 1 If the venting valve is open
- * @param battery_voltage [V] Battery voltage
- * @param current_consumption [A] Current drained from the battery
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_motor_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, uint8_t floating_level, float tank_temperature, uint8_t main_valve_state, uint8_t venting_valve_state, float battery_voltage, float current_consumption)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MOTOR_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, top_tank_pressure);
- _mav_put_float(buf, 12, bottom_tank_pressure);
- _mav_put_float(buf, 16, combustion_chamber_pressure);
- _mav_put_float(buf, 20, tank_temperature);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_float(buf, 28, current_consumption);
- _mav_put_uint8_t(buf, 32, floating_level);
- _mav_put_uint8_t(buf, 33, main_valve_state);
- _mav_put_uint8_t(buf, 34, venting_valve_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOTOR_TM_LEN);
-#else
- mavlink_motor_tm_t packet;
- packet.timestamp = timestamp;
- packet.top_tank_pressure = top_tank_pressure;
- packet.bottom_tank_pressure = bottom_tank_pressure;
- packet.combustion_chamber_pressure = combustion_chamber_pressure;
- packet.tank_temperature = tank_temperature;
- packet.battery_voltage = battery_voltage;
- packet.current_consumption = current_consumption;
- packet.floating_level = floating_level;
- packet.main_valve_state = main_valve_state;
- packet.venting_valve_state = venting_valve_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOTOR_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_MOTOR_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
-}
-
-/**
- * @brief Pack a motor_tm 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 in microseconds
- * @param top_tank_pressure [Bar] Tank upper pressure
- * @param bottom_tank_pressure [Bar] Tank bottom pressure
- * @param combustion_chamber_pressure [Bar] Pressure inside the combustion chamber used for automatic shutdown
- * @param floating_level Floating level in tank
- * @param tank_temperature Tank temperature
- * @param main_valve_state 1 If the main valve is open
- * @param venting_valve_state 1 If the venting valve is open
- * @param battery_voltage [V] Battery voltage
- * @param current_consumption [A] Current drained from the battery
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_motor_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,float top_tank_pressure,float bottom_tank_pressure,float combustion_chamber_pressure,uint8_t floating_level,float tank_temperature,uint8_t main_valve_state,uint8_t venting_valve_state,float battery_voltage,float current_consumption)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MOTOR_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, top_tank_pressure);
- _mav_put_float(buf, 12, bottom_tank_pressure);
- _mav_put_float(buf, 16, combustion_chamber_pressure);
- _mav_put_float(buf, 20, tank_temperature);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_float(buf, 28, current_consumption);
- _mav_put_uint8_t(buf, 32, floating_level);
- _mav_put_uint8_t(buf, 33, main_valve_state);
- _mav_put_uint8_t(buf, 34, venting_valve_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOTOR_TM_LEN);
-#else
- mavlink_motor_tm_t packet;
- packet.timestamp = timestamp;
- packet.top_tank_pressure = top_tank_pressure;
- packet.bottom_tank_pressure = bottom_tank_pressure;
- packet.combustion_chamber_pressure = combustion_chamber_pressure;
- packet.tank_temperature = tank_temperature;
- packet.battery_voltage = battery_voltage;
- packet.current_consumption = current_consumption;
- packet.floating_level = floating_level;
- packet.main_valve_state = main_valve_state;
- packet.venting_valve_state = venting_valve_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOTOR_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_MOTOR_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
-}
-
-/**
- * @brief Encode a motor_tm 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 motor_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_motor_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_motor_tm_t* motor_tm)
-{
- return mavlink_msg_motor_tm_pack(system_id, component_id, msg, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->floating_level, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->venting_valve_state, motor_tm->battery_voltage, motor_tm->current_consumption);
-}
-
-/**
- * @brief Encode a motor_tm 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 motor_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_motor_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_motor_tm_t* motor_tm)
-{
- return mavlink_msg_motor_tm_pack_chan(system_id, component_id, chan, msg, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->floating_level, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->venting_valve_state, motor_tm->battery_voltage, motor_tm->current_consumption);
-}
-
-/**
- * @brief Send a motor_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp in microseconds
- * @param top_tank_pressure [Bar] Tank upper pressure
- * @param bottom_tank_pressure [Bar] Tank bottom pressure
- * @param combustion_chamber_pressure [Bar] Pressure inside the combustion chamber used for automatic shutdown
- * @param floating_level Floating level in tank
- * @param tank_temperature Tank temperature
- * @param main_valve_state 1 If the main valve is open
- * @param venting_valve_state 1 If the venting valve is open
- * @param battery_voltage [V] Battery voltage
- * @param current_consumption [A] Current drained from the battery
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_motor_tm_send(mavlink_channel_t chan, uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, uint8_t floating_level, float tank_temperature, uint8_t main_valve_state, uint8_t venting_valve_state, float battery_voltage, float current_consumption)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MOTOR_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, top_tank_pressure);
- _mav_put_float(buf, 12, bottom_tank_pressure);
- _mav_put_float(buf, 16, combustion_chamber_pressure);
- _mav_put_float(buf, 20, tank_temperature);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_float(buf, 28, current_consumption);
- _mav_put_uint8_t(buf, 32, floating_level);
- _mav_put_uint8_t(buf, 33, main_valve_state);
- _mav_put_uint8_t(buf, 34, venting_valve_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOTOR_TM, buf, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
-#else
- mavlink_motor_tm_t packet;
- packet.timestamp = timestamp;
- packet.top_tank_pressure = top_tank_pressure;
- packet.bottom_tank_pressure = bottom_tank_pressure;
- packet.combustion_chamber_pressure = combustion_chamber_pressure;
- packet.tank_temperature = tank_temperature;
- packet.battery_voltage = battery_voltage;
- packet.current_consumption = current_consumption;
- packet.floating_level = floating_level;
- packet.main_valve_state = main_valve_state;
- packet.venting_valve_state = venting_valve_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOTOR_TM, (const char *)&packet, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a motor_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_motor_tm_send_struct(mavlink_channel_t chan, const mavlink_motor_tm_t* motor_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_motor_tm_send(chan, motor_tm->timestamp, motor_tm->top_tank_pressure, motor_tm->bottom_tank_pressure, motor_tm->combustion_chamber_pressure, motor_tm->floating_level, motor_tm->tank_temperature, motor_tm->main_valve_state, motor_tm->venting_valve_state, motor_tm->battery_voltage, motor_tm->current_consumption);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOTOR_TM, (const char *)motor_tm, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_MOTOR_TM_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_motor_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float top_tank_pressure, float bottom_tank_pressure, float combustion_chamber_pressure, uint8_t floating_level, float tank_temperature, uint8_t main_valve_state, uint8_t venting_valve_state, float battery_voltage, float current_consumption)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, top_tank_pressure);
- _mav_put_float(buf, 12, bottom_tank_pressure);
- _mav_put_float(buf, 16, combustion_chamber_pressure);
- _mav_put_float(buf, 20, tank_temperature);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_float(buf, 28, current_consumption);
- _mav_put_uint8_t(buf, 32, floating_level);
- _mav_put_uint8_t(buf, 33, main_valve_state);
- _mav_put_uint8_t(buf, 34, venting_valve_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOTOR_TM, buf, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
-#else
- mavlink_motor_tm_t *packet = (mavlink_motor_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->top_tank_pressure = top_tank_pressure;
- packet->bottom_tank_pressure = bottom_tank_pressure;
- packet->combustion_chamber_pressure = combustion_chamber_pressure;
- packet->tank_temperature = tank_temperature;
- packet->battery_voltage = battery_voltage;
- packet->current_consumption = current_consumption;
- packet->floating_level = floating_level;
- packet->main_valve_state = main_valve_state;
- packet->venting_valve_state = venting_valve_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOTOR_TM, (const char *)packet, MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN, MAVLINK_MSG_ID_MOTOR_TM_LEN, MAVLINK_MSG_ID_MOTOR_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE MOTOR_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from motor_tm message
- *
- * @return [us] Timestamp in microseconds
- */
-static inline uint64_t mavlink_msg_motor_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field top_tank_pressure from motor_tm message
- *
- * @return [Bar] Tank upper pressure
- */
-static inline float mavlink_msg_motor_tm_get_top_tank_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field bottom_tank_pressure from motor_tm message
- *
- * @return [Bar] Tank bottom pressure
- */
-static inline float mavlink_msg_motor_tm_get_bottom_tank_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field combustion_chamber_pressure from motor_tm message
- *
- * @return [Bar] Pressure inside the combustion chamber used for automatic shutdown
- */
-static inline float mavlink_msg_motor_tm_get_combustion_chamber_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field floating_level from motor_tm message
- *
- * @return Floating level in tank
- */
-static inline uint8_t mavlink_msg_motor_tm_get_floating_level(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 32);
-}
-
-/**
- * @brief Get field tank_temperature from motor_tm message
- *
- * @return Tank temperature
- */
-static inline float mavlink_msg_motor_tm_get_tank_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field main_valve_state from motor_tm message
- *
- * @return 1 If the main valve is open
- */
-static inline uint8_t mavlink_msg_motor_tm_get_main_valve_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 33);
-}
-
-/**
- * @brief Get field venting_valve_state from motor_tm message
- *
- * @return 1 If the venting valve is open
- */
-static inline uint8_t mavlink_msg_motor_tm_get_venting_valve_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 34);
-}
-
-/**
- * @brief Get field battery_voltage from motor_tm message
- *
- * @return [V] Battery voltage
- */
-static inline float mavlink_msg_motor_tm_get_battery_voltage(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field current_consumption from motor_tm message
- *
- * @return [A] Current drained from the battery
- */
-static inline float mavlink_msg_motor_tm_get_current_consumption(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Decode a motor_tm message into a struct
- *
- * @param msg The message to decode
- * @param motor_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_motor_tm_decode(const mavlink_message_t* msg, mavlink_motor_tm_t* motor_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- motor_tm->timestamp = mavlink_msg_motor_tm_get_timestamp(msg);
- motor_tm->top_tank_pressure = mavlink_msg_motor_tm_get_top_tank_pressure(msg);
- motor_tm->bottom_tank_pressure = mavlink_msg_motor_tm_get_bottom_tank_pressure(msg);
- motor_tm->combustion_chamber_pressure = mavlink_msg_motor_tm_get_combustion_chamber_pressure(msg);
- motor_tm->tank_temperature = mavlink_msg_motor_tm_get_tank_temperature(msg);
- motor_tm->battery_voltage = mavlink_msg_motor_tm_get_battery_voltage(msg);
- motor_tm->current_consumption = mavlink_msg_motor_tm_get_current_consumption(msg);
- motor_tm->floating_level = mavlink_msg_motor_tm_get_floating_level(msg);
- motor_tm->main_valve_state = mavlink_msg_motor_tm_get_main_valve_state(msg);
- motor_tm->venting_valve_state = mavlink_msg_motor_tm_get_venting_valve_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_MOTOR_TM_LEN? msg->len : MAVLINK_MSG_ID_MOTOR_TM_LEN;
- memset(motor_tm, 0, MAVLINK_MSG_ID_MOTOR_TM_LEN);
- memcpy(motor_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_nack_tm.h b/mavlink_lib/lyra/mavlink_msg_nack_tm.h
deleted file mode 100644
index 85abd048c50911cd99ded380f566cf5c34b29322..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_nack_tm.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE NACK_TM PACKING
-
-#define MAVLINK_MSG_ID_NACK_TM 101
-
-
-typedef struct __mavlink_nack_tm_t {
- uint8_t recv_msgid; /*< Message id of the received message*/
- uint8_t seq_ack; /*< Sequence number of the received message*/
-} mavlink_nack_tm_t;
-
-#define MAVLINK_MSG_ID_NACK_TM_LEN 2
-#define MAVLINK_MSG_ID_NACK_TM_MIN_LEN 2
-#define MAVLINK_MSG_ID_101_LEN 2
-#define MAVLINK_MSG_ID_101_MIN_LEN 2
-
-#define MAVLINK_MSG_ID_NACK_TM_CRC 146
-#define MAVLINK_MSG_ID_101_CRC 146
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_NACK_TM { \
- 101, \
- "NACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_nack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_nack_tm_t, seq_ack) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_NACK_TM { \
- "NACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_nack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_nack_tm_t, seq_ack) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a nack_tm 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 recv_msgid Message id of the received message
- * @param seq_ack Sequence number of the received message
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_nack_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NACK_TM_LEN);
-#else
- mavlink_nack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NACK_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-}
-
-/**
- * @brief Pack a nack_tm 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 recv_msgid Message id of the received message
- * @param seq_ack Sequence number of the received message
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_nack_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t recv_msgid,uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NACK_TM_LEN);
-#else
- mavlink_nack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NACK_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-}
-
-/**
- * @brief Encode a nack_tm 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 nack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_nack_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nack_tm_t* nack_tm)
-{
- return mavlink_msg_nack_tm_pack(system_id, component_id, msg, nack_tm->recv_msgid, nack_tm->seq_ack);
-}
-
-/**
- * @brief Encode a nack_tm 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 nack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_nack_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nack_tm_t* nack_tm)
-{
- return mavlink_msg_nack_tm_pack_chan(system_id, component_id, chan, msg, nack_tm->recv_msgid, nack_tm->seq_ack);
-}
-
-/**
- * @brief Send a nack_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param recv_msgid Message id of the received message
- * @param seq_ack Sequence number of the received message
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_nack_tm_send(mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, buf, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#else
- mavlink_nack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, (const char *)&packet, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a nack_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_nack_tm_send_struct(mavlink_channel_t chan, const mavlink_nack_tm_t* nack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_nack_tm_send(chan, nack_tm->recv_msgid, nack_tm->seq_ack);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, (const char *)nack_tm, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_NACK_TM_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_nack_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, buf, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#else
- mavlink_nack_tm_t *packet = (mavlink_nack_tm_t *)msgbuf;
- packet->recv_msgid = recv_msgid;
- packet->seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, (const char *)packet, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE NACK_TM UNPACKING
-
-
-/**
- * @brief Get field recv_msgid from nack_tm message
- *
- * @return Message id of the received message
- */
-static inline uint8_t mavlink_msg_nack_tm_get_recv_msgid(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field seq_ack from nack_tm message
- *
- * @return Sequence number of the received message
- */
-static inline uint8_t mavlink_msg_nack_tm_get_seq_ack(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Decode a nack_tm message into a struct
- *
- * @param msg The message to decode
- * @param nack_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_nack_tm_decode(const mavlink_message_t* msg, mavlink_nack_tm_t* nack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- nack_tm->recv_msgid = mavlink_msg_nack_tm_get_recv_msgid(msg);
- nack_tm->seq_ack = mavlink_msg_nack_tm_get_seq_ack(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_NACK_TM_LEN? msg->len : MAVLINK_MSG_ID_NACK_TM_LEN;
- memset(nack_tm, 0, MAVLINK_MSG_ID_NACK_TM_LEN);
- memcpy(nack_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_nas_tm.h b/mavlink_lib/lyra/mavlink_msg_nas_tm.h
deleted file mode 100644
index e91b837c04d4e2bc46c3226696f68c32890b9f08..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_nas_tm.h
+++ /dev/null
@@ -1,663 +0,0 @@
-#pragma once
-// MESSAGE NAS_TM PACKING
-
-#define MAVLINK_MSG_ID_NAS_TM 206
-
-
-typedef struct __mavlink_nas_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float nas_n; /*< [deg] Navigation system estimated noth position*/
- float nas_e; /*< [deg] Navigation system estimated east position*/
- float nas_d; /*< [m] Navigation system estimated down position*/
- float nas_vn; /*< [m/s] Navigation system estimated north velocity*/
- float nas_ve; /*< [m/s] Navigation system estimated east velocity*/
- float nas_vd; /*< [m/s] Navigation system estimated down velocity*/
- float nas_qx; /*< [deg] Navigation system estimated attitude (qx)*/
- float nas_qy; /*< [deg] Navigation system estimated attitude (qy)*/
- float nas_qz; /*< [deg] Navigation system estimated attitude (qz)*/
- float nas_qw; /*< [deg] Navigation system estimated attitude (qw)*/
- float nas_bias_x; /*< Navigation system gyroscope bias on x axis*/
- float nas_bias_y; /*< Navigation system gyroscope bias on y axis*/
- float nas_bias_z; /*< Navigation system gyroscope bias on z axis*/
- float ref_pressure; /*< [Pa] Calibration pressure*/
- float ref_temperature; /*< [degC] Calibration temperature*/
- float ref_latitude; /*< [deg] Calibration latitude*/
- float ref_longitude; /*< [deg] Calibration longitude*/
- uint8_t state; /*< NAS current state*/
-} mavlink_nas_tm_t;
-
-#define MAVLINK_MSG_ID_NAS_TM_LEN 77
-#define MAVLINK_MSG_ID_NAS_TM_MIN_LEN 77
-#define MAVLINK_MSG_ID_206_LEN 77
-#define MAVLINK_MSG_ID_206_MIN_LEN 77
-
-#define MAVLINK_MSG_ID_NAS_TM_CRC 66
-#define MAVLINK_MSG_ID_206_CRC 66
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_NAS_TM { \
- 206, \
- "NAS_TM", \
- 19, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_nas_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 76, offsetof(mavlink_nas_tm_t, state) }, \
- { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nas_tm_t, nas_n) }, \
- { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nas_tm_t, nas_e) }, \
- { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nas_tm_t, nas_d) }, \
- { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_nas_tm_t, nas_vn) }, \
- { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_nas_tm_t, nas_ve) }, \
- { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_nas_tm_t, nas_vd) }, \
- { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_nas_tm_t, nas_qx) }, \
- { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_nas_tm_t, nas_qy) }, \
- { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_nas_tm_t, nas_qz) }, \
- { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_nas_tm_t, nas_qw) }, \
- { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_nas_tm_t, nas_bias_x) }, \
- { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_nas_tm_t, nas_bias_y) }, \
- { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_nas_tm_t, nas_bias_z) }, \
- { "ref_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_nas_tm_t, ref_pressure) }, \
- { "ref_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_nas_tm_t, ref_temperature) }, \
- { "ref_latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_nas_tm_t, ref_latitude) }, \
- { "ref_longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_nas_tm_t, ref_longitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_NAS_TM { \
- "NAS_TM", \
- 19, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_nas_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 76, offsetof(mavlink_nas_tm_t, state) }, \
- { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nas_tm_t, nas_n) }, \
- { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nas_tm_t, nas_e) }, \
- { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nas_tm_t, nas_d) }, \
- { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_nas_tm_t, nas_vn) }, \
- { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_nas_tm_t, nas_ve) }, \
- { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_nas_tm_t, nas_vd) }, \
- { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_nas_tm_t, nas_qx) }, \
- { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_nas_tm_t, nas_qy) }, \
- { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_nas_tm_t, nas_qz) }, \
- { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_nas_tm_t, nas_qw) }, \
- { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_nas_tm_t, nas_bias_x) }, \
- { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_nas_tm_t, nas_bias_y) }, \
- { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_nas_tm_t, nas_bias_z) }, \
- { "ref_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_nas_tm_t, ref_pressure) }, \
- { "ref_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_nas_tm_t, ref_temperature) }, \
- { "ref_latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_nas_tm_t, ref_latitude) }, \
- { "ref_longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_nas_tm_t, ref_longitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a nas_tm 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] When was this logged
- * @param state NAS current state
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on y axis
- * @param nas_bias_z Navigation system gyroscope bias on z axis
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_temperature [degC] Calibration temperature
- * @param ref_latitude [deg] Calibration latitude
- * @param ref_longitude [deg] Calibration longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_nas_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t state, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float ref_pressure, float ref_temperature, float ref_latitude, float ref_longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NAS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, nas_n);
- _mav_put_float(buf, 12, nas_e);
- _mav_put_float(buf, 16, nas_d);
- _mav_put_float(buf, 20, nas_vn);
- _mav_put_float(buf, 24, nas_ve);
- _mav_put_float(buf, 28, nas_vd);
- _mav_put_float(buf, 32, nas_qx);
- _mav_put_float(buf, 36, nas_qy);
- _mav_put_float(buf, 40, nas_qz);
- _mav_put_float(buf, 44, nas_qw);
- _mav_put_float(buf, 48, nas_bias_x);
- _mav_put_float(buf, 52, nas_bias_y);
- _mav_put_float(buf, 56, nas_bias_z);
- _mav_put_float(buf, 60, ref_pressure);
- _mav_put_float(buf, 64, ref_temperature);
- _mav_put_float(buf, 68, ref_latitude);
- _mav_put_float(buf, 72, ref_longitude);
- _mav_put_uint8_t(buf, 76, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAS_TM_LEN);
-#else
- mavlink_nas_tm_t packet;
- packet.timestamp = timestamp;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.ref_pressure = ref_pressure;
- packet.ref_temperature = ref_temperature;
- packet.ref_latitude = ref_latitude;
- packet.ref_longitude = ref_longitude;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NAS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-}
-
-/**
- * @brief Pack a nas_tm 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] When was this logged
- * @param state NAS current state
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on y axis
- * @param nas_bias_z Navigation system gyroscope bias on z axis
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_temperature [degC] Calibration temperature
- * @param ref_latitude [deg] Calibration latitude
- * @param ref_longitude [deg] Calibration longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_nas_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t state,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,float ref_pressure,float ref_temperature,float ref_latitude,float ref_longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NAS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, nas_n);
- _mav_put_float(buf, 12, nas_e);
- _mav_put_float(buf, 16, nas_d);
- _mav_put_float(buf, 20, nas_vn);
- _mav_put_float(buf, 24, nas_ve);
- _mav_put_float(buf, 28, nas_vd);
- _mav_put_float(buf, 32, nas_qx);
- _mav_put_float(buf, 36, nas_qy);
- _mav_put_float(buf, 40, nas_qz);
- _mav_put_float(buf, 44, nas_qw);
- _mav_put_float(buf, 48, nas_bias_x);
- _mav_put_float(buf, 52, nas_bias_y);
- _mav_put_float(buf, 56, nas_bias_z);
- _mav_put_float(buf, 60, ref_pressure);
- _mav_put_float(buf, 64, ref_temperature);
- _mav_put_float(buf, 68, ref_latitude);
- _mav_put_float(buf, 72, ref_longitude);
- _mav_put_uint8_t(buf, 76, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAS_TM_LEN);
-#else
- mavlink_nas_tm_t packet;
- packet.timestamp = timestamp;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.ref_pressure = ref_pressure;
- packet.ref_temperature = ref_temperature;
- packet.ref_latitude = ref_latitude;
- packet.ref_longitude = ref_longitude;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NAS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-}
-
-/**
- * @brief Encode a nas_tm 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 nas_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_nas_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nas_tm_t* nas_tm)
-{
- return mavlink_msg_nas_tm_pack(system_id, component_id, msg, nas_tm->timestamp, nas_tm->state, nas_tm->nas_n, nas_tm->nas_e, nas_tm->nas_d, nas_tm->nas_vn, nas_tm->nas_ve, nas_tm->nas_vd, nas_tm->nas_qx, nas_tm->nas_qy, nas_tm->nas_qz, nas_tm->nas_qw, nas_tm->nas_bias_x, nas_tm->nas_bias_y, nas_tm->nas_bias_z, nas_tm->ref_pressure, nas_tm->ref_temperature, nas_tm->ref_latitude, nas_tm->ref_longitude);
-}
-
-/**
- * @brief Encode a nas_tm 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 nas_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_nas_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nas_tm_t* nas_tm)
-{
- return mavlink_msg_nas_tm_pack_chan(system_id, component_id, chan, msg, nas_tm->timestamp, nas_tm->state, nas_tm->nas_n, nas_tm->nas_e, nas_tm->nas_d, nas_tm->nas_vn, nas_tm->nas_ve, nas_tm->nas_vd, nas_tm->nas_qx, nas_tm->nas_qy, nas_tm->nas_qz, nas_tm->nas_qw, nas_tm->nas_bias_x, nas_tm->nas_bias_y, nas_tm->nas_bias_z, nas_tm->ref_pressure, nas_tm->ref_temperature, nas_tm->ref_latitude, nas_tm->ref_longitude);
-}
-
-/**
- * @brief Send a nas_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param state NAS current state
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on y axis
- * @param nas_bias_z Navigation system gyroscope bias on z axis
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_temperature [degC] Calibration temperature
- * @param ref_latitude [deg] Calibration latitude
- * @param ref_longitude [deg] Calibration longitude
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_nas_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float ref_pressure, float ref_temperature, float ref_latitude, float ref_longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NAS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, nas_n);
- _mav_put_float(buf, 12, nas_e);
- _mav_put_float(buf, 16, nas_d);
- _mav_put_float(buf, 20, nas_vn);
- _mav_put_float(buf, 24, nas_ve);
- _mav_put_float(buf, 28, nas_vd);
- _mav_put_float(buf, 32, nas_qx);
- _mav_put_float(buf, 36, nas_qy);
- _mav_put_float(buf, 40, nas_qz);
- _mav_put_float(buf, 44, nas_qw);
- _mav_put_float(buf, 48, nas_bias_x);
- _mav_put_float(buf, 52, nas_bias_y);
- _mav_put_float(buf, 56, nas_bias_z);
- _mav_put_float(buf, 60, ref_pressure);
- _mav_put_float(buf, 64, ref_temperature);
- _mav_put_float(buf, 68, ref_latitude);
- _mav_put_float(buf, 72, ref_longitude);
- _mav_put_uint8_t(buf, 76, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAS_TM, buf, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-#else
- mavlink_nas_tm_t packet;
- packet.timestamp = timestamp;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.ref_pressure = ref_pressure;
- packet.ref_temperature = ref_temperature;
- packet.ref_latitude = ref_latitude;
- packet.ref_longitude = ref_longitude;
- packet.state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAS_TM, (const char *)&packet, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a nas_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_nas_tm_send_struct(mavlink_channel_t chan, const mavlink_nas_tm_t* nas_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_nas_tm_send(chan, nas_tm->timestamp, nas_tm->state, nas_tm->nas_n, nas_tm->nas_e, nas_tm->nas_d, nas_tm->nas_vn, nas_tm->nas_ve, nas_tm->nas_vd, nas_tm->nas_qx, nas_tm->nas_qy, nas_tm->nas_qz, nas_tm->nas_qw, nas_tm->nas_bias_x, nas_tm->nas_bias_y, nas_tm->nas_bias_z, nas_tm->ref_pressure, nas_tm->ref_temperature, nas_tm->ref_latitude, nas_tm->ref_longitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAS_TM, (const char *)nas_tm, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_NAS_TM_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_nas_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float ref_pressure, float ref_temperature, float ref_latitude, float ref_longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, nas_n);
- _mav_put_float(buf, 12, nas_e);
- _mav_put_float(buf, 16, nas_d);
- _mav_put_float(buf, 20, nas_vn);
- _mav_put_float(buf, 24, nas_ve);
- _mav_put_float(buf, 28, nas_vd);
- _mav_put_float(buf, 32, nas_qx);
- _mav_put_float(buf, 36, nas_qy);
- _mav_put_float(buf, 40, nas_qz);
- _mav_put_float(buf, 44, nas_qw);
- _mav_put_float(buf, 48, nas_bias_x);
- _mav_put_float(buf, 52, nas_bias_y);
- _mav_put_float(buf, 56, nas_bias_z);
- _mav_put_float(buf, 60, ref_pressure);
- _mav_put_float(buf, 64, ref_temperature);
- _mav_put_float(buf, 68, ref_latitude);
- _mav_put_float(buf, 72, ref_longitude);
- _mav_put_uint8_t(buf, 76, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAS_TM, buf, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-#else
- mavlink_nas_tm_t *packet = (mavlink_nas_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->nas_n = nas_n;
- packet->nas_e = nas_e;
- packet->nas_d = nas_d;
- packet->nas_vn = nas_vn;
- packet->nas_ve = nas_ve;
- packet->nas_vd = nas_vd;
- packet->nas_qx = nas_qx;
- packet->nas_qy = nas_qy;
- packet->nas_qz = nas_qz;
- packet->nas_qw = nas_qw;
- packet->nas_bias_x = nas_bias_x;
- packet->nas_bias_y = nas_bias_y;
- packet->nas_bias_z = nas_bias_z;
- packet->ref_pressure = ref_pressure;
- packet->ref_temperature = ref_temperature;
- packet->ref_latitude = ref_latitude;
- packet->ref_longitude = ref_longitude;
- packet->state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAS_TM, (const char *)packet, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE NAS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from nas_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_nas_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field state from nas_tm message
- *
- * @return NAS current state
- */
-static inline uint8_t mavlink_msg_nas_tm_get_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 76);
-}
-
-/**
- * @brief Get field nas_n from nas_tm message
- *
- * @return [deg] Navigation system estimated noth position
- */
-static inline float mavlink_msg_nas_tm_get_nas_n(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field nas_e from nas_tm message
- *
- * @return [deg] Navigation system estimated east position
- */
-static inline float mavlink_msg_nas_tm_get_nas_e(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field nas_d from nas_tm message
- *
- * @return [m] Navigation system estimated down position
- */
-static inline float mavlink_msg_nas_tm_get_nas_d(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field nas_vn from nas_tm message
- *
- * @return [m/s] Navigation system estimated north velocity
- */
-static inline float mavlink_msg_nas_tm_get_nas_vn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field nas_ve from nas_tm message
- *
- * @return [m/s] Navigation system estimated east velocity
- */
-static inline float mavlink_msg_nas_tm_get_nas_ve(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field nas_vd from nas_tm message
- *
- * @return [m/s] Navigation system estimated down velocity
- */
-static inline float mavlink_msg_nas_tm_get_nas_vd(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field nas_qx from nas_tm message
- *
- * @return [deg] Navigation system estimated attitude (qx)
- */
-static inline float mavlink_msg_nas_tm_get_nas_qx(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field nas_qy from nas_tm message
- *
- * @return [deg] Navigation system estimated attitude (qy)
- */
-static inline float mavlink_msg_nas_tm_get_nas_qy(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field nas_qz from nas_tm message
- *
- * @return [deg] Navigation system estimated attitude (qz)
- */
-static inline float mavlink_msg_nas_tm_get_nas_qz(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field nas_qw from nas_tm message
- *
- * @return [deg] Navigation system estimated attitude (qw)
- */
-static inline float mavlink_msg_nas_tm_get_nas_qw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field nas_bias_x from nas_tm message
- *
- * @return Navigation system gyroscope bias on x axis
- */
-static inline float mavlink_msg_nas_tm_get_nas_bias_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field nas_bias_y from nas_tm message
- *
- * @return Navigation system gyroscope bias on y axis
- */
-static inline float mavlink_msg_nas_tm_get_nas_bias_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field nas_bias_z from nas_tm message
- *
- * @return Navigation system gyroscope bias on z axis
- */
-static inline float mavlink_msg_nas_tm_get_nas_bias_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field ref_pressure from nas_tm message
- *
- * @return [Pa] Calibration pressure
- */
-static inline float mavlink_msg_nas_tm_get_ref_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field ref_temperature from nas_tm message
- *
- * @return [degC] Calibration temperature
- */
-static inline float mavlink_msg_nas_tm_get_ref_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field ref_latitude from nas_tm message
- *
- * @return [deg] Calibration latitude
- */
-static inline float mavlink_msg_nas_tm_get_ref_latitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field ref_longitude from nas_tm message
- *
- * @return [deg] Calibration longitude
- */
-static inline float mavlink_msg_nas_tm_get_ref_longitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 72);
-}
-
-/**
- * @brief Decode a nas_tm message into a struct
- *
- * @param msg The message to decode
- * @param nas_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_nas_tm_decode(const mavlink_message_t* msg, mavlink_nas_tm_t* nas_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- nas_tm->timestamp = mavlink_msg_nas_tm_get_timestamp(msg);
- nas_tm->nas_n = mavlink_msg_nas_tm_get_nas_n(msg);
- nas_tm->nas_e = mavlink_msg_nas_tm_get_nas_e(msg);
- nas_tm->nas_d = mavlink_msg_nas_tm_get_nas_d(msg);
- nas_tm->nas_vn = mavlink_msg_nas_tm_get_nas_vn(msg);
- nas_tm->nas_ve = mavlink_msg_nas_tm_get_nas_ve(msg);
- nas_tm->nas_vd = mavlink_msg_nas_tm_get_nas_vd(msg);
- nas_tm->nas_qx = mavlink_msg_nas_tm_get_nas_qx(msg);
- nas_tm->nas_qy = mavlink_msg_nas_tm_get_nas_qy(msg);
- nas_tm->nas_qz = mavlink_msg_nas_tm_get_nas_qz(msg);
- nas_tm->nas_qw = mavlink_msg_nas_tm_get_nas_qw(msg);
- nas_tm->nas_bias_x = mavlink_msg_nas_tm_get_nas_bias_x(msg);
- nas_tm->nas_bias_y = mavlink_msg_nas_tm_get_nas_bias_y(msg);
- nas_tm->nas_bias_z = mavlink_msg_nas_tm_get_nas_bias_z(msg);
- nas_tm->ref_pressure = mavlink_msg_nas_tm_get_ref_pressure(msg);
- nas_tm->ref_temperature = mavlink_msg_nas_tm_get_ref_temperature(msg);
- nas_tm->ref_latitude = mavlink_msg_nas_tm_get_ref_latitude(msg);
- nas_tm->ref_longitude = mavlink_msg_nas_tm_get_ref_longitude(msg);
- nas_tm->state = mavlink_msg_nas_tm_get_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_NAS_TM_LEN? msg->len : MAVLINK_MSG_ID_NAS_TM_LEN;
- memset(nas_tm, 0, MAVLINK_MSG_ID_NAS_TM_LEN);
- memcpy(nas_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_payload_flight_tm.h b/mavlink_lib/lyra/mavlink_msg_payload_flight_tm.h
deleted file mode 100644
index bfe077c3582106f59cfe4d17c86e22f178d0d299..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_payload_flight_tm.h
+++ /dev/null
@@ -1,1313 +0,0 @@
-#pragma once
-// MESSAGE PAYLOAD_FLIGHT_TM PACKING
-
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM 209
-
-
-typedef struct __mavlink_payload_flight_tm_t {
- uint64_t timestamp; /*< [us] Timestamp in microseconds*/
- float pressure_digi; /*< [Pa] Pressure from digital sensor*/
- float pressure_static; /*< [Pa] Pressure from static port*/
- float airspeed_pitot; /*< [m/s] Pitot airspeed*/
- float altitude_agl; /*< [m] Altitude above ground level*/
- float acc_x; /*< [m/s^2] Acceleration on X axis (body)*/
- float acc_y; /*< [m/s^2] Acceleration on Y axis (body)*/
- float acc_z; /*< [m/s^2] Acceleration on Z axis (body)*/
- float gyro_x; /*< [rad/s] Angular speed on X axis (body)*/
- float gyro_y; /*< [rad/s] Angular speed on Y axis (body)*/
- float gyro_z; /*< [rad/s] Angular speed on Z axis (body)*/
- float mag_x; /*< [uT] Magnetic field on X axis (body)*/
- float mag_y; /*< [uT] Magnetic field on Y axis (body)*/
- float mag_z; /*< [uT] Magnetic field on Z axis (body)*/
- float gps_lat; /*< [deg] Latitude*/
- float gps_lon; /*< [deg] Longitude*/
- float gps_alt; /*< [m] GPS Altitude*/
- float left_servo_angle; /*< [deg] Left servo motor angle*/
- float right_servo_angle; /*< [deg] Right servo motor angle*/
- float nas_n; /*< [deg] Navigation system estimated noth position*/
- float nas_e; /*< [deg] Navigation system estimated east position*/
- float nas_d; /*< [m] Navigation system estimated down position*/
- float nas_vn; /*< [m/s] Navigation system estimated north velocity*/
- float nas_ve; /*< [m/s] Navigation system estimated east velocity*/
- float nas_vd; /*< [m/s] Navigation system estimated down velocity*/
- float nas_qx; /*< [deg] Navigation system estimated attitude (qx)*/
- float nas_qy; /*< [deg] Navigation system estimated attitude (qy)*/
- float nas_qz; /*< [deg] Navigation system estimated attitude (qz)*/
- float nas_qw; /*< [deg] Navigation system estimated attitude (qw)*/
- float nas_bias_x; /*< Navigation system gyroscope bias on x axis*/
- float nas_bias_y; /*< Navigation system gyroscope bias on y axis*/
- float nas_bias_z; /*< Navigation system gyroscope bias on z axis*/
- float wes_n; /*< [m/s] Wind estimated north velocity*/
- float wes_e; /*< [m/s] Wind estimated east velocity*/
- float battery_voltage; /*< [V] Battery voltage*/
- float cam_battery_voltage; /*< [V] Camera battery voltage*/
- float current_consumption; /*< [A] Battery current*/
- float temperature; /*< [degC] Temperature*/
- uint8_t fmm_state; /*< Flight Mode Manager State*/
- uint8_t nas_state; /*< Navigation System FSM State*/
- uint8_t wes_state; /*< Wind Estimation System FSM State*/
- uint8_t gps_fix; /*< GPS fix (1 = fix, 0 = no fix)*/
- uint8_t pin_nosecone; /*< Nosecone pin status (1 = connected, 0 = disconnected)*/
- uint8_t cutter_presence; /*< Cutter presence status (1 = present, 0 = missing)*/
- int8_t logger_error; /*< Logger error (0 = no error)*/
-} mavlink_payload_flight_tm_t;
-
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN 163
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN 163
-#define MAVLINK_MSG_ID_209_LEN 163
-#define MAVLINK_MSG_ID_209_MIN_LEN 163
-
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC 84
-#define MAVLINK_MSG_ID_209_CRC 84
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM { \
- 209, \
- "PAYLOAD_FLIGHT_TM", \
- 45, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_flight_tm_t, timestamp) }, \
- { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \
- { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_payload_flight_tm_t, nas_state) }, \
- { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_payload_flight_tm_t, wes_state) }, \
- { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_payload_flight_tm_t, pressure_digi) }, \
- { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_payload_flight_tm_t, pressure_static) }, \
- { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_payload_flight_tm_t, airspeed_pitot) }, \
- { "altitude_agl", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_payload_flight_tm_t, altitude_agl) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_payload_flight_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_payload_flight_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_payload_flight_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_payload_flight_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_payload_flight_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_payload_flight_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_payload_flight_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_payload_flight_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_payload_flight_tm_t, mag_z) }, \
- { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \
- { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_flight_tm_t, gps_lat) }, \
- { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_flight_tm_t, gps_lon) }, \
- { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_flight_tm_t, gps_alt) }, \
- { "left_servo_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_payload_flight_tm_t, left_servo_angle) }, \
- { "right_servo_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_payload_flight_tm_t, right_servo_angle) }, \
- { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_payload_flight_tm_t, nas_n) }, \
- { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_payload_flight_tm_t, nas_e) }, \
- { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_payload_flight_tm_t, nas_d) }, \
- { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_payload_flight_tm_t, nas_vn) }, \
- { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_payload_flight_tm_t, nas_ve) }, \
- { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_payload_flight_tm_t, nas_vd) }, \
- { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_payload_flight_tm_t, nas_qx) }, \
- { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_payload_flight_tm_t, nas_qy) }, \
- { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_payload_flight_tm_t, nas_qz) }, \
- { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_payload_flight_tm_t, nas_qw) }, \
- { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_payload_flight_tm_t, nas_bias_x) }, \
- { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_payload_flight_tm_t, nas_bias_y) }, \
- { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_payload_flight_tm_t, nas_bias_z) }, \
- { "wes_n", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_payload_flight_tm_t, wes_n) }, \
- { "wes_e", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_payload_flight_tm_t, wes_e) }, \
- { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_payload_flight_tm_t, battery_voltage) }, \
- { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_flight_tm_t, cam_battery_voltage) }, \
- { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, current_consumption) }, \
- { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_payload_flight_tm_t, cutter_presence) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
- { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 162, offsetof(mavlink_payload_flight_tm_t, logger_error) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM { \
- "PAYLOAD_FLIGHT_TM", \
- 45, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_flight_tm_t, timestamp) }, \
- { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \
- { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_payload_flight_tm_t, nas_state) }, \
- { "wes_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_payload_flight_tm_t, wes_state) }, \
- { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_payload_flight_tm_t, pressure_digi) }, \
- { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_payload_flight_tm_t, pressure_static) }, \
- { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_payload_flight_tm_t, airspeed_pitot) }, \
- { "altitude_agl", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_payload_flight_tm_t, altitude_agl) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_payload_flight_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_payload_flight_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_payload_flight_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_payload_flight_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_payload_flight_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_payload_flight_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_payload_flight_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_payload_flight_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_payload_flight_tm_t, mag_z) }, \
- { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \
- { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_flight_tm_t, gps_lat) }, \
- { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_flight_tm_t, gps_lon) }, \
- { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_flight_tm_t, gps_alt) }, \
- { "left_servo_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_payload_flight_tm_t, left_servo_angle) }, \
- { "right_servo_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_payload_flight_tm_t, right_servo_angle) }, \
- { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_payload_flight_tm_t, nas_n) }, \
- { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_payload_flight_tm_t, nas_e) }, \
- { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_payload_flight_tm_t, nas_d) }, \
- { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_payload_flight_tm_t, nas_vn) }, \
- { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_payload_flight_tm_t, nas_ve) }, \
- { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_payload_flight_tm_t, nas_vd) }, \
- { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_payload_flight_tm_t, nas_qx) }, \
- { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_payload_flight_tm_t, nas_qy) }, \
- { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_payload_flight_tm_t, nas_qz) }, \
- { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_payload_flight_tm_t, nas_qw) }, \
- { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_payload_flight_tm_t, nas_bias_x) }, \
- { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_payload_flight_tm_t, nas_bias_y) }, \
- { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_payload_flight_tm_t, nas_bias_z) }, \
- { "wes_n", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_payload_flight_tm_t, wes_n) }, \
- { "wes_e", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_payload_flight_tm_t, wes_e) }, \
- { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_payload_flight_tm_t, battery_voltage) }, \
- { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_flight_tm_t, cam_battery_voltage) }, \
- { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, current_consumption) }, \
- { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_payload_flight_tm_t, cutter_presence) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
- { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 162, offsetof(mavlink_payload_flight_tm_t, logger_error) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a payload_flight_tm 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 in microseconds
- * @param fmm_state Flight Mode Manager State
- * @param nas_state Navigation System FSM State
- * @param wes_state Wind Estimation System FSM State
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param altitude_agl [m] Altitude above ground level
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param left_servo_angle [deg] Left servo motor angle
- * @param right_servo_angle [deg] Right servo motor angle
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on y axis
- * @param nas_bias_z Navigation system gyroscope bias on z axis
- * @param wes_n [m/s] Wind estimated north velocity
- * @param wes_e [m/s] Wind estimated east velocity
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param battery_voltage [V] Battery voltage
- * @param cam_battery_voltage [V] Camera battery voltage
- * @param current_consumption [A] Battery current
- * @param cutter_presence Cutter presence status (1 = present, 0 = missing)
- * @param temperature [degC] Temperature
- * @param logger_error Logger error (0 = no error)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float battery_voltage, float cam_battery_voltage, float current_consumption, uint8_t cutter_presence, float temperature, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_digi);
- _mav_put_float(buf, 12, pressure_static);
- _mav_put_float(buf, 16, airspeed_pitot);
- _mav_put_float(buf, 20, altitude_agl);
- _mav_put_float(buf, 24, acc_x);
- _mav_put_float(buf, 28, acc_y);
- _mav_put_float(buf, 32, acc_z);
- _mav_put_float(buf, 36, gyro_x);
- _mav_put_float(buf, 40, gyro_y);
- _mav_put_float(buf, 44, gyro_z);
- _mav_put_float(buf, 48, mag_x);
- _mav_put_float(buf, 52, mag_y);
- _mav_put_float(buf, 56, mag_z);
- _mav_put_float(buf, 60, gps_lat);
- _mav_put_float(buf, 64, gps_lon);
- _mav_put_float(buf, 68, gps_alt);
- _mav_put_float(buf, 72, left_servo_angle);
- _mav_put_float(buf, 76, right_servo_angle);
- _mav_put_float(buf, 80, nas_n);
- _mav_put_float(buf, 84, nas_e);
- _mav_put_float(buf, 88, nas_d);
- _mav_put_float(buf, 92, nas_vn);
- _mav_put_float(buf, 96, nas_ve);
- _mav_put_float(buf, 100, nas_vd);
- _mav_put_float(buf, 104, nas_qx);
- _mav_put_float(buf, 108, nas_qy);
- _mav_put_float(buf, 112, nas_qz);
- _mav_put_float(buf, 116, nas_qw);
- _mav_put_float(buf, 120, nas_bias_x);
- _mav_put_float(buf, 124, nas_bias_y);
- _mav_put_float(buf, 128, nas_bias_z);
- _mav_put_float(buf, 132, wes_n);
- _mav_put_float(buf, 136, wes_e);
- _mav_put_float(buf, 140, battery_voltage);
- _mav_put_float(buf, 144, cam_battery_voltage);
- _mav_put_float(buf, 148, current_consumption);
- _mav_put_float(buf, 152, temperature);
- _mav_put_uint8_t(buf, 156, fmm_state);
- _mav_put_uint8_t(buf, 157, nas_state);
- _mav_put_uint8_t(buf, 158, wes_state);
- _mav_put_uint8_t(buf, 159, gps_fix);
- _mav_put_uint8_t(buf, 160, pin_nosecone);
- _mav_put_uint8_t(buf, 161, cutter_presence);
- _mav_put_int8_t(buf, 162, logger_error);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
-#else
- mavlink_payload_flight_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.airspeed_pitot = airspeed_pitot;
- packet.altitude_agl = altitude_agl;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.left_servo_angle = left_servo_angle;
- packet.right_servo_angle = right_servo_angle;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.wes_n = wes_n;
- packet.wes_e = wes_e;
- packet.battery_voltage = battery_voltage;
- packet.cam_battery_voltage = cam_battery_voltage;
- packet.current_consumption = current_consumption;
- packet.temperature = temperature;
- packet.fmm_state = fmm_state;
- packet.nas_state = nas_state;
- packet.wes_state = wes_state;
- packet.gps_fix = gps_fix;
- packet.pin_nosecone = pin_nosecone;
- packet.cutter_presence = cutter_presence;
- packet.logger_error = logger_error;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-}
-
-/**
- * @brief Pack a payload_flight_tm 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 in microseconds
- * @param fmm_state Flight Mode Manager State
- * @param nas_state Navigation System FSM State
- * @param wes_state Wind Estimation System FSM State
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param altitude_agl [m] Altitude above ground level
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param left_servo_angle [deg] Left servo motor angle
- * @param right_servo_angle [deg] Right servo motor angle
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on y axis
- * @param nas_bias_z Navigation system gyroscope bias on z axis
- * @param wes_n [m/s] Wind estimated north velocity
- * @param wes_e [m/s] Wind estimated east velocity
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param battery_voltage [V] Battery voltage
- * @param cam_battery_voltage [V] Camera battery voltage
- * @param current_consumption [A] Battery current
- * @param cutter_presence Cutter presence status (1 = present, 0 = missing)
- * @param temperature [degC] Temperature
- * @param logger_error Logger error (0 = no error)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_payload_flight_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t fmm_state,uint8_t nas_state,uint8_t wes_state,float pressure_digi,float pressure_static,float airspeed_pitot,float altitude_agl,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float left_servo_angle,float right_servo_angle,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,float wes_n,float wes_e,uint8_t pin_nosecone,float battery_voltage,float cam_battery_voltage,float current_consumption,uint8_t cutter_presence,float temperature,int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_digi);
- _mav_put_float(buf, 12, pressure_static);
- _mav_put_float(buf, 16, airspeed_pitot);
- _mav_put_float(buf, 20, altitude_agl);
- _mav_put_float(buf, 24, acc_x);
- _mav_put_float(buf, 28, acc_y);
- _mav_put_float(buf, 32, acc_z);
- _mav_put_float(buf, 36, gyro_x);
- _mav_put_float(buf, 40, gyro_y);
- _mav_put_float(buf, 44, gyro_z);
- _mav_put_float(buf, 48, mag_x);
- _mav_put_float(buf, 52, mag_y);
- _mav_put_float(buf, 56, mag_z);
- _mav_put_float(buf, 60, gps_lat);
- _mav_put_float(buf, 64, gps_lon);
- _mav_put_float(buf, 68, gps_alt);
- _mav_put_float(buf, 72, left_servo_angle);
- _mav_put_float(buf, 76, right_servo_angle);
- _mav_put_float(buf, 80, nas_n);
- _mav_put_float(buf, 84, nas_e);
- _mav_put_float(buf, 88, nas_d);
- _mav_put_float(buf, 92, nas_vn);
- _mav_put_float(buf, 96, nas_ve);
- _mav_put_float(buf, 100, nas_vd);
- _mav_put_float(buf, 104, nas_qx);
- _mav_put_float(buf, 108, nas_qy);
- _mav_put_float(buf, 112, nas_qz);
- _mav_put_float(buf, 116, nas_qw);
- _mav_put_float(buf, 120, nas_bias_x);
- _mav_put_float(buf, 124, nas_bias_y);
- _mav_put_float(buf, 128, nas_bias_z);
- _mav_put_float(buf, 132, wes_n);
- _mav_put_float(buf, 136, wes_e);
- _mav_put_float(buf, 140, battery_voltage);
- _mav_put_float(buf, 144, cam_battery_voltage);
- _mav_put_float(buf, 148, current_consumption);
- _mav_put_float(buf, 152, temperature);
- _mav_put_uint8_t(buf, 156, fmm_state);
- _mav_put_uint8_t(buf, 157, nas_state);
- _mav_put_uint8_t(buf, 158, wes_state);
- _mav_put_uint8_t(buf, 159, gps_fix);
- _mav_put_uint8_t(buf, 160, pin_nosecone);
- _mav_put_uint8_t(buf, 161, cutter_presence);
- _mav_put_int8_t(buf, 162, logger_error);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
-#else
- mavlink_payload_flight_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.airspeed_pitot = airspeed_pitot;
- packet.altitude_agl = altitude_agl;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.left_servo_angle = left_servo_angle;
- packet.right_servo_angle = right_servo_angle;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.wes_n = wes_n;
- packet.wes_e = wes_e;
- packet.battery_voltage = battery_voltage;
- packet.cam_battery_voltage = cam_battery_voltage;
- packet.current_consumption = current_consumption;
- packet.temperature = temperature;
- packet.fmm_state = fmm_state;
- packet.nas_state = nas_state;
- packet.wes_state = wes_state;
- packet.gps_fix = gps_fix;
- packet.pin_nosecone = pin_nosecone;
- packet.cutter_presence = cutter_presence;
- packet.logger_error = logger_error;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-}
-
-/**
- * @brief Encode a payload_flight_tm 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 payload_flight_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_payload_flight_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_payload_flight_tm_t* payload_flight_tm)
-{
- return mavlink_msg_payload_flight_tm_pack(system_id, component_id, msg, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->current_consumption, payload_flight_tm->cutter_presence, payload_flight_tm->temperature, payload_flight_tm->logger_error);
-}
-
-/**
- * @brief Encode a payload_flight_tm 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 payload_flight_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_payload_flight_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_payload_flight_tm_t* payload_flight_tm)
-{
- return mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, chan, msg, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->current_consumption, payload_flight_tm->cutter_presence, payload_flight_tm->temperature, payload_flight_tm->logger_error);
-}
-
-/**
- * @brief Send a payload_flight_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp in microseconds
- * @param fmm_state Flight Mode Manager State
- * @param nas_state Navigation System FSM State
- * @param wes_state Wind Estimation System FSM State
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param altitude_agl [m] Altitude above ground level
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param left_servo_angle [deg] Left servo motor angle
- * @param right_servo_angle [deg] Right servo motor angle
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on y axis
- * @param nas_bias_z Navigation system gyroscope bias on z axis
- * @param wes_n [m/s] Wind estimated north velocity
- * @param wes_e [m/s] Wind estimated east velocity
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param battery_voltage [V] Battery voltage
- * @param cam_battery_voltage [V] Camera battery voltage
- * @param current_consumption [A] Battery current
- * @param cutter_presence Cutter presence status (1 = present, 0 = missing)
- * @param temperature [degC] Temperature
- * @param logger_error Logger error (0 = no error)
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float battery_voltage, float cam_battery_voltage, float current_consumption, uint8_t cutter_presence, float temperature, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_digi);
- _mav_put_float(buf, 12, pressure_static);
- _mav_put_float(buf, 16, airspeed_pitot);
- _mav_put_float(buf, 20, altitude_agl);
- _mav_put_float(buf, 24, acc_x);
- _mav_put_float(buf, 28, acc_y);
- _mav_put_float(buf, 32, acc_z);
- _mav_put_float(buf, 36, gyro_x);
- _mav_put_float(buf, 40, gyro_y);
- _mav_put_float(buf, 44, gyro_z);
- _mav_put_float(buf, 48, mag_x);
- _mav_put_float(buf, 52, mag_y);
- _mav_put_float(buf, 56, mag_z);
- _mav_put_float(buf, 60, gps_lat);
- _mav_put_float(buf, 64, gps_lon);
- _mav_put_float(buf, 68, gps_alt);
- _mav_put_float(buf, 72, left_servo_angle);
- _mav_put_float(buf, 76, right_servo_angle);
- _mav_put_float(buf, 80, nas_n);
- _mav_put_float(buf, 84, nas_e);
- _mav_put_float(buf, 88, nas_d);
- _mav_put_float(buf, 92, nas_vn);
- _mav_put_float(buf, 96, nas_ve);
- _mav_put_float(buf, 100, nas_vd);
- _mav_put_float(buf, 104, nas_qx);
- _mav_put_float(buf, 108, nas_qy);
- _mav_put_float(buf, 112, nas_qz);
- _mav_put_float(buf, 116, nas_qw);
- _mav_put_float(buf, 120, nas_bias_x);
- _mav_put_float(buf, 124, nas_bias_y);
- _mav_put_float(buf, 128, nas_bias_z);
- _mav_put_float(buf, 132, wes_n);
- _mav_put_float(buf, 136, wes_e);
- _mav_put_float(buf, 140, battery_voltage);
- _mav_put_float(buf, 144, cam_battery_voltage);
- _mav_put_float(buf, 148, current_consumption);
- _mav_put_float(buf, 152, temperature);
- _mav_put_uint8_t(buf, 156, fmm_state);
- _mav_put_uint8_t(buf, 157, nas_state);
- _mav_put_uint8_t(buf, 158, wes_state);
- _mav_put_uint8_t(buf, 159, gps_fix);
- _mav_put_uint8_t(buf, 160, pin_nosecone);
- _mav_put_uint8_t(buf, 161, cutter_presence);
- _mav_put_int8_t(buf, 162, logger_error);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-#else
- mavlink_payload_flight_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.airspeed_pitot = airspeed_pitot;
- packet.altitude_agl = altitude_agl;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.left_servo_angle = left_servo_angle;
- packet.right_servo_angle = right_servo_angle;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.wes_n = wes_n;
- packet.wes_e = wes_e;
- packet.battery_voltage = battery_voltage;
- packet.cam_battery_voltage = cam_battery_voltage;
- packet.current_consumption = current_consumption;
- packet.temperature = temperature;
- packet.fmm_state = fmm_state;
- packet.nas_state = nas_state;
- packet.wes_state = wes_state;
- packet.gps_fix = gps_fix;
- packet.pin_nosecone = pin_nosecone;
- packet.cutter_presence = cutter_presence;
- packet.logger_error = logger_error;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, (const char *)&packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a payload_flight_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_payload_flight_tm_send_struct(mavlink_channel_t chan, const mavlink_payload_flight_tm_t* payload_flight_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_payload_flight_tm_send(chan, payload_flight_tm->timestamp, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->wes_state, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->wes_n, payload_flight_tm->wes_e, payload_flight_tm->pin_nosecone, payload_flight_tm->battery_voltage, payload_flight_tm->cam_battery_voltage, payload_flight_tm->current_consumption, payload_flight_tm->cutter_presence, payload_flight_tm->temperature, payload_flight_tm->logger_error);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, (const char *)payload_flight_tm, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_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_payload_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t fmm_state, uint8_t nas_state, uint8_t wes_state, float pressure_digi, float pressure_static, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float wes_n, float wes_e, uint8_t pin_nosecone, float battery_voltage, float cam_battery_voltage, float current_consumption, uint8_t cutter_presence, float temperature, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_digi);
- _mav_put_float(buf, 12, pressure_static);
- _mav_put_float(buf, 16, airspeed_pitot);
- _mav_put_float(buf, 20, altitude_agl);
- _mav_put_float(buf, 24, acc_x);
- _mav_put_float(buf, 28, acc_y);
- _mav_put_float(buf, 32, acc_z);
- _mav_put_float(buf, 36, gyro_x);
- _mav_put_float(buf, 40, gyro_y);
- _mav_put_float(buf, 44, gyro_z);
- _mav_put_float(buf, 48, mag_x);
- _mav_put_float(buf, 52, mag_y);
- _mav_put_float(buf, 56, mag_z);
- _mav_put_float(buf, 60, gps_lat);
- _mav_put_float(buf, 64, gps_lon);
- _mav_put_float(buf, 68, gps_alt);
- _mav_put_float(buf, 72, left_servo_angle);
- _mav_put_float(buf, 76, right_servo_angle);
- _mav_put_float(buf, 80, nas_n);
- _mav_put_float(buf, 84, nas_e);
- _mav_put_float(buf, 88, nas_d);
- _mav_put_float(buf, 92, nas_vn);
- _mav_put_float(buf, 96, nas_ve);
- _mav_put_float(buf, 100, nas_vd);
- _mav_put_float(buf, 104, nas_qx);
- _mav_put_float(buf, 108, nas_qy);
- _mav_put_float(buf, 112, nas_qz);
- _mav_put_float(buf, 116, nas_qw);
- _mav_put_float(buf, 120, nas_bias_x);
- _mav_put_float(buf, 124, nas_bias_y);
- _mav_put_float(buf, 128, nas_bias_z);
- _mav_put_float(buf, 132, wes_n);
- _mav_put_float(buf, 136, wes_e);
- _mav_put_float(buf, 140, battery_voltage);
- _mav_put_float(buf, 144, cam_battery_voltage);
- _mav_put_float(buf, 148, current_consumption);
- _mav_put_float(buf, 152, temperature);
- _mav_put_uint8_t(buf, 156, fmm_state);
- _mav_put_uint8_t(buf, 157, nas_state);
- _mav_put_uint8_t(buf, 158, wes_state);
- _mav_put_uint8_t(buf, 159, gps_fix);
- _mav_put_uint8_t(buf, 160, pin_nosecone);
- _mav_put_uint8_t(buf, 161, cutter_presence);
- _mav_put_int8_t(buf, 162, logger_error);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-#else
- mavlink_payload_flight_tm_t *packet = (mavlink_payload_flight_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->pressure_digi = pressure_digi;
- packet->pressure_static = pressure_static;
- packet->airspeed_pitot = airspeed_pitot;
- packet->altitude_agl = altitude_agl;
- packet->acc_x = acc_x;
- packet->acc_y = acc_y;
- packet->acc_z = acc_z;
- packet->gyro_x = gyro_x;
- packet->gyro_y = gyro_y;
- packet->gyro_z = gyro_z;
- packet->mag_x = mag_x;
- packet->mag_y = mag_y;
- packet->mag_z = mag_z;
- packet->gps_lat = gps_lat;
- packet->gps_lon = gps_lon;
- packet->gps_alt = gps_alt;
- packet->left_servo_angle = left_servo_angle;
- packet->right_servo_angle = right_servo_angle;
- packet->nas_n = nas_n;
- packet->nas_e = nas_e;
- packet->nas_d = nas_d;
- packet->nas_vn = nas_vn;
- packet->nas_ve = nas_ve;
- packet->nas_vd = nas_vd;
- packet->nas_qx = nas_qx;
- packet->nas_qy = nas_qy;
- packet->nas_qz = nas_qz;
- packet->nas_qw = nas_qw;
- packet->nas_bias_x = nas_bias_x;
- packet->nas_bias_y = nas_bias_y;
- packet->nas_bias_z = nas_bias_z;
- packet->wes_n = wes_n;
- packet->wes_e = wes_e;
- packet->battery_voltage = battery_voltage;
- packet->cam_battery_voltage = cam_battery_voltage;
- packet->current_consumption = current_consumption;
- packet->temperature = temperature;
- packet->fmm_state = fmm_state;
- packet->nas_state = nas_state;
- packet->wes_state = wes_state;
- packet->gps_fix = gps_fix;
- packet->pin_nosecone = pin_nosecone;
- packet->cutter_presence = cutter_presence;
- packet->logger_error = logger_error;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, (const char *)packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE PAYLOAD_FLIGHT_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from payload_flight_tm message
- *
- * @return [us] Timestamp in microseconds
- */
-static inline uint64_t mavlink_msg_payload_flight_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field fmm_state from payload_flight_tm message
- *
- * @return Flight Mode Manager State
- */
-static inline uint8_t mavlink_msg_payload_flight_tm_get_fmm_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 156);
-}
-
-/**
- * @brief Get field nas_state from payload_flight_tm message
- *
- * @return Navigation System FSM State
- */
-static inline uint8_t mavlink_msg_payload_flight_tm_get_nas_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 157);
-}
-
-/**
- * @brief Get field wes_state from payload_flight_tm message
- *
- * @return Wind Estimation System FSM State
- */
-static inline uint8_t mavlink_msg_payload_flight_tm_get_wes_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 158);
-}
-
-/**
- * @brief Get field pressure_digi from payload_flight_tm message
- *
- * @return [Pa] Pressure from digital sensor
- */
-static inline float mavlink_msg_payload_flight_tm_get_pressure_digi(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field pressure_static from payload_flight_tm message
- *
- * @return [Pa] Pressure from static port
- */
-static inline float mavlink_msg_payload_flight_tm_get_pressure_static(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field airspeed_pitot from payload_flight_tm message
- *
- * @return [m/s] Pitot airspeed
- */
-static inline float mavlink_msg_payload_flight_tm_get_airspeed_pitot(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field altitude_agl from payload_flight_tm message
- *
- * @return [m] Altitude above ground level
- */
-static inline float mavlink_msg_payload_flight_tm_get_altitude_agl(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field acc_x from payload_flight_tm message
- *
- * @return [m/s^2] Acceleration on X axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_acc_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field acc_y from payload_flight_tm message
- *
- * @return [m/s^2] Acceleration on Y axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_acc_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field acc_z from payload_flight_tm message
- *
- * @return [m/s^2] Acceleration on Z axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_acc_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field gyro_x from payload_flight_tm message
- *
- * @return [rad/s] Angular speed on X axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_gyro_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field gyro_y from payload_flight_tm message
- *
- * @return [rad/s] Angular speed on Y axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_gyro_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field gyro_z from payload_flight_tm message
- *
- * @return [rad/s] Angular speed on Z axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_gyro_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field mag_x from payload_flight_tm message
- *
- * @return [uT] Magnetic field on X axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_mag_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field mag_y from payload_flight_tm message
- *
- * @return [uT] Magnetic field on Y axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_mag_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field mag_z from payload_flight_tm message
- *
- * @return [uT] Magnetic field on Z axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_mag_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field gps_fix from payload_flight_tm message
- *
- * @return GPS fix (1 = fix, 0 = no fix)
- */
-static inline uint8_t mavlink_msg_payload_flight_tm_get_gps_fix(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 159);
-}
-
-/**
- * @brief Get field gps_lat from payload_flight_tm message
- *
- * @return [deg] Latitude
- */
-static inline float mavlink_msg_payload_flight_tm_get_gps_lat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field gps_lon from payload_flight_tm message
- *
- * @return [deg] Longitude
- */
-static inline float mavlink_msg_payload_flight_tm_get_gps_lon(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field gps_alt from payload_flight_tm message
- *
- * @return [m] GPS Altitude
- */
-static inline float mavlink_msg_payload_flight_tm_get_gps_alt(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field left_servo_angle from payload_flight_tm message
- *
- * @return [deg] Left servo motor angle
- */
-static inline float mavlink_msg_payload_flight_tm_get_left_servo_angle(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 72);
-}
-
-/**
- * @brief Get field right_servo_angle from payload_flight_tm message
- *
- * @return [deg] Right servo motor angle
- */
-static inline float mavlink_msg_payload_flight_tm_get_right_servo_angle(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 76);
-}
-
-/**
- * @brief Get field nas_n from payload_flight_tm message
- *
- * @return [deg] Navigation system estimated noth position
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_n(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 80);
-}
-
-/**
- * @brief Get field nas_e from payload_flight_tm message
- *
- * @return [deg] Navigation system estimated east position
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_e(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 84);
-}
-
-/**
- * @brief Get field nas_d from payload_flight_tm message
- *
- * @return [m] Navigation system estimated down position
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_d(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 88);
-}
-
-/**
- * @brief Get field nas_vn from payload_flight_tm message
- *
- * @return [m/s] Navigation system estimated north velocity
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_vn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 92);
-}
-
-/**
- * @brief Get field nas_ve from payload_flight_tm message
- *
- * @return [m/s] Navigation system estimated east velocity
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_ve(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 96);
-}
-
-/**
- * @brief Get field nas_vd from payload_flight_tm message
- *
- * @return [m/s] Navigation system estimated down velocity
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_vd(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 100);
-}
-
-/**
- * @brief Get field nas_qx from payload_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qx)
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_qx(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 104);
-}
-
-/**
- * @brief Get field nas_qy from payload_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qy)
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_qy(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 108);
-}
-
-/**
- * @brief Get field nas_qz from payload_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qz)
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_qz(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 112);
-}
-
-/**
- * @brief Get field nas_qw from payload_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qw)
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_qw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 116);
-}
-
-/**
- * @brief Get field nas_bias_x from payload_flight_tm message
- *
- * @return Navigation system gyroscope bias on x axis
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_bias_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 120);
-}
-
-/**
- * @brief Get field nas_bias_y from payload_flight_tm message
- *
- * @return Navigation system gyroscope bias on y axis
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_bias_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 124);
-}
-
-/**
- * @brief Get field nas_bias_z from payload_flight_tm message
- *
- * @return Navigation system gyroscope bias on z axis
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_bias_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 128);
-}
-
-/**
- * @brief Get field wes_n from payload_flight_tm message
- *
- * @return [m/s] Wind estimated north velocity
- */
-static inline float mavlink_msg_payload_flight_tm_get_wes_n(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 132);
-}
-
-/**
- * @brief Get field wes_e from payload_flight_tm message
- *
- * @return [m/s] Wind estimated east velocity
- */
-static inline float mavlink_msg_payload_flight_tm_get_wes_e(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 136);
-}
-
-/**
- * @brief Get field pin_nosecone from payload_flight_tm message
- *
- * @return Nosecone pin status (1 = connected, 0 = disconnected)
- */
-static inline uint8_t mavlink_msg_payload_flight_tm_get_pin_nosecone(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 160);
-}
-
-/**
- * @brief Get field battery_voltage from payload_flight_tm message
- *
- * @return [V] Battery voltage
- */
-static inline float mavlink_msg_payload_flight_tm_get_battery_voltage(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 140);
-}
-
-/**
- * @brief Get field cam_battery_voltage from payload_flight_tm message
- *
- * @return [V] Camera battery voltage
- */
-static inline float mavlink_msg_payload_flight_tm_get_cam_battery_voltage(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 144);
-}
-
-/**
- * @brief Get field current_consumption from payload_flight_tm message
- *
- * @return [A] Battery current
- */
-static inline float mavlink_msg_payload_flight_tm_get_current_consumption(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 148);
-}
-
-/**
- * @brief Get field cutter_presence from payload_flight_tm message
- *
- * @return Cutter presence status (1 = present, 0 = missing)
- */
-static inline uint8_t mavlink_msg_payload_flight_tm_get_cutter_presence(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 161);
-}
-
-/**
- * @brief Get field temperature from payload_flight_tm message
- *
- * @return [degC] Temperature
- */
-static inline float mavlink_msg_payload_flight_tm_get_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 152);
-}
-
-/**
- * @brief Get field logger_error from payload_flight_tm message
- *
- * @return Logger error (0 = no error)
- */
-static inline int8_t mavlink_msg_payload_flight_tm_get_logger_error(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int8_t(msg, 162);
-}
-
-/**
- * @brief Decode a payload_flight_tm message into a struct
- *
- * @param msg The message to decode
- * @param payload_flight_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_payload_flight_tm_decode(const mavlink_message_t* msg, mavlink_payload_flight_tm_t* payload_flight_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- payload_flight_tm->timestamp = mavlink_msg_payload_flight_tm_get_timestamp(msg);
- payload_flight_tm->pressure_digi = mavlink_msg_payload_flight_tm_get_pressure_digi(msg);
- payload_flight_tm->pressure_static = mavlink_msg_payload_flight_tm_get_pressure_static(msg);
- payload_flight_tm->airspeed_pitot = mavlink_msg_payload_flight_tm_get_airspeed_pitot(msg);
- payload_flight_tm->altitude_agl = mavlink_msg_payload_flight_tm_get_altitude_agl(msg);
- payload_flight_tm->acc_x = mavlink_msg_payload_flight_tm_get_acc_x(msg);
- payload_flight_tm->acc_y = mavlink_msg_payload_flight_tm_get_acc_y(msg);
- payload_flight_tm->acc_z = mavlink_msg_payload_flight_tm_get_acc_z(msg);
- payload_flight_tm->gyro_x = mavlink_msg_payload_flight_tm_get_gyro_x(msg);
- payload_flight_tm->gyro_y = mavlink_msg_payload_flight_tm_get_gyro_y(msg);
- payload_flight_tm->gyro_z = mavlink_msg_payload_flight_tm_get_gyro_z(msg);
- payload_flight_tm->mag_x = mavlink_msg_payload_flight_tm_get_mag_x(msg);
- payload_flight_tm->mag_y = mavlink_msg_payload_flight_tm_get_mag_y(msg);
- payload_flight_tm->mag_z = mavlink_msg_payload_flight_tm_get_mag_z(msg);
- payload_flight_tm->gps_lat = mavlink_msg_payload_flight_tm_get_gps_lat(msg);
- payload_flight_tm->gps_lon = mavlink_msg_payload_flight_tm_get_gps_lon(msg);
- payload_flight_tm->gps_alt = mavlink_msg_payload_flight_tm_get_gps_alt(msg);
- payload_flight_tm->left_servo_angle = mavlink_msg_payload_flight_tm_get_left_servo_angle(msg);
- payload_flight_tm->right_servo_angle = mavlink_msg_payload_flight_tm_get_right_servo_angle(msg);
- payload_flight_tm->nas_n = mavlink_msg_payload_flight_tm_get_nas_n(msg);
- payload_flight_tm->nas_e = mavlink_msg_payload_flight_tm_get_nas_e(msg);
- payload_flight_tm->nas_d = mavlink_msg_payload_flight_tm_get_nas_d(msg);
- payload_flight_tm->nas_vn = mavlink_msg_payload_flight_tm_get_nas_vn(msg);
- payload_flight_tm->nas_ve = mavlink_msg_payload_flight_tm_get_nas_ve(msg);
- payload_flight_tm->nas_vd = mavlink_msg_payload_flight_tm_get_nas_vd(msg);
- payload_flight_tm->nas_qx = mavlink_msg_payload_flight_tm_get_nas_qx(msg);
- payload_flight_tm->nas_qy = mavlink_msg_payload_flight_tm_get_nas_qy(msg);
- payload_flight_tm->nas_qz = mavlink_msg_payload_flight_tm_get_nas_qz(msg);
- payload_flight_tm->nas_qw = mavlink_msg_payload_flight_tm_get_nas_qw(msg);
- payload_flight_tm->nas_bias_x = mavlink_msg_payload_flight_tm_get_nas_bias_x(msg);
- payload_flight_tm->nas_bias_y = mavlink_msg_payload_flight_tm_get_nas_bias_y(msg);
- payload_flight_tm->nas_bias_z = mavlink_msg_payload_flight_tm_get_nas_bias_z(msg);
- payload_flight_tm->wes_n = mavlink_msg_payload_flight_tm_get_wes_n(msg);
- payload_flight_tm->wes_e = mavlink_msg_payload_flight_tm_get_wes_e(msg);
- payload_flight_tm->battery_voltage = mavlink_msg_payload_flight_tm_get_battery_voltage(msg);
- payload_flight_tm->cam_battery_voltage = mavlink_msg_payload_flight_tm_get_cam_battery_voltage(msg);
- payload_flight_tm->current_consumption = mavlink_msg_payload_flight_tm_get_current_consumption(msg);
- payload_flight_tm->temperature = mavlink_msg_payload_flight_tm_get_temperature(msg);
- payload_flight_tm->fmm_state = mavlink_msg_payload_flight_tm_get_fmm_state(msg);
- payload_flight_tm->nas_state = mavlink_msg_payload_flight_tm_get_nas_state(msg);
- payload_flight_tm->wes_state = mavlink_msg_payload_flight_tm_get_wes_state(msg);
- payload_flight_tm->gps_fix = mavlink_msg_payload_flight_tm_get_gps_fix(msg);
- payload_flight_tm->pin_nosecone = mavlink_msg_payload_flight_tm_get_pin_nosecone(msg);
- payload_flight_tm->cutter_presence = mavlink_msg_payload_flight_tm_get_cutter_presence(msg);
- payload_flight_tm->logger_error = mavlink_msg_payload_flight_tm_get_logger_error(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN? msg->len : MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN;
- memset(payload_flight_tm, 0, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
- memcpy(payload_flight_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_payload_stats_tm.h b/mavlink_lib/lyra/mavlink_msg_payload_stats_tm.h
deleted file mode 100644
index 3b945c4692aa2e834689fd0617809d5f5be22970..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_payload_stats_tm.h
+++ /dev/null
@@ -1,563 +0,0 @@
-#pragma once
-// MESSAGE PAYLOAD_STATS_TM PACKING
-
-#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM 211
-
-
-typedef struct __mavlink_payload_stats_tm_t {
- uint64_t liftoff_max_acc_ts; /*< [us] System clock at the maximum liftoff acceleration*/
- uint64_t dpl_ts; /*< [us] System clock at drouge deployment*/
- uint64_t max_z_speed_ts; /*< [us] System clock at max vertical speed*/
- uint64_t apogee_ts; /*< [us] System clock at apogee*/
- float liftoff_max_acc; /*< [m/s2] Maximum liftoff acceleration*/
- float dpl_max_acc; /*< [m/s2] Max acceleration during drouge deployment*/
- float max_z_speed; /*< [m/s] Max measured vertical speed*/
- float max_airspeed_pitot; /*< [m/s] Max speed read by the pitot tube*/
- float max_speed_altitude; /*< [m] Altitude at max speed*/
- float apogee_lat; /*< [deg] Apogee latitude*/
- float apogee_lon; /*< [deg] Apogee longitude*/
- float apogee_alt; /*< [m] Apogee altitude*/
- float min_pressure; /*< [Pa] Apogee pressure - Digital barometer*/
- float cpu_load; /*< CPU load in percentage*/
- uint32_t free_heap; /*< Amount of available heap in memory*/
-} mavlink_payload_stats_tm_t;
-
-#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN 76
-#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN 76
-#define MAVLINK_MSG_ID_211_LEN 76
-#define MAVLINK_MSG_ID_211_MIN_LEN 76
-
-#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC 115
-#define MAVLINK_MSG_ID_211_CRC 115
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM { \
- 211, \
- "PAYLOAD_STATS_TM", \
- 15, \
- { { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc_ts) }, \
- { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc) }, \
- { "dpl_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_payload_stats_tm_t, dpl_ts) }, \
- { "dpl_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_payload_stats_tm_t, dpl_max_acc) }, \
- { "max_z_speed_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_payload_stats_tm_t, max_z_speed_ts) }, \
- { "max_z_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_payload_stats_tm_t, max_z_speed) }, \
- { "max_airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_payload_stats_tm_t, max_airspeed_pitot) }, \
- { "max_speed_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_payload_stats_tm_t, max_speed_altitude) }, \
- { "apogee_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 24, offsetof(mavlink_payload_stats_tm_t, apogee_ts) }, \
- { "apogee_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_payload_stats_tm_t, apogee_lat) }, \
- { "apogee_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_payload_stats_tm_t, apogee_lon) }, \
- { "apogee_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_stats_tm_t, apogee_alt) }, \
- { "min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_stats_tm_t, min_pressure) }, \
- { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_stats_tm_t, cpu_load) }, \
- { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 72, offsetof(mavlink_payload_stats_tm_t, free_heap) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM { \
- "PAYLOAD_STATS_TM", \
- 15, \
- { { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc_ts) }, \
- { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc) }, \
- { "dpl_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_payload_stats_tm_t, dpl_ts) }, \
- { "dpl_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_payload_stats_tm_t, dpl_max_acc) }, \
- { "max_z_speed_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_payload_stats_tm_t, max_z_speed_ts) }, \
- { "max_z_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_payload_stats_tm_t, max_z_speed) }, \
- { "max_airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_payload_stats_tm_t, max_airspeed_pitot) }, \
- { "max_speed_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_payload_stats_tm_t, max_speed_altitude) }, \
- { "apogee_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 24, offsetof(mavlink_payload_stats_tm_t, apogee_ts) }, \
- { "apogee_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_payload_stats_tm_t, apogee_lat) }, \
- { "apogee_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_payload_stats_tm_t, apogee_lon) }, \
- { "apogee_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_stats_tm_t, apogee_alt) }, \
- { "min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_stats_tm_t, min_pressure) }, \
- { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_stats_tm_t, cpu_load) }, \
- { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 72, offsetof(mavlink_payload_stats_tm_t, free_heap) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a payload_stats_tm 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 liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param dpl_ts [us] System clock at drouge deployment
- * @param dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param max_z_speed_ts [us] System clock at max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [us] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param apogee_alt [m] Apogee altitude
- * @param min_pressure [Pa] Apogee pressure - Digital barometer
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_payload_stats_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 8, dpl_ts);
- _mav_put_uint64_t(buf, 16, max_z_speed_ts);
- _mav_put_uint64_t(buf, 24, apogee_ts);
- _mav_put_float(buf, 32, liftoff_max_acc);
- _mav_put_float(buf, 36, dpl_max_acc);
- _mav_put_float(buf, 40, max_z_speed);
- _mav_put_float(buf, 44, max_airspeed_pitot);
- _mav_put_float(buf, 48, max_speed_altitude);
- _mav_put_float(buf, 52, apogee_lat);
- _mav_put_float(buf, 56, apogee_lon);
- _mav_put_float(buf, 60, apogee_alt);
- _mav_put_float(buf, 64, min_pressure);
- _mav_put_float(buf, 68, cpu_load);
- _mav_put_uint32_t(buf, 72, free_heap);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
-#else
- mavlink_payload_stats_tm_t packet;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.dpl_ts = dpl_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.dpl_max_acc = dpl_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.apogee_alt = apogee_alt;
- packet.min_pressure = min_pressure;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PAYLOAD_STATS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-}
-
-/**
- * @brief Pack a payload_stats_tm 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 liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param dpl_ts [us] System clock at drouge deployment
- * @param dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param max_z_speed_ts [us] System clock at max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [us] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param apogee_alt [m] Apogee altitude
- * @param min_pressure [Pa] Apogee pressure - Digital barometer
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_payload_stats_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t liftoff_max_acc_ts,float liftoff_max_acc,uint64_t dpl_ts,float dpl_max_acc,uint64_t max_z_speed_ts,float max_z_speed,float max_airspeed_pitot,float max_speed_altitude,uint64_t apogee_ts,float apogee_lat,float apogee_lon,float apogee_alt,float min_pressure,float cpu_load,uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 8, dpl_ts);
- _mav_put_uint64_t(buf, 16, max_z_speed_ts);
- _mav_put_uint64_t(buf, 24, apogee_ts);
- _mav_put_float(buf, 32, liftoff_max_acc);
- _mav_put_float(buf, 36, dpl_max_acc);
- _mav_put_float(buf, 40, max_z_speed);
- _mav_put_float(buf, 44, max_airspeed_pitot);
- _mav_put_float(buf, 48, max_speed_altitude);
- _mav_put_float(buf, 52, apogee_lat);
- _mav_put_float(buf, 56, apogee_lon);
- _mav_put_float(buf, 60, apogee_alt);
- _mav_put_float(buf, 64, min_pressure);
- _mav_put_float(buf, 68, cpu_load);
- _mav_put_uint32_t(buf, 72, free_heap);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
-#else
- mavlink_payload_stats_tm_t packet;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.dpl_ts = dpl_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.dpl_max_acc = dpl_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.apogee_alt = apogee_alt;
- packet.min_pressure = min_pressure;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PAYLOAD_STATS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-}
-
-/**
- * @brief Encode a payload_stats_tm 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 payload_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_payload_stats_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_payload_stats_tm_t* payload_stats_tm)
-{
- return mavlink_msg_payload_stats_tm_pack(system_id, component_id, msg, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->max_z_speed_ts, payload_stats_tm->max_z_speed, payload_stats_tm->max_airspeed_pitot, payload_stats_tm->max_speed_altitude, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap);
-}
-
-/**
- * @brief Encode a payload_stats_tm 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 payload_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_payload_stats_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_payload_stats_tm_t* payload_stats_tm)
-{
- return mavlink_msg_payload_stats_tm_pack_chan(system_id, component_id, chan, msg, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->max_z_speed_ts, payload_stats_tm->max_z_speed, payload_stats_tm->max_airspeed_pitot, payload_stats_tm->max_speed_altitude, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap);
-}
-
-/**
- * @brief Send a payload_stats_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param dpl_ts [us] System clock at drouge deployment
- * @param dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param max_z_speed_ts [us] System clock at max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [us] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param apogee_alt [m] Apogee altitude
- * @param min_pressure [Pa] Apogee pressure - Digital barometer
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_payload_stats_tm_send(mavlink_channel_t chan, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 8, dpl_ts);
- _mav_put_uint64_t(buf, 16, max_z_speed_ts);
- _mav_put_uint64_t(buf, 24, apogee_ts);
- _mav_put_float(buf, 32, liftoff_max_acc);
- _mav_put_float(buf, 36, dpl_max_acc);
- _mav_put_float(buf, 40, max_z_speed);
- _mav_put_float(buf, 44, max_airspeed_pitot);
- _mav_put_float(buf, 48, max_speed_altitude);
- _mav_put_float(buf, 52, apogee_lat);
- _mav_put_float(buf, 56, apogee_lon);
- _mav_put_float(buf, 60, apogee_alt);
- _mav_put_float(buf, 64, min_pressure);
- _mav_put_float(buf, 68, cpu_load);
- _mav_put_uint32_t(buf, 72, free_heap);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM, buf, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-#else
- mavlink_payload_stats_tm_t packet;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.dpl_ts = dpl_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.dpl_max_acc = dpl_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.apogee_alt = apogee_alt;
- packet.min_pressure = min_pressure;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM, (const char *)&packet, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a payload_stats_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_payload_stats_tm_send_struct(mavlink_channel_t chan, const mavlink_payload_stats_tm_t* payload_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_payload_stats_tm_send(chan, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->max_z_speed_ts, payload_stats_tm->max_z_speed, payload_stats_tm->max_airspeed_pitot, payload_stats_tm->max_speed_altitude, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM, (const char *)payload_stats_tm, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_PAYLOAD_STATS_TM_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_payload_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 8, dpl_ts);
- _mav_put_uint64_t(buf, 16, max_z_speed_ts);
- _mav_put_uint64_t(buf, 24, apogee_ts);
- _mav_put_float(buf, 32, liftoff_max_acc);
- _mav_put_float(buf, 36, dpl_max_acc);
- _mav_put_float(buf, 40, max_z_speed);
- _mav_put_float(buf, 44, max_airspeed_pitot);
- _mav_put_float(buf, 48, max_speed_altitude);
- _mav_put_float(buf, 52, apogee_lat);
- _mav_put_float(buf, 56, apogee_lon);
- _mav_put_float(buf, 60, apogee_alt);
- _mav_put_float(buf, 64, min_pressure);
- _mav_put_float(buf, 68, cpu_load);
- _mav_put_uint32_t(buf, 72, free_heap);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM, buf, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-#else
- mavlink_payload_stats_tm_t *packet = (mavlink_payload_stats_tm_t *)msgbuf;
- packet->liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet->dpl_ts = dpl_ts;
- packet->max_z_speed_ts = max_z_speed_ts;
- packet->apogee_ts = apogee_ts;
- packet->liftoff_max_acc = liftoff_max_acc;
- packet->dpl_max_acc = dpl_max_acc;
- packet->max_z_speed = max_z_speed;
- packet->max_airspeed_pitot = max_airspeed_pitot;
- packet->max_speed_altitude = max_speed_altitude;
- packet->apogee_lat = apogee_lat;
- packet->apogee_lon = apogee_lon;
- packet->apogee_alt = apogee_alt;
- packet->min_pressure = min_pressure;
- packet->cpu_load = cpu_load;
- packet->free_heap = free_heap;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM, (const char *)packet, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE PAYLOAD_STATS_TM UNPACKING
-
-
-/**
- * @brief Get field liftoff_max_acc_ts from payload_stats_tm message
- *
- * @return [us] System clock at the maximum liftoff acceleration
- */
-static inline uint64_t mavlink_msg_payload_stats_tm_get_liftoff_max_acc_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field liftoff_max_acc from payload_stats_tm message
- *
- * @return [m/s2] Maximum liftoff acceleration
- */
-static inline float mavlink_msg_payload_stats_tm_get_liftoff_max_acc(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field dpl_ts from payload_stats_tm message
- *
- * @return [us] System clock at drouge deployment
- */
-static inline uint64_t mavlink_msg_payload_stats_tm_get_dpl_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 8);
-}
-
-/**
- * @brief Get field dpl_max_acc from payload_stats_tm message
- *
- * @return [m/s2] Max acceleration during drouge deployment
- */
-static inline float mavlink_msg_payload_stats_tm_get_dpl_max_acc(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field max_z_speed_ts from payload_stats_tm message
- *
- * @return [us] System clock at max vertical speed
- */
-static inline uint64_t mavlink_msg_payload_stats_tm_get_max_z_speed_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 16);
-}
-
-/**
- * @brief Get field max_z_speed from payload_stats_tm message
- *
- * @return [m/s] Max measured vertical speed
- */
-static inline float mavlink_msg_payload_stats_tm_get_max_z_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field max_airspeed_pitot from payload_stats_tm message
- *
- * @return [m/s] Max speed read by the pitot tube
- */
-static inline float mavlink_msg_payload_stats_tm_get_max_airspeed_pitot(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field max_speed_altitude from payload_stats_tm message
- *
- * @return [m] Altitude at max speed
- */
-static inline float mavlink_msg_payload_stats_tm_get_max_speed_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field apogee_ts from payload_stats_tm message
- *
- * @return [us] System clock at apogee
- */
-static inline uint64_t mavlink_msg_payload_stats_tm_get_apogee_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 24);
-}
-
-/**
- * @brief Get field apogee_lat from payload_stats_tm message
- *
- * @return [deg] Apogee latitude
- */
-static inline float mavlink_msg_payload_stats_tm_get_apogee_lat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field apogee_lon from payload_stats_tm message
- *
- * @return [deg] Apogee longitude
- */
-static inline float mavlink_msg_payload_stats_tm_get_apogee_lon(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field apogee_alt from payload_stats_tm message
- *
- * @return [m] Apogee altitude
- */
-static inline float mavlink_msg_payload_stats_tm_get_apogee_alt(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field min_pressure from payload_stats_tm message
- *
- * @return [Pa] Apogee pressure - Digital barometer
- */
-static inline float mavlink_msg_payload_stats_tm_get_min_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field cpu_load from payload_stats_tm message
- *
- * @return CPU load in percentage
- */
-static inline float mavlink_msg_payload_stats_tm_get_cpu_load(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field free_heap from payload_stats_tm message
- *
- * @return Amount of available heap in memory
- */
-static inline uint32_t mavlink_msg_payload_stats_tm_get_free_heap(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 72);
-}
-
-/**
- * @brief Decode a payload_stats_tm message into a struct
- *
- * @param msg The message to decode
- * @param payload_stats_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_payload_stats_tm_decode(const mavlink_message_t* msg, mavlink_payload_stats_tm_t* payload_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- payload_stats_tm->liftoff_max_acc_ts = mavlink_msg_payload_stats_tm_get_liftoff_max_acc_ts(msg);
- payload_stats_tm->dpl_ts = mavlink_msg_payload_stats_tm_get_dpl_ts(msg);
- payload_stats_tm->max_z_speed_ts = mavlink_msg_payload_stats_tm_get_max_z_speed_ts(msg);
- payload_stats_tm->apogee_ts = mavlink_msg_payload_stats_tm_get_apogee_ts(msg);
- payload_stats_tm->liftoff_max_acc = mavlink_msg_payload_stats_tm_get_liftoff_max_acc(msg);
- payload_stats_tm->dpl_max_acc = mavlink_msg_payload_stats_tm_get_dpl_max_acc(msg);
- payload_stats_tm->max_z_speed = mavlink_msg_payload_stats_tm_get_max_z_speed(msg);
- payload_stats_tm->max_airspeed_pitot = mavlink_msg_payload_stats_tm_get_max_airspeed_pitot(msg);
- payload_stats_tm->max_speed_altitude = mavlink_msg_payload_stats_tm_get_max_speed_altitude(msg);
- payload_stats_tm->apogee_lat = mavlink_msg_payload_stats_tm_get_apogee_lat(msg);
- payload_stats_tm->apogee_lon = mavlink_msg_payload_stats_tm_get_apogee_lon(msg);
- payload_stats_tm->apogee_alt = mavlink_msg_payload_stats_tm_get_apogee_alt(msg);
- payload_stats_tm->min_pressure = mavlink_msg_payload_stats_tm_get_min_pressure(msg);
- payload_stats_tm->cpu_load = mavlink_msg_payload_stats_tm_get_cpu_load(msg);
- payload_stats_tm->free_heap = mavlink_msg_payload_stats_tm_get_free_heap(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN? msg->len : MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN;
- memset(payload_stats_tm, 0, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
- memcpy(payload_stats_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_pin_tm.h b/mavlink_lib/lyra/mavlink_msg_pin_tm.h
deleted file mode 100644
index 80cc7d6547bd54d6257b5450532274f2c13126ac..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_pin_tm.h
+++ /dev/null
@@ -1,313 +0,0 @@
-#pragma once
-// MESSAGE PIN_TM PACKING
-
-#define MAVLINK_MSG_ID_PIN_TM 113
-
-
-typedef struct __mavlink_pin_tm_t {
- uint64_t timestamp; /*< [us] Timestamp*/
- uint64_t last_change_timestamp; /*< Last change timestamp of pin*/
- uint8_t pin_id; /*< A member of the PinsList enum*/
- uint8_t changes_counter; /*< Number of changes of pin*/
- uint8_t current_state; /*< Current state of pin*/
-} mavlink_pin_tm_t;
-
-#define MAVLINK_MSG_ID_PIN_TM_LEN 19
-#define MAVLINK_MSG_ID_PIN_TM_MIN_LEN 19
-#define MAVLINK_MSG_ID_113_LEN 19
-#define MAVLINK_MSG_ID_113_MIN_LEN 19
-
-#define MAVLINK_MSG_ID_PIN_TM_CRC 255
-#define MAVLINK_MSG_ID_113_CRC 255
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_PIN_TM { \
- 113, \
- "PIN_TM", \
- 5, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_pin_tm_t, timestamp) }, \
- { "pin_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_pin_tm_t, pin_id) }, \
- { "last_change_timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_pin_tm_t, last_change_timestamp) }, \
- { "changes_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_pin_tm_t, changes_counter) }, \
- { "current_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_pin_tm_t, current_state) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_PIN_TM { \
- "PIN_TM", \
- 5, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_pin_tm_t, timestamp) }, \
- { "pin_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_pin_tm_t, pin_id) }, \
- { "last_change_timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_pin_tm_t, last_change_timestamp) }, \
- { "changes_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_pin_tm_t, changes_counter) }, \
- { "current_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_pin_tm_t, current_state) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a pin_tm 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
- * @param pin_id A member of the PinsList enum
- * @param last_change_timestamp Last change timestamp of pin
- * @param changes_counter Number of changes of pin
- * @param current_state Current state of pin
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_pin_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t pin_id, uint64_t last_change_timestamp, uint8_t changes_counter, uint8_t current_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PIN_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, last_change_timestamp);
- _mav_put_uint8_t(buf, 16, pin_id);
- _mav_put_uint8_t(buf, 17, changes_counter);
- _mav_put_uint8_t(buf, 18, current_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PIN_TM_LEN);
-#else
- mavlink_pin_tm_t packet;
- packet.timestamp = timestamp;
- packet.last_change_timestamp = last_change_timestamp;
- packet.pin_id = pin_id;
- packet.changes_counter = changes_counter;
- packet.current_state = current_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PIN_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PIN_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-}
-
-/**
- * @brief Pack a pin_tm 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
- * @param pin_id A member of the PinsList enum
- * @param last_change_timestamp Last change timestamp of pin
- * @param changes_counter Number of changes of pin
- * @param current_state Current state of pin
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_pin_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t pin_id,uint64_t last_change_timestamp,uint8_t changes_counter,uint8_t current_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PIN_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, last_change_timestamp);
- _mav_put_uint8_t(buf, 16, pin_id);
- _mav_put_uint8_t(buf, 17, changes_counter);
- _mav_put_uint8_t(buf, 18, current_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PIN_TM_LEN);
-#else
- mavlink_pin_tm_t packet;
- packet.timestamp = timestamp;
- packet.last_change_timestamp = last_change_timestamp;
- packet.pin_id = pin_id;
- packet.changes_counter = changes_counter;
- packet.current_state = current_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PIN_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PIN_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-}
-
-/**
- * @brief Encode a pin_tm 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 pin_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_pin_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pin_tm_t* pin_tm)
-{
- return mavlink_msg_pin_tm_pack(system_id, component_id, msg, pin_tm->timestamp, pin_tm->pin_id, pin_tm->last_change_timestamp, pin_tm->changes_counter, pin_tm->current_state);
-}
-
-/**
- * @brief Encode a pin_tm 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 pin_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_pin_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_pin_tm_t* pin_tm)
-{
- return mavlink_msg_pin_tm_pack_chan(system_id, component_id, chan, msg, pin_tm->timestamp, pin_tm->pin_id, pin_tm->last_change_timestamp, pin_tm->changes_counter, pin_tm->current_state);
-}
-
-/**
- * @brief Send a pin_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp
- * @param pin_id A member of the PinsList enum
- * @param last_change_timestamp Last change timestamp of pin
- * @param changes_counter Number of changes of pin
- * @param current_state Current state of pin
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_pin_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t pin_id, uint64_t last_change_timestamp, uint8_t changes_counter, uint8_t current_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PIN_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, last_change_timestamp);
- _mav_put_uint8_t(buf, 16, pin_id);
- _mav_put_uint8_t(buf, 17, changes_counter);
- _mav_put_uint8_t(buf, 18, current_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PIN_TM, buf, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-#else
- mavlink_pin_tm_t packet;
- packet.timestamp = timestamp;
- packet.last_change_timestamp = last_change_timestamp;
- packet.pin_id = pin_id;
- packet.changes_counter = changes_counter;
- packet.current_state = current_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PIN_TM, (const char *)&packet, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a pin_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_pin_tm_send_struct(mavlink_channel_t chan, const mavlink_pin_tm_t* pin_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_pin_tm_send(chan, pin_tm->timestamp, pin_tm->pin_id, pin_tm->last_change_timestamp, pin_tm->changes_counter, pin_tm->current_state);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PIN_TM, (const char *)pin_tm, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_PIN_TM_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_pin_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t pin_id, uint64_t last_change_timestamp, uint8_t changes_counter, uint8_t current_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, last_change_timestamp);
- _mav_put_uint8_t(buf, 16, pin_id);
- _mav_put_uint8_t(buf, 17, changes_counter);
- _mav_put_uint8_t(buf, 18, current_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PIN_TM, buf, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-#else
- mavlink_pin_tm_t *packet = (mavlink_pin_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->last_change_timestamp = last_change_timestamp;
- packet->pin_id = pin_id;
- packet->changes_counter = changes_counter;
- packet->current_state = current_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PIN_TM, (const char *)packet, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE PIN_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from pin_tm message
- *
- * @return [us] Timestamp
- */
-static inline uint64_t mavlink_msg_pin_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field pin_id from pin_tm message
- *
- * @return A member of the PinsList enum
- */
-static inline uint8_t mavlink_msg_pin_tm_get_pin_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 16);
-}
-
-/**
- * @brief Get field last_change_timestamp from pin_tm message
- *
- * @return Last change timestamp of pin
- */
-static inline uint64_t mavlink_msg_pin_tm_get_last_change_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 8);
-}
-
-/**
- * @brief Get field changes_counter from pin_tm message
- *
- * @return Number of changes of pin
- */
-static inline uint8_t mavlink_msg_pin_tm_get_changes_counter(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 17);
-}
-
-/**
- * @brief Get field current_state from pin_tm message
- *
- * @return Current state of pin
- */
-static inline uint8_t mavlink_msg_pin_tm_get_current_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 18);
-}
-
-/**
- * @brief Decode a pin_tm message into a struct
- *
- * @param msg The message to decode
- * @param pin_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_pin_tm_decode(const mavlink_message_t* msg, mavlink_pin_tm_t* pin_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- pin_tm->timestamp = mavlink_msg_pin_tm_get_timestamp(msg);
- pin_tm->last_change_timestamp = mavlink_msg_pin_tm_get_last_change_timestamp(msg);
- pin_tm->pin_id = mavlink_msg_pin_tm_get_pin_id(msg);
- pin_tm->changes_counter = mavlink_msg_pin_tm_get_changes_counter(msg);
- pin_tm->current_state = mavlink_msg_pin_tm_get_current_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_PIN_TM_LEN? msg->len : MAVLINK_MSG_ID_PIN_TM_LEN;
- memset(pin_tm, 0, MAVLINK_MSG_ID_PIN_TM_LEN);
- memcpy(pin_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_ping_tc.h b/mavlink_lib/lyra/mavlink_msg_ping_tc.h
deleted file mode 100644
index 99a2895f9933675f201a98a080067ebf3b33bb66..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_ping_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE PING_TC PACKING
-
-#define MAVLINK_MSG_ID_PING_TC 1
-
-
-typedef struct __mavlink_ping_tc_t {
- uint64_t timestamp; /*< Timestamp to identify when it was sent*/
-} mavlink_ping_tc_t;
-
-#define MAVLINK_MSG_ID_PING_TC_LEN 8
-#define MAVLINK_MSG_ID_PING_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_1_LEN 8
-#define MAVLINK_MSG_ID_1_MIN_LEN 8
-
-#define MAVLINK_MSG_ID_PING_TC_CRC 136
-#define MAVLINK_MSG_ID_1_CRC 136
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_PING_TC { \
- 1, \
- "PING_TC", \
- 1, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_tc_t, timestamp) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_PING_TC { \
- "PING_TC", \
- 1, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_tc_t, timestamp) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ping_tc 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 Timestamp to identify when it was sent
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ping_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_TC_LEN);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PING_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-}
-
-/**
- * @brief Pack a ping_tc 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 Timestamp to identify when it was sent
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ping_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_TC_LEN);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PING_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-}
-
-/**
- * @brief Encode a ping_tc 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_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ping_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_tc_t* ping_tc)
-{
- return mavlink_msg_ping_tc_pack(system_id, component_id, msg, ping_tc->timestamp);
-}
-
-/**
- * @brief Encode a ping_tc 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_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ping_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ping_tc_t* ping_tc)
-{
- return mavlink_msg_ping_tc_pack_chan(system_id, component_id, chan, msg, ping_tc->timestamp);
-}
-
-/**
- * @brief Send a ping_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp Timestamp to identify when it was sent
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ping_tc_send(mavlink_channel_t chan, uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, buf, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)&packet, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a ping_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ping_tc_send_struct(mavlink_channel_t chan, const mavlink_ping_tc_t* ping_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ping_tc_send(chan, ping_tc->timestamp);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)ping_tc, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_PING_TC_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_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, buf, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#else
- mavlink_ping_tc_t *packet = (mavlink_ping_tc_t *)msgbuf;
- packet->timestamp = timestamp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)packet, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE PING_TC UNPACKING
-
-
-/**
- * @brief Get field timestamp from ping_tc message
- *
- * @return Timestamp to identify when it was sent
- */
-static inline uint64_t mavlink_msg_ping_tc_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Decode a ping_tc message into a struct
- *
- * @param msg The message to decode
- * @param ping_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ping_tc_decode(const mavlink_message_t* msg, mavlink_ping_tc_t* ping_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ping_tc->timestamp = mavlink_msg_ping_tc_get_timestamp(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_PING_TC_LEN? msg->len : MAVLINK_MSG_ID_PING_TC_LEN;
- memset(ping_tc, 0, MAVLINK_MSG_ID_PING_TC_LEN);
- memcpy(ping_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_pressure_tm.h b/mavlink_lib/lyra/mavlink_msg_pressure_tm.h
deleted file mode 100644
index 8291d6e36b4c63ac30cc308ca496ad3c1d1ad4a6..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_pressure_tm.h
+++ /dev/null
@@ -1,255 +0,0 @@
-#pragma once
-// MESSAGE PRESSURE_TM PACKING
-
-#define MAVLINK_MSG_ID_PRESSURE_TM 104
-
-
-typedef struct __mavlink_pressure_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float pressure; /*< [Pa] Pressure of the digital barometer*/
- char sensor_name[20]; /*< Sensor name*/
-} mavlink_pressure_tm_t;
-
-#define MAVLINK_MSG_ID_PRESSURE_TM_LEN 32
-#define MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_104_LEN 32
-#define MAVLINK_MSG_ID_104_MIN_LEN 32
-
-#define MAVLINK_MSG_ID_PRESSURE_TM_CRC 87
-#define MAVLINK_MSG_ID_104_CRC 87
-
-#define MAVLINK_MSG_PRESSURE_TM_FIELD_SENSOR_NAME_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_PRESSURE_TM { \
- 104, \
- "PRESSURE_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_pressure_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_pressure_tm_t, sensor_name) }, \
- { "pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_pressure_tm_t, pressure) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_PRESSURE_TM { \
- "PRESSURE_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_pressure_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_pressure_tm_t, sensor_name) }, \
- { "pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_pressure_tm_t, pressure) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a pressure_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param pressure [Pa] Pressure of the digital barometer
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_pressure_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_name, float pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PRESSURE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PRESSURE_TM_LEN);
-#else
- mavlink_pressure_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure = pressure;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PRESSURE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PRESSURE_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-}
-
-/**
- * @brief Pack a pressure_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param pressure [Pa] Pressure of the digital barometer
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_pressure_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_name,float pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PRESSURE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PRESSURE_TM_LEN);
-#else
- mavlink_pressure_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure = pressure;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PRESSURE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PRESSURE_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-}
-
-/**
- * @brief Encode a pressure_tm 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 pressure_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_pressure_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pressure_tm_t* pressure_tm)
-{
- return mavlink_msg_pressure_tm_pack(system_id, component_id, msg, pressure_tm->timestamp, pressure_tm->sensor_name, pressure_tm->pressure);
-}
-
-/**
- * @brief Encode a pressure_tm 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 pressure_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_pressure_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_pressure_tm_t* pressure_tm)
-{
- return mavlink_msg_pressure_tm_pack_chan(system_id, component_id, chan, msg, pressure_tm->timestamp, pressure_tm->sensor_name, pressure_tm->pressure);
-}
-
-/**
- * @brief Send a pressure_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_name Sensor name
- * @param pressure [Pa] Pressure of the digital barometer
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_pressure_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PRESSURE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PRESSURE_TM, buf, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-#else
- mavlink_pressure_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure = pressure;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PRESSURE_TM, (const char *)&packet, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a pressure_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_pressure_tm_send_struct(mavlink_channel_t chan, const mavlink_pressure_tm_t* pressure_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_pressure_tm_send(chan, pressure_tm->timestamp, pressure_tm->sensor_name, pressure_tm->pressure);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PRESSURE_TM, (const char *)pressure_tm, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_PRESSURE_TM_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_pressure_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PRESSURE_TM, buf, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-#else
- mavlink_pressure_tm_t *packet = (mavlink_pressure_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->pressure = pressure;
- mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PRESSURE_TM, (const char *)packet, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE PRESSURE_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from pressure_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_pressure_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_name from pressure_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_pressure_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
-{
- return _MAV_RETURN_char_array(msg, sensor_name, 20, 12);
-}
-
-/**
- * @brief Get field pressure from pressure_tm message
- *
- * @return [Pa] Pressure of the digital barometer
- */
-static inline float mavlink_msg_pressure_tm_get_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Decode a pressure_tm message into a struct
- *
- * @param msg The message to decode
- * @param pressure_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_pressure_tm_decode(const mavlink_message_t* msg, mavlink_pressure_tm_t* pressure_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- pressure_tm->timestamp = mavlink_msg_pressure_tm_get_timestamp(msg);
- pressure_tm->pressure = mavlink_msg_pressure_tm_get_pressure(msg);
- mavlink_msg_pressure_tm_get_sensor_name(msg, pressure_tm->sensor_name);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_PRESSURE_TM_LEN? msg->len : MAVLINK_MSG_ID_PRESSURE_TM_LEN;
- memset(pressure_tm, 0, MAVLINK_MSG_ID_PRESSURE_TM_LEN);
- memcpy(pressure_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_raw_event_tc.h b/mavlink_lib/lyra/mavlink_msg_raw_event_tc.h
deleted file mode 100644
index fe6d60a1b38e429fc0f0049aa21234613d3c8e99..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_raw_event_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE RAW_EVENT_TC PACKING
-
-#define MAVLINK_MSG_ID_RAW_EVENT_TC 13
-
-
-typedef struct __mavlink_raw_event_tc_t {
- uint8_t topic_id; /*< Id of the topic to which the event should be posted*/
- uint8_t event_id; /*< Id of the event to be posted*/
-} mavlink_raw_event_tc_t;
-
-#define MAVLINK_MSG_ID_RAW_EVENT_TC_LEN 2
-#define MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN 2
-#define MAVLINK_MSG_ID_13_LEN 2
-#define MAVLINK_MSG_ID_13_MIN_LEN 2
-
-#define MAVLINK_MSG_ID_RAW_EVENT_TC_CRC 218
-#define MAVLINK_MSG_ID_13_CRC 218
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_RAW_EVENT_TC { \
- 13, \
- "RAW_EVENT_TC", \
- 2, \
- { { "topic_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_raw_event_tc_t, topic_id) }, \
- { "event_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_raw_event_tc_t, event_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_RAW_EVENT_TC { \
- "RAW_EVENT_TC", \
- 2, \
- { { "topic_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_raw_event_tc_t, topic_id) }, \
- { "event_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_raw_event_tc_t, event_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a raw_event_tc 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 topic_id Id of the topic to which the event should be posted
- * @param event_id Id of the event to be posted
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_raw_event_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t topic_id, uint8_t event_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_EVENT_TC_LEN];
- _mav_put_uint8_t(buf, 0, topic_id);
- _mav_put_uint8_t(buf, 1, event_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#else
- mavlink_raw_event_tc_t packet;
- packet.topic_id = topic_id;
- packet.event_id = event_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RAW_EVENT_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-}
-
-/**
- * @brief Pack a raw_event_tc 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 topic_id Id of the topic to which the event should be posted
- * @param event_id Id of the event to be posted
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_raw_event_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t topic_id,uint8_t event_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_EVENT_TC_LEN];
- _mav_put_uint8_t(buf, 0, topic_id);
- _mav_put_uint8_t(buf, 1, event_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#else
- mavlink_raw_event_tc_t packet;
- packet.topic_id = topic_id;
- packet.event_id = event_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RAW_EVENT_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-}
-
-/**
- * @brief Encode a raw_event_tc 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_event_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_raw_event_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_event_tc_t* raw_event_tc)
-{
- return mavlink_msg_raw_event_tc_pack(system_id, component_id, msg, raw_event_tc->topic_id, raw_event_tc->event_id);
-}
-
-/**
- * @brief Encode a raw_event_tc 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_event_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_raw_event_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_event_tc_t* raw_event_tc)
-{
- return mavlink_msg_raw_event_tc_pack_chan(system_id, component_id, chan, msg, raw_event_tc->topic_id, raw_event_tc->event_id);
-}
-
-/**
- * @brief Send a raw_event_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param topic_id Id of the topic to which the event should be posted
- * @param event_id Id of the event to be posted
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_raw_event_tc_send(mavlink_channel_t chan, uint8_t topic_id, uint8_t event_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_EVENT_TC_LEN];
- _mav_put_uint8_t(buf, 0, topic_id);
- _mav_put_uint8_t(buf, 1, event_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, buf, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#else
- mavlink_raw_event_tc_t packet;
- packet.topic_id = topic_id;
- packet.event_id = event_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, (const char *)&packet, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a raw_event_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_raw_event_tc_send_struct(mavlink_channel_t chan, const mavlink_raw_event_tc_t* raw_event_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_raw_event_tc_send(chan, raw_event_tc->topic_id, raw_event_tc->event_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, (const char *)raw_event_tc, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_RAW_EVENT_TC_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_event_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t topic_id, uint8_t event_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, topic_id);
- _mav_put_uint8_t(buf, 1, event_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, buf, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#else
- mavlink_raw_event_tc_t *packet = (mavlink_raw_event_tc_t *)msgbuf;
- packet->topic_id = topic_id;
- packet->event_id = event_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, (const char *)packet, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE RAW_EVENT_TC UNPACKING
-
-
-/**
- * @brief Get field topic_id from raw_event_tc message
- *
- * @return Id of the topic to which the event should be posted
- */
-static inline uint8_t mavlink_msg_raw_event_tc_get_topic_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field event_id from raw_event_tc message
- *
- * @return Id of the event to be posted
- */
-static inline uint8_t mavlink_msg_raw_event_tc_get_event_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Decode a raw_event_tc message into a struct
- *
- * @param msg The message to decode
- * @param raw_event_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_raw_event_tc_decode(const mavlink_message_t* msg, mavlink_raw_event_tc_t* raw_event_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- raw_event_tc->topic_id = mavlink_msg_raw_event_tc_get_topic_id(msg);
- raw_event_tc->event_id = mavlink_msg_raw_event_tc_get_event_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_RAW_EVENT_TC_LEN? msg->len : MAVLINK_MSG_ID_RAW_EVENT_TC_LEN;
- memset(raw_event_tc, 0, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
- memcpy(raw_event_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_receiver_tm.h b/mavlink_lib/lyra/mavlink_msg_receiver_tm.h
deleted file mode 100644
index d87647ee1d1ad1a8b59605721d6fca6469887093..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_receiver_tm.h
+++ /dev/null
@@ -1,688 +0,0 @@
-#pragma once
-// MESSAGE RECEIVER_TM PACKING
-
-#define MAVLINK_MSG_ID_RECEIVER_TM 150
-
-
-typedef struct __mavlink_receiver_tm_t {
- uint64_t timestamp; /*< [us] Timestamp*/
- float main_rx_rssi; /*< [dBm] Receive RSSI*/
- float main_rx_fei; /*< [Hz] Receive frequency error index*/
- float payload_rx_rssi; /*< [dBm] Receive RSSI*/
- float payload_rx_fei; /*< [Hz] Receive frequency error index*/
- float battery_voltage; /*< [V] Battery voltage*/
- uint16_t main_packet_tx_error_count; /*< Number of errors during send*/
- uint16_t main_tx_bitrate; /*< [b/s] Send bitrate*/
- uint16_t main_packet_rx_success_count; /*< Number of succesfull received mavlink packets*/
- uint16_t main_packet_rx_drop_count; /*< Number of dropped mavlink packets*/
- uint16_t main_rx_bitrate; /*< [b/s] Receive bitrate*/
- uint16_t payload_packet_tx_error_count; /*< Number of errors during send*/
- uint16_t payload_tx_bitrate; /*< [b/s] Send bitrate*/
- uint16_t payload_packet_rx_success_count; /*< Number of succesfull received mavlink packets*/
- uint16_t payload_packet_rx_drop_count; /*< Number of dropped mavlink packets*/
- uint16_t payload_rx_bitrate; /*< [b/s] Receive bitrate*/
- uint8_t main_radio_present; /*< Boolean indicating the presence of the main radio*/
- uint8_t payload_radio_present; /*< Boolean indicating the presence of the payload radio*/
- uint8_t ethernet_present; /*< Boolean indicating the presence of the ethernet module*/
- uint8_t ethernet_status; /*< Status flag indicating the status of the ethernet PHY*/
-} mavlink_receiver_tm_t;
-
-#define MAVLINK_MSG_ID_RECEIVER_TM_LEN 52
-#define MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN 52
-#define MAVLINK_MSG_ID_150_LEN 52
-#define MAVLINK_MSG_ID_150_MIN_LEN 52
-
-#define MAVLINK_MSG_ID_RECEIVER_TM_CRC 117
-#define MAVLINK_MSG_ID_150_CRC 117
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_RECEIVER_TM { \
- 150, \
- "RECEIVER_TM", \
- 20, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_receiver_tm_t, timestamp) }, \
- { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_receiver_tm_t, main_radio_present) }, \
- { "main_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_receiver_tm_t, main_packet_tx_error_count) }, \
- { "main_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_receiver_tm_t, main_tx_bitrate) }, \
- { "main_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_receiver_tm_t, main_packet_rx_success_count) }, \
- { "main_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_receiver_tm_t, main_packet_rx_drop_count) }, \
- { "main_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_receiver_tm_t, main_rx_bitrate) }, \
- { "main_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_receiver_tm_t, main_rx_rssi) }, \
- { "main_rx_fei", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_receiver_tm_t, main_rx_fei) }, \
- { "payload_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_receiver_tm_t, payload_radio_present) }, \
- { "payload_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_receiver_tm_t, payload_packet_tx_error_count) }, \
- { "payload_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_receiver_tm_t, payload_tx_bitrate) }, \
- { "payload_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 42, offsetof(mavlink_receiver_tm_t, payload_packet_rx_success_count) }, \
- { "payload_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_receiver_tm_t, payload_packet_rx_drop_count) }, \
- { "payload_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 46, offsetof(mavlink_receiver_tm_t, payload_rx_bitrate) }, \
- { "payload_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_receiver_tm_t, payload_rx_rssi) }, \
- { "payload_rx_fei", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_receiver_tm_t, payload_rx_fei) }, \
- { "ethernet_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_receiver_tm_t, ethernet_present) }, \
- { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_receiver_tm_t, ethernet_status) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_receiver_tm_t, battery_voltage) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_RECEIVER_TM { \
- "RECEIVER_TM", \
- 20, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_receiver_tm_t, timestamp) }, \
- { "main_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_receiver_tm_t, main_radio_present) }, \
- { "main_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_receiver_tm_t, main_packet_tx_error_count) }, \
- { "main_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_receiver_tm_t, main_tx_bitrate) }, \
- { "main_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_receiver_tm_t, main_packet_rx_success_count) }, \
- { "main_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_receiver_tm_t, main_packet_rx_drop_count) }, \
- { "main_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_receiver_tm_t, main_rx_bitrate) }, \
- { "main_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_receiver_tm_t, main_rx_rssi) }, \
- { "main_rx_fei", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_receiver_tm_t, main_rx_fei) }, \
- { "payload_radio_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_receiver_tm_t, payload_radio_present) }, \
- { "payload_packet_tx_error_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_receiver_tm_t, payload_packet_tx_error_count) }, \
- { "payload_tx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_receiver_tm_t, payload_tx_bitrate) }, \
- { "payload_packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 42, offsetof(mavlink_receiver_tm_t, payload_packet_rx_success_count) }, \
- { "payload_packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_receiver_tm_t, payload_packet_rx_drop_count) }, \
- { "payload_rx_bitrate", NULL, MAVLINK_TYPE_UINT16_T, 0, 46, offsetof(mavlink_receiver_tm_t, payload_rx_bitrate) }, \
- { "payload_rx_rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_receiver_tm_t, payload_rx_rssi) }, \
- { "payload_rx_fei", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_receiver_tm_t, payload_rx_fei) }, \
- { "ethernet_present", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_receiver_tm_t, ethernet_present) }, \
- { "ethernet_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_receiver_tm_t, ethernet_status) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_receiver_tm_t, battery_voltage) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a receiver_tm 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
- * @param main_radio_present Boolean indicating the presence of the main radio
- * @param main_packet_tx_error_count Number of errors during send
- * @param main_tx_bitrate [b/s] Send bitrate
- * @param main_packet_rx_success_count Number of succesfull received mavlink packets
- * @param main_packet_rx_drop_count Number of dropped mavlink packets
- * @param main_rx_bitrate [b/s] Receive bitrate
- * @param main_rx_rssi [dBm] Receive RSSI
- * @param main_rx_fei [Hz] Receive frequency error index
- * @param payload_radio_present Boolean indicating the presence of the payload radio
- * @param payload_packet_tx_error_count Number of errors during send
- * @param payload_tx_bitrate [b/s] Send bitrate
- * @param payload_packet_rx_success_count Number of succesfull received mavlink packets
- * @param payload_packet_rx_drop_count Number of dropped mavlink packets
- * @param payload_rx_bitrate [b/s] Receive bitrate
- * @param payload_rx_rssi [dBm] Receive RSSI
- * @param payload_rx_fei [Hz] Receive frequency error index
- * @param ethernet_present Boolean indicating the presence of the ethernet module
- * @param ethernet_status Status flag indicating the status of the ethernet PHY
- * @param battery_voltage [V] Battery voltage
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_receiver_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, float main_rx_fei, uint8_t payload_radio_present, uint16_t payload_packet_tx_error_count, uint16_t payload_tx_bitrate, uint16_t payload_packet_rx_success_count, uint16_t payload_packet_rx_drop_count, uint16_t payload_rx_bitrate, float payload_rx_rssi, float payload_rx_fei, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RECEIVER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, main_rx_rssi);
- _mav_put_float(buf, 12, main_rx_fei);
- _mav_put_float(buf, 16, payload_rx_rssi);
- _mav_put_float(buf, 20, payload_rx_fei);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_uint16_t(buf, 28, main_packet_tx_error_count);
- _mav_put_uint16_t(buf, 30, main_tx_bitrate);
- _mav_put_uint16_t(buf, 32, main_packet_rx_success_count);
- _mav_put_uint16_t(buf, 34, main_packet_rx_drop_count);
- _mav_put_uint16_t(buf, 36, main_rx_bitrate);
- _mav_put_uint16_t(buf, 38, payload_packet_tx_error_count);
- _mav_put_uint16_t(buf, 40, payload_tx_bitrate);
- _mav_put_uint16_t(buf, 42, payload_packet_rx_success_count);
- _mav_put_uint16_t(buf, 44, payload_packet_rx_drop_count);
- _mav_put_uint16_t(buf, 46, payload_rx_bitrate);
- _mav_put_uint8_t(buf, 48, main_radio_present);
- _mav_put_uint8_t(buf, 49, payload_radio_present);
- _mav_put_uint8_t(buf, 50, ethernet_present);
- _mav_put_uint8_t(buf, 51, ethernet_status);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
-#else
- mavlink_receiver_tm_t packet;
- packet.timestamp = timestamp;
- packet.main_rx_rssi = main_rx_rssi;
- packet.main_rx_fei = main_rx_fei;
- packet.payload_rx_rssi = payload_rx_rssi;
- packet.payload_rx_fei = payload_rx_fei;
- packet.battery_voltage = battery_voltage;
- packet.main_packet_tx_error_count = main_packet_tx_error_count;
- packet.main_tx_bitrate = main_tx_bitrate;
- packet.main_packet_rx_success_count = main_packet_rx_success_count;
- packet.main_packet_rx_drop_count = main_packet_rx_drop_count;
- packet.main_rx_bitrate = main_rx_bitrate;
- packet.payload_packet_tx_error_count = payload_packet_tx_error_count;
- packet.payload_tx_bitrate = payload_tx_bitrate;
- packet.payload_packet_rx_success_count = payload_packet_rx_success_count;
- packet.payload_packet_rx_drop_count = payload_packet_rx_drop_count;
- packet.payload_rx_bitrate = payload_rx_bitrate;
- packet.main_radio_present = main_radio_present;
- packet.payload_radio_present = payload_radio_present;
- packet.ethernet_present = ethernet_present;
- packet.ethernet_status = ethernet_status;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RECEIVER_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-}
-
-/**
- * @brief Pack a receiver_tm 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
- * @param main_radio_present Boolean indicating the presence of the main radio
- * @param main_packet_tx_error_count Number of errors during send
- * @param main_tx_bitrate [b/s] Send bitrate
- * @param main_packet_rx_success_count Number of succesfull received mavlink packets
- * @param main_packet_rx_drop_count Number of dropped mavlink packets
- * @param main_rx_bitrate [b/s] Receive bitrate
- * @param main_rx_rssi [dBm] Receive RSSI
- * @param main_rx_fei [Hz] Receive frequency error index
- * @param payload_radio_present Boolean indicating the presence of the payload radio
- * @param payload_packet_tx_error_count Number of errors during send
- * @param payload_tx_bitrate [b/s] Send bitrate
- * @param payload_packet_rx_success_count Number of succesfull received mavlink packets
- * @param payload_packet_rx_drop_count Number of dropped mavlink packets
- * @param payload_rx_bitrate [b/s] Receive bitrate
- * @param payload_rx_rssi [dBm] Receive RSSI
- * @param payload_rx_fei [Hz] Receive frequency error index
- * @param ethernet_present Boolean indicating the presence of the ethernet module
- * @param ethernet_status Status flag indicating the status of the ethernet PHY
- * @param battery_voltage [V] Battery voltage
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_receiver_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t main_radio_present,uint16_t main_packet_tx_error_count,uint16_t main_tx_bitrate,uint16_t main_packet_rx_success_count,uint16_t main_packet_rx_drop_count,uint16_t main_rx_bitrate,float main_rx_rssi,float main_rx_fei,uint8_t payload_radio_present,uint16_t payload_packet_tx_error_count,uint16_t payload_tx_bitrate,uint16_t payload_packet_rx_success_count,uint16_t payload_packet_rx_drop_count,uint16_t payload_rx_bitrate,float payload_rx_rssi,float payload_rx_fei,uint8_t ethernet_present,uint8_t ethernet_status,float battery_voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RECEIVER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, main_rx_rssi);
- _mav_put_float(buf, 12, main_rx_fei);
- _mav_put_float(buf, 16, payload_rx_rssi);
- _mav_put_float(buf, 20, payload_rx_fei);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_uint16_t(buf, 28, main_packet_tx_error_count);
- _mav_put_uint16_t(buf, 30, main_tx_bitrate);
- _mav_put_uint16_t(buf, 32, main_packet_rx_success_count);
- _mav_put_uint16_t(buf, 34, main_packet_rx_drop_count);
- _mav_put_uint16_t(buf, 36, main_rx_bitrate);
- _mav_put_uint16_t(buf, 38, payload_packet_tx_error_count);
- _mav_put_uint16_t(buf, 40, payload_tx_bitrate);
- _mav_put_uint16_t(buf, 42, payload_packet_rx_success_count);
- _mav_put_uint16_t(buf, 44, payload_packet_rx_drop_count);
- _mav_put_uint16_t(buf, 46, payload_rx_bitrate);
- _mav_put_uint8_t(buf, 48, main_radio_present);
- _mav_put_uint8_t(buf, 49, payload_radio_present);
- _mav_put_uint8_t(buf, 50, ethernet_present);
- _mav_put_uint8_t(buf, 51, ethernet_status);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
-#else
- mavlink_receiver_tm_t packet;
- packet.timestamp = timestamp;
- packet.main_rx_rssi = main_rx_rssi;
- packet.main_rx_fei = main_rx_fei;
- packet.payload_rx_rssi = payload_rx_rssi;
- packet.payload_rx_fei = payload_rx_fei;
- packet.battery_voltage = battery_voltage;
- packet.main_packet_tx_error_count = main_packet_tx_error_count;
- packet.main_tx_bitrate = main_tx_bitrate;
- packet.main_packet_rx_success_count = main_packet_rx_success_count;
- packet.main_packet_rx_drop_count = main_packet_rx_drop_count;
- packet.main_rx_bitrate = main_rx_bitrate;
- packet.payload_packet_tx_error_count = payload_packet_tx_error_count;
- packet.payload_tx_bitrate = payload_tx_bitrate;
- packet.payload_packet_rx_success_count = payload_packet_rx_success_count;
- packet.payload_packet_rx_drop_count = payload_packet_rx_drop_count;
- packet.payload_rx_bitrate = payload_rx_bitrate;
- packet.main_radio_present = main_radio_present;
- packet.payload_radio_present = payload_radio_present;
- packet.ethernet_present = ethernet_present;
- packet.ethernet_status = ethernet_status;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RECEIVER_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-}
-
-/**
- * @brief Encode a receiver_tm 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 receiver_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_receiver_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_receiver_tm_t* receiver_tm)
-{
- return mavlink_msg_receiver_tm_pack(system_id, component_id, msg, receiver_tm->timestamp, receiver_tm->main_radio_present, receiver_tm->main_packet_tx_error_count, receiver_tm->main_tx_bitrate, receiver_tm->main_packet_rx_success_count, receiver_tm->main_packet_rx_drop_count, receiver_tm->main_rx_bitrate, receiver_tm->main_rx_rssi, receiver_tm->main_rx_fei, receiver_tm->payload_radio_present, receiver_tm->payload_packet_tx_error_count, receiver_tm->payload_tx_bitrate, receiver_tm->payload_packet_rx_success_count, receiver_tm->payload_packet_rx_drop_count, receiver_tm->payload_rx_bitrate, receiver_tm->payload_rx_rssi, receiver_tm->payload_rx_fei, receiver_tm->ethernet_present, receiver_tm->ethernet_status, receiver_tm->battery_voltage);
-}
-
-/**
- * @brief Encode a receiver_tm 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 receiver_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_receiver_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_receiver_tm_t* receiver_tm)
-{
- return mavlink_msg_receiver_tm_pack_chan(system_id, component_id, chan, msg, receiver_tm->timestamp, receiver_tm->main_radio_present, receiver_tm->main_packet_tx_error_count, receiver_tm->main_tx_bitrate, receiver_tm->main_packet_rx_success_count, receiver_tm->main_packet_rx_drop_count, receiver_tm->main_rx_bitrate, receiver_tm->main_rx_rssi, receiver_tm->main_rx_fei, receiver_tm->payload_radio_present, receiver_tm->payload_packet_tx_error_count, receiver_tm->payload_tx_bitrate, receiver_tm->payload_packet_rx_success_count, receiver_tm->payload_packet_rx_drop_count, receiver_tm->payload_rx_bitrate, receiver_tm->payload_rx_rssi, receiver_tm->payload_rx_fei, receiver_tm->ethernet_present, receiver_tm->ethernet_status, receiver_tm->battery_voltage);
-}
-
-/**
- * @brief Send a receiver_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp
- * @param main_radio_present Boolean indicating the presence of the main radio
- * @param main_packet_tx_error_count Number of errors during send
- * @param main_tx_bitrate [b/s] Send bitrate
- * @param main_packet_rx_success_count Number of succesfull received mavlink packets
- * @param main_packet_rx_drop_count Number of dropped mavlink packets
- * @param main_rx_bitrate [b/s] Receive bitrate
- * @param main_rx_rssi [dBm] Receive RSSI
- * @param main_rx_fei [Hz] Receive frequency error index
- * @param payload_radio_present Boolean indicating the presence of the payload radio
- * @param payload_packet_tx_error_count Number of errors during send
- * @param payload_tx_bitrate [b/s] Send bitrate
- * @param payload_packet_rx_success_count Number of succesfull received mavlink packets
- * @param payload_packet_rx_drop_count Number of dropped mavlink packets
- * @param payload_rx_bitrate [b/s] Receive bitrate
- * @param payload_rx_rssi [dBm] Receive RSSI
- * @param payload_rx_fei [Hz] Receive frequency error index
- * @param ethernet_present Boolean indicating the presence of the ethernet module
- * @param ethernet_status Status flag indicating the status of the ethernet PHY
- * @param battery_voltage [V] Battery voltage
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_receiver_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, float main_rx_fei, uint8_t payload_radio_present, uint16_t payload_packet_tx_error_count, uint16_t payload_tx_bitrate, uint16_t payload_packet_rx_success_count, uint16_t payload_packet_rx_drop_count, uint16_t payload_rx_bitrate, float payload_rx_rssi, float payload_rx_fei, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RECEIVER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, main_rx_rssi);
- _mav_put_float(buf, 12, main_rx_fei);
- _mav_put_float(buf, 16, payload_rx_rssi);
- _mav_put_float(buf, 20, payload_rx_fei);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_uint16_t(buf, 28, main_packet_tx_error_count);
- _mav_put_uint16_t(buf, 30, main_tx_bitrate);
- _mav_put_uint16_t(buf, 32, main_packet_rx_success_count);
- _mav_put_uint16_t(buf, 34, main_packet_rx_drop_count);
- _mav_put_uint16_t(buf, 36, main_rx_bitrate);
- _mav_put_uint16_t(buf, 38, payload_packet_tx_error_count);
- _mav_put_uint16_t(buf, 40, payload_tx_bitrate);
- _mav_put_uint16_t(buf, 42, payload_packet_rx_success_count);
- _mav_put_uint16_t(buf, 44, payload_packet_rx_drop_count);
- _mav_put_uint16_t(buf, 46, payload_rx_bitrate);
- _mav_put_uint8_t(buf, 48, main_radio_present);
- _mav_put_uint8_t(buf, 49, payload_radio_present);
- _mav_put_uint8_t(buf, 50, ethernet_present);
- _mav_put_uint8_t(buf, 51, ethernet_status);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, buf, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-#else
- mavlink_receiver_tm_t packet;
- packet.timestamp = timestamp;
- packet.main_rx_rssi = main_rx_rssi;
- packet.main_rx_fei = main_rx_fei;
- packet.payload_rx_rssi = payload_rx_rssi;
- packet.payload_rx_fei = payload_rx_fei;
- packet.battery_voltage = battery_voltage;
- packet.main_packet_tx_error_count = main_packet_tx_error_count;
- packet.main_tx_bitrate = main_tx_bitrate;
- packet.main_packet_rx_success_count = main_packet_rx_success_count;
- packet.main_packet_rx_drop_count = main_packet_rx_drop_count;
- packet.main_rx_bitrate = main_rx_bitrate;
- packet.payload_packet_tx_error_count = payload_packet_tx_error_count;
- packet.payload_tx_bitrate = payload_tx_bitrate;
- packet.payload_packet_rx_success_count = payload_packet_rx_success_count;
- packet.payload_packet_rx_drop_count = payload_packet_rx_drop_count;
- packet.payload_rx_bitrate = payload_rx_bitrate;
- packet.main_radio_present = main_radio_present;
- packet.payload_radio_present = payload_radio_present;
- packet.ethernet_present = ethernet_present;
- packet.ethernet_status = ethernet_status;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, (const char *)&packet, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a receiver_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_receiver_tm_send_struct(mavlink_channel_t chan, const mavlink_receiver_tm_t* receiver_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_receiver_tm_send(chan, receiver_tm->timestamp, receiver_tm->main_radio_present, receiver_tm->main_packet_tx_error_count, receiver_tm->main_tx_bitrate, receiver_tm->main_packet_rx_success_count, receiver_tm->main_packet_rx_drop_count, receiver_tm->main_rx_bitrate, receiver_tm->main_rx_rssi, receiver_tm->main_rx_fei, receiver_tm->payload_radio_present, receiver_tm->payload_packet_tx_error_count, receiver_tm->payload_tx_bitrate, receiver_tm->payload_packet_rx_success_count, receiver_tm->payload_packet_rx_drop_count, receiver_tm->payload_rx_bitrate, receiver_tm->payload_rx_rssi, receiver_tm->payload_rx_fei, receiver_tm->ethernet_present, receiver_tm->ethernet_status, receiver_tm->battery_voltage);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, (const char *)receiver_tm, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_RECEIVER_TM_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_receiver_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t main_radio_present, uint16_t main_packet_tx_error_count, uint16_t main_tx_bitrate, uint16_t main_packet_rx_success_count, uint16_t main_packet_rx_drop_count, uint16_t main_rx_bitrate, float main_rx_rssi, float main_rx_fei, uint8_t payload_radio_present, uint16_t payload_packet_tx_error_count, uint16_t payload_tx_bitrate, uint16_t payload_packet_rx_success_count, uint16_t payload_packet_rx_drop_count, uint16_t payload_rx_bitrate, float payload_rx_rssi, float payload_rx_fei, uint8_t ethernet_present, uint8_t ethernet_status, float battery_voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, main_rx_rssi);
- _mav_put_float(buf, 12, main_rx_fei);
- _mav_put_float(buf, 16, payload_rx_rssi);
- _mav_put_float(buf, 20, payload_rx_fei);
- _mav_put_float(buf, 24, battery_voltage);
- _mav_put_uint16_t(buf, 28, main_packet_tx_error_count);
- _mav_put_uint16_t(buf, 30, main_tx_bitrate);
- _mav_put_uint16_t(buf, 32, main_packet_rx_success_count);
- _mav_put_uint16_t(buf, 34, main_packet_rx_drop_count);
- _mav_put_uint16_t(buf, 36, main_rx_bitrate);
- _mav_put_uint16_t(buf, 38, payload_packet_tx_error_count);
- _mav_put_uint16_t(buf, 40, payload_tx_bitrate);
- _mav_put_uint16_t(buf, 42, payload_packet_rx_success_count);
- _mav_put_uint16_t(buf, 44, payload_packet_rx_drop_count);
- _mav_put_uint16_t(buf, 46, payload_rx_bitrate);
- _mav_put_uint8_t(buf, 48, main_radio_present);
- _mav_put_uint8_t(buf, 49, payload_radio_present);
- _mav_put_uint8_t(buf, 50, ethernet_present);
- _mav_put_uint8_t(buf, 51, ethernet_status);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, buf, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-#else
- mavlink_receiver_tm_t *packet = (mavlink_receiver_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->main_rx_rssi = main_rx_rssi;
- packet->main_rx_fei = main_rx_fei;
- packet->payload_rx_rssi = payload_rx_rssi;
- packet->payload_rx_fei = payload_rx_fei;
- packet->battery_voltage = battery_voltage;
- packet->main_packet_tx_error_count = main_packet_tx_error_count;
- packet->main_tx_bitrate = main_tx_bitrate;
- packet->main_packet_rx_success_count = main_packet_rx_success_count;
- packet->main_packet_rx_drop_count = main_packet_rx_drop_count;
- packet->main_rx_bitrate = main_rx_bitrate;
- packet->payload_packet_tx_error_count = payload_packet_tx_error_count;
- packet->payload_tx_bitrate = payload_tx_bitrate;
- packet->payload_packet_rx_success_count = payload_packet_rx_success_count;
- packet->payload_packet_rx_drop_count = payload_packet_rx_drop_count;
- packet->payload_rx_bitrate = payload_rx_bitrate;
- packet->main_radio_present = main_radio_present;
- packet->payload_radio_present = payload_radio_present;
- packet->ethernet_present = ethernet_present;
- packet->ethernet_status = ethernet_status;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, (const char *)packet, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE RECEIVER_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from receiver_tm message
- *
- * @return [us] Timestamp
- */
-static inline uint64_t mavlink_msg_receiver_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field main_radio_present from receiver_tm message
- *
- * @return Boolean indicating the presence of the main radio
- */
-static inline uint8_t mavlink_msg_receiver_tm_get_main_radio_present(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 48);
-}
-
-/**
- * @brief Get field main_packet_tx_error_count from receiver_tm message
- *
- * @return Number of errors during send
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_main_packet_tx_error_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 28);
-}
-
-/**
- * @brief Get field main_tx_bitrate from receiver_tm message
- *
- * @return [b/s] Send bitrate
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_main_tx_bitrate(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 30);
-}
-
-/**
- * @brief Get field main_packet_rx_success_count from receiver_tm message
- *
- * @return Number of succesfull received mavlink packets
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_main_packet_rx_success_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 32);
-}
-
-/**
- * @brief Get field main_packet_rx_drop_count from receiver_tm message
- *
- * @return Number of dropped mavlink packets
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_main_packet_rx_drop_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 34);
-}
-
-/**
- * @brief Get field main_rx_bitrate from receiver_tm message
- *
- * @return [b/s] Receive bitrate
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_main_rx_bitrate(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 36);
-}
-
-/**
- * @brief Get field main_rx_rssi from receiver_tm message
- *
- * @return [dBm] Receive RSSI
- */
-static inline float mavlink_msg_receiver_tm_get_main_rx_rssi(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field main_rx_fei from receiver_tm message
- *
- * @return [Hz] Receive frequency error index
- */
-static inline float mavlink_msg_receiver_tm_get_main_rx_fei(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field payload_radio_present from receiver_tm message
- *
- * @return Boolean indicating the presence of the payload radio
- */
-static inline uint8_t mavlink_msg_receiver_tm_get_payload_radio_present(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 49);
-}
-
-/**
- * @brief Get field payload_packet_tx_error_count from receiver_tm message
- *
- * @return Number of errors during send
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_payload_packet_tx_error_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 38);
-}
-
-/**
- * @brief Get field payload_tx_bitrate from receiver_tm message
- *
- * @return [b/s] Send bitrate
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_payload_tx_bitrate(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 40);
-}
-
-/**
- * @brief Get field payload_packet_rx_success_count from receiver_tm message
- *
- * @return Number of succesfull received mavlink packets
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_payload_packet_rx_success_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 42);
-}
-
-/**
- * @brief Get field payload_packet_rx_drop_count from receiver_tm message
- *
- * @return Number of dropped mavlink packets
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_payload_packet_rx_drop_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 44);
-}
-
-/**
- * @brief Get field payload_rx_bitrate from receiver_tm message
- *
- * @return [b/s] Receive bitrate
- */
-static inline uint16_t mavlink_msg_receiver_tm_get_payload_rx_bitrate(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 46);
-}
-
-/**
- * @brief Get field payload_rx_rssi from receiver_tm message
- *
- * @return [dBm] Receive RSSI
- */
-static inline float mavlink_msg_receiver_tm_get_payload_rx_rssi(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field payload_rx_fei from receiver_tm message
- *
- * @return [Hz] Receive frequency error index
- */
-static inline float mavlink_msg_receiver_tm_get_payload_rx_fei(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field ethernet_present from receiver_tm message
- *
- * @return Boolean indicating the presence of the ethernet module
- */
-static inline uint8_t mavlink_msg_receiver_tm_get_ethernet_present(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 50);
-}
-
-/**
- * @brief Get field ethernet_status from receiver_tm message
- *
- * @return Status flag indicating the status of the ethernet PHY
- */
-static inline uint8_t mavlink_msg_receiver_tm_get_ethernet_status(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 51);
-}
-
-/**
- * @brief Get field battery_voltage from receiver_tm message
- *
- * @return [V] Battery voltage
- */
-static inline float mavlink_msg_receiver_tm_get_battery_voltage(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Decode a receiver_tm message into a struct
- *
- * @param msg The message to decode
- * @param receiver_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_receiver_tm_decode(const mavlink_message_t* msg, mavlink_receiver_tm_t* receiver_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- receiver_tm->timestamp = mavlink_msg_receiver_tm_get_timestamp(msg);
- receiver_tm->main_rx_rssi = mavlink_msg_receiver_tm_get_main_rx_rssi(msg);
- receiver_tm->main_rx_fei = mavlink_msg_receiver_tm_get_main_rx_fei(msg);
- receiver_tm->payload_rx_rssi = mavlink_msg_receiver_tm_get_payload_rx_rssi(msg);
- receiver_tm->payload_rx_fei = mavlink_msg_receiver_tm_get_payload_rx_fei(msg);
- receiver_tm->battery_voltage = mavlink_msg_receiver_tm_get_battery_voltage(msg);
- receiver_tm->main_packet_tx_error_count = mavlink_msg_receiver_tm_get_main_packet_tx_error_count(msg);
- receiver_tm->main_tx_bitrate = mavlink_msg_receiver_tm_get_main_tx_bitrate(msg);
- receiver_tm->main_packet_rx_success_count = mavlink_msg_receiver_tm_get_main_packet_rx_success_count(msg);
- receiver_tm->main_packet_rx_drop_count = mavlink_msg_receiver_tm_get_main_packet_rx_drop_count(msg);
- receiver_tm->main_rx_bitrate = mavlink_msg_receiver_tm_get_main_rx_bitrate(msg);
- receiver_tm->payload_packet_tx_error_count = mavlink_msg_receiver_tm_get_payload_packet_tx_error_count(msg);
- receiver_tm->payload_tx_bitrate = mavlink_msg_receiver_tm_get_payload_tx_bitrate(msg);
- receiver_tm->payload_packet_rx_success_count = mavlink_msg_receiver_tm_get_payload_packet_rx_success_count(msg);
- receiver_tm->payload_packet_rx_drop_count = mavlink_msg_receiver_tm_get_payload_packet_rx_drop_count(msg);
- receiver_tm->payload_rx_bitrate = mavlink_msg_receiver_tm_get_payload_rx_bitrate(msg);
- receiver_tm->main_radio_present = mavlink_msg_receiver_tm_get_main_radio_present(msg);
- receiver_tm->payload_radio_present = mavlink_msg_receiver_tm_get_payload_radio_present(msg);
- receiver_tm->ethernet_present = mavlink_msg_receiver_tm_get_ethernet_present(msg);
- receiver_tm->ethernet_status = mavlink_msg_receiver_tm_get_ethernet_status(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_RECEIVER_TM_LEN? msg->len : MAVLINK_MSG_ID_RECEIVER_TM_LEN;
- memset(receiver_tm, 0, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
- memcpy(receiver_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_reset_servo_tc.h b/mavlink_lib/lyra/mavlink_msg_reset_servo_tc.h
deleted file mode 100644
index 3194a30241ddfb4d40efc96b727240c69f4842ac..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_reset_servo_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE RESET_SERVO_TC PACKING
-
-#define MAVLINK_MSG_ID_RESET_SERVO_TC 8
-
-
-typedef struct __mavlink_reset_servo_tc_t {
- uint8_t servo_id; /*< A member of the ServosList enum*/
-} mavlink_reset_servo_tc_t;
-
-#define MAVLINK_MSG_ID_RESET_SERVO_TC_LEN 1
-#define MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_8_LEN 1
-#define MAVLINK_MSG_ID_8_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_RESET_SERVO_TC_CRC 226
-#define MAVLINK_MSG_ID_8_CRC 226
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_RESET_SERVO_TC { \
- 8, \
- "RESET_SERVO_TC", \
- 1, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_reset_servo_tc_t, servo_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_RESET_SERVO_TC { \
- "RESET_SERVO_TC", \
- 1, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_reset_servo_tc_t, servo_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a reset_servo_tc 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 servo_id A member of the ServosList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_reset_servo_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RESET_SERVO_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN);
-#else
- mavlink_reset_servo_tc_t packet;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RESET_SERVO_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-}
-
-/**
- * @brief Pack a reset_servo_tc 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 servo_id A member of the ServosList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_reset_servo_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RESET_SERVO_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN);
-#else
- mavlink_reset_servo_tc_t packet;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RESET_SERVO_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-}
-
-/**
- * @brief Encode a reset_servo_tc 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 reset_servo_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_reset_servo_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_reset_servo_tc_t* reset_servo_tc)
-{
- return mavlink_msg_reset_servo_tc_pack(system_id, component_id, msg, reset_servo_tc->servo_id);
-}
-
-/**
- * @brief Encode a reset_servo_tc 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 reset_servo_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_reset_servo_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_reset_servo_tc_t* reset_servo_tc)
-{
- return mavlink_msg_reset_servo_tc_pack_chan(system_id, component_id, chan, msg, reset_servo_tc->servo_id);
-}
-
-/**
- * @brief Send a reset_servo_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param servo_id A member of the ServosList enum
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_reset_servo_tc_send(mavlink_channel_t chan, uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RESET_SERVO_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESET_SERVO_TC, buf, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-#else
- mavlink_reset_servo_tc_t packet;
- packet.servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESET_SERVO_TC, (const char *)&packet, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a reset_servo_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_reset_servo_tc_send_struct(mavlink_channel_t chan, const mavlink_reset_servo_tc_t* reset_servo_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_reset_servo_tc_send(chan, reset_servo_tc->servo_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESET_SERVO_TC, (const char *)reset_servo_tc, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_RESET_SERVO_TC_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_reset_servo_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESET_SERVO_TC, buf, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-#else
- mavlink_reset_servo_tc_t *packet = (mavlink_reset_servo_tc_t *)msgbuf;
- packet->servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESET_SERVO_TC, (const char *)packet, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE RESET_SERVO_TC UNPACKING
-
-
-/**
- * @brief Get field servo_id from reset_servo_tc message
- *
- * @return A member of the ServosList enum
- */
-static inline uint8_t mavlink_msg_reset_servo_tc_get_servo_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a reset_servo_tc message into a struct
- *
- * @param msg The message to decode
- * @param reset_servo_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_reset_servo_tc_decode(const mavlink_message_t* msg, mavlink_reset_servo_tc_t* reset_servo_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- reset_servo_tc->servo_id = mavlink_msg_reset_servo_tc_get_servo_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_RESET_SERVO_TC_LEN? msg->len : MAVLINK_MSG_ID_RESET_SERVO_TC_LEN;
- memset(reset_servo_tc, 0, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN);
- memcpy(reset_servo_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_rocket_flight_tm.h b/mavlink_lib/lyra/mavlink_msg_rocket_flight_tm.h
deleted file mode 100644
index e3949ca456e8719920b4822b1e08e708b2e51b26..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_rocket_flight_tm.h
+++ /dev/null
@@ -1,1488 +0,0 @@
-#pragma once
-// MESSAGE ROCKET_FLIGHT_TM PACKING
-
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM 208
-
-
-typedef struct __mavlink_rocket_flight_tm_t {
- uint64_t timestamp; /*< [us] Timestamp in microseconds*/
- float pressure_ada; /*< [Pa] Atmospheric pressure estimated by ADA*/
- float pressure_digi; /*< [Pa] Pressure from digital sensor*/
- float pressure_static; /*< [Pa] Pressure from static port*/
- float pressure_dpl; /*< [Pa] Pressure from deployment vane sensor*/
- float airspeed_pitot; /*< [m/s] Pitot airspeed*/
- float altitude_agl; /*< [m] Altitude above ground level*/
- float ada_vert_speed; /*< [m/s] Vertical speed estimated by ADA*/
- float mea_mass; /*< [kg] Mass estimated by MEA*/
- float acc_x; /*< [m/s^2] Acceleration on X axis (body)*/
- float acc_y; /*< [m/s^2] Acceleration on Y axis (body)*/
- float acc_z; /*< [m/s^2] Acceleration on Z axis (body)*/
- float gyro_x; /*< [rad/s] Angular speed on X axis (body)*/
- float gyro_y; /*< [rad/s] Angular speed on Y axis (body)*/
- float gyro_z; /*< [rad/s] Angular speed on Z axis (body)*/
- float mag_x; /*< [uT] Magnetic field on X axis (body)*/
- float mag_y; /*< [uT] Magnetic field on Y axis (body)*/
- float mag_z; /*< [uT] Magnetic field on Z axis (body)*/
- float gps_lat; /*< [deg] Latitude*/
- float gps_lon; /*< [deg] Longitude*/
- float gps_alt; /*< [m] GPS Altitude*/
- float abk_angle; /*< [deg] Air Brakes angle*/
- float nas_n; /*< [deg] Navigation system estimated noth position*/
- float nas_e; /*< [deg] Navigation system estimated east position*/
- float nas_d; /*< [m] Navigation system estimated down position*/
- float nas_vn; /*< [m/s] Navigation system estimated north velocity*/
- float nas_ve; /*< [m/s] Navigation system estimated east velocity*/
- float nas_vd; /*< [m/s] Navigation system estimated down velocity*/
- float nas_qx; /*< [deg] Navigation system estimated attitude (qx)*/
- float nas_qy; /*< [deg] Navigation system estimated attitude (qy)*/
- float nas_qz; /*< [deg] Navigation system estimated attitude (qz)*/
- float nas_qw; /*< [deg] Navigation system estimated attitude (qw)*/
- float nas_bias_x; /*< Navigation system gyroscope bias on x axis*/
- float nas_bias_y; /*< Navigation system gyroscope bias on y axis*/
- float nas_bias_z; /*< Navigation system gyroscope bias on z axis*/
- float pin_quick_connector; /*< Quick connector detach pin */
- float battery_voltage; /*< [V] Battery voltage*/
- float cam_battery_voltage; /*< [V] Camera battery voltage*/
- float current_consumption; /*< [A] Battery current*/
- float temperature; /*< [degC] Temperature*/
- uint8_t ada_state; /*< ADA Controller State*/
- uint8_t fmm_state; /*< Flight Mode Manager State*/
- uint8_t dpl_state; /*< Deployment Controller State*/
- uint8_t abk_state; /*< Airbrake FSM state*/
- uint8_t nas_state; /*< Navigation System FSM State*/
- uint8_t mea_state; /*< MEA Controller State*/
- uint8_t gps_fix; /*< GPS fix (1 = fix, 0 = no fix)*/
- uint8_t pin_launch; /*< Launch pin status (1 = connected, 0 = disconnected)*/
- uint8_t pin_nosecone; /*< Nosecone pin status (1 = connected, 0 = disconnected)*/
- uint8_t pin_expulsion; /*< Servo sensor status (1 = actuated, 0 = idle)*/
- uint8_t cutter_presence; /*< Cutter presence status (1 = present, 0 = missing)*/
- int8_t logger_error; /*< Logger error (0 = no error, -1 otherwise)*/
-} mavlink_rocket_flight_tm_t;
-
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN 176
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN 176
-#define MAVLINK_MSG_ID_208_LEN 176
-#define MAVLINK_MSG_ID_208_MIN_LEN 176
-
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC 214
-#define MAVLINK_MSG_ID_208_CRC 214
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM { \
- 208, \
- "ROCKET_FLIGHT_TM", \
- 52, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_flight_tm_t, timestamp) }, \
- { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_rocket_flight_tm_t, ada_state) }, \
- { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_rocket_flight_tm_t, fmm_state) }, \
- { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_rocket_flight_tm_t, dpl_state) }, \
- { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 167, offsetof(mavlink_rocket_flight_tm_t, abk_state) }, \
- { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 168, offsetof(mavlink_rocket_flight_tm_t, nas_state) }, \
- { "mea_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 169, offsetof(mavlink_rocket_flight_tm_t, mea_state) }, \
- { "pressure_ada", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_rocket_flight_tm_t, pressure_ada) }, \
- { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_rocket_flight_tm_t, pressure_digi) }, \
- { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_rocket_flight_tm_t, pressure_static) }, \
- { "pressure_dpl", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_rocket_flight_tm_t, pressure_dpl) }, \
- { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_rocket_flight_tm_t, airspeed_pitot) }, \
- { "altitude_agl", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_rocket_flight_tm_t, altitude_agl) }, \
- { "ada_vert_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_rocket_flight_tm_t, ada_vert_speed) }, \
- { "mea_mass", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_rocket_flight_tm_t, mea_mass) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_rocket_flight_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_rocket_flight_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_rocket_flight_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_rocket_flight_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_rocket_flight_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_rocket_flight_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_flight_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_flight_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_flight_tm_t, mag_z) }, \
- { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 170, offsetof(mavlink_rocket_flight_tm_t, gps_fix) }, \
- { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_flight_tm_t, gps_lat) }, \
- { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_flight_tm_t, gps_lon) }, \
- { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_flight_tm_t, gps_alt) }, \
- { "abk_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_rocket_flight_tm_t, abk_angle) }, \
- { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_rocket_flight_tm_t, nas_n) }, \
- { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_rocket_flight_tm_t, nas_e) }, \
- { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_rocket_flight_tm_t, nas_d) }, \
- { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_rocket_flight_tm_t, nas_vn) }, \
- { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_rocket_flight_tm_t, nas_ve) }, \
- { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_rocket_flight_tm_t, nas_vd) }, \
- { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_rocket_flight_tm_t, nas_qx) }, \
- { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_rocket_flight_tm_t, nas_qy) }, \
- { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_rocket_flight_tm_t, nas_qz) }, \
- { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_rocket_flight_tm_t, nas_qw) }, \
- { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_rocket_flight_tm_t, nas_bias_x) }, \
- { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_rocket_flight_tm_t, nas_bias_y) }, \
- { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_rocket_flight_tm_t, nas_bias_z) }, \
- { "pin_quick_connector", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_rocket_flight_tm_t, pin_quick_connector) }, \
- { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 171, offsetof(mavlink_rocket_flight_tm_t, pin_launch) }, \
- { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 172, offsetof(mavlink_rocket_flight_tm_t, pin_nosecone) }, \
- { "pin_expulsion", NULL, MAVLINK_TYPE_UINT8_T, 0, 173, offsetof(mavlink_rocket_flight_tm_t, pin_expulsion) }, \
- { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 174, offsetof(mavlink_rocket_flight_tm_t, cutter_presence) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, battery_voltage) }, \
- { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_rocket_flight_tm_t, cam_battery_voltage) }, \
- { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 156, offsetof(mavlink_rocket_flight_tm_t, current_consumption) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 160, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \
- { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 175, offsetof(mavlink_rocket_flight_tm_t, logger_error) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM { \
- "ROCKET_FLIGHT_TM", \
- 52, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_flight_tm_t, timestamp) }, \
- { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_rocket_flight_tm_t, ada_state) }, \
- { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_rocket_flight_tm_t, fmm_state) }, \
- { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_rocket_flight_tm_t, dpl_state) }, \
- { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 167, offsetof(mavlink_rocket_flight_tm_t, abk_state) }, \
- { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 168, offsetof(mavlink_rocket_flight_tm_t, nas_state) }, \
- { "mea_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 169, offsetof(mavlink_rocket_flight_tm_t, mea_state) }, \
- { "pressure_ada", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_rocket_flight_tm_t, pressure_ada) }, \
- { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_rocket_flight_tm_t, pressure_digi) }, \
- { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_rocket_flight_tm_t, pressure_static) }, \
- { "pressure_dpl", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_rocket_flight_tm_t, pressure_dpl) }, \
- { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_rocket_flight_tm_t, airspeed_pitot) }, \
- { "altitude_agl", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_rocket_flight_tm_t, altitude_agl) }, \
- { "ada_vert_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_rocket_flight_tm_t, ada_vert_speed) }, \
- { "mea_mass", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_rocket_flight_tm_t, mea_mass) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_rocket_flight_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_rocket_flight_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_rocket_flight_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_rocket_flight_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_rocket_flight_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_rocket_flight_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_flight_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_flight_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_flight_tm_t, mag_z) }, \
- { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 170, offsetof(mavlink_rocket_flight_tm_t, gps_fix) }, \
- { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_flight_tm_t, gps_lat) }, \
- { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_flight_tm_t, gps_lon) }, \
- { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_flight_tm_t, gps_alt) }, \
- { "abk_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_rocket_flight_tm_t, abk_angle) }, \
- { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_rocket_flight_tm_t, nas_n) }, \
- { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_rocket_flight_tm_t, nas_e) }, \
- { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_rocket_flight_tm_t, nas_d) }, \
- { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_rocket_flight_tm_t, nas_vn) }, \
- { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_rocket_flight_tm_t, nas_ve) }, \
- { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_rocket_flight_tm_t, nas_vd) }, \
- { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_rocket_flight_tm_t, nas_qx) }, \
- { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_rocket_flight_tm_t, nas_qy) }, \
- { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_rocket_flight_tm_t, nas_qz) }, \
- { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_rocket_flight_tm_t, nas_qw) }, \
- { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_rocket_flight_tm_t, nas_bias_x) }, \
- { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_rocket_flight_tm_t, nas_bias_y) }, \
- { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_rocket_flight_tm_t, nas_bias_z) }, \
- { "pin_quick_connector", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_rocket_flight_tm_t, pin_quick_connector) }, \
- { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 171, offsetof(mavlink_rocket_flight_tm_t, pin_launch) }, \
- { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 172, offsetof(mavlink_rocket_flight_tm_t, pin_nosecone) }, \
- { "pin_expulsion", NULL, MAVLINK_TYPE_UINT8_T, 0, 173, offsetof(mavlink_rocket_flight_tm_t, pin_expulsion) }, \
- { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 174, offsetof(mavlink_rocket_flight_tm_t, cutter_presence) }, \
- { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, battery_voltage) }, \
- { "cam_battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_rocket_flight_tm_t, cam_battery_voltage) }, \
- { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 156, offsetof(mavlink_rocket_flight_tm_t, current_consumption) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 160, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \
- { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 175, offsetof(mavlink_rocket_flight_tm_t, logger_error) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a rocket_flight_tm 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 in microseconds
- * @param ada_state ADA Controller State
- * @param fmm_state Flight Mode Manager State
- * @param dpl_state Deployment Controller State
- * @param abk_state Airbrake FSM state
- * @param nas_state Navigation System FSM State
- * @param mea_state MEA Controller State
- * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane sensor
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param altitude_agl [m] Altitude above ground level
- * @param ada_vert_speed [m/s] Vertical speed estimated by ADA
- * @param mea_mass [kg] Mass estimated by MEA
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param abk_angle [deg] Air Brakes angle
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on y axis
- * @param nas_bias_z Navigation system gyroscope bias on z axis
- * @param pin_quick_connector Quick connector detach pin
- * @param pin_launch Launch pin status (1 = connected, 0 = disconnected)
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param pin_expulsion Servo sensor status (1 = actuated, 0 = idle)
- * @param cutter_presence Cutter presence status (1 = present, 0 = missing)
- * @param battery_voltage [V] Battery voltage
- * @param cam_battery_voltage [V] Camera battery voltage
- * @param current_consumption [A] Battery current
- * @param temperature [degC] Temperature
- * @param logger_error Logger error (0 = no error, -1 otherwise)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float pin_quick_connector, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float current_consumption, float temperature, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_ada);
- _mav_put_float(buf, 12, pressure_digi);
- _mav_put_float(buf, 16, pressure_static);
- _mav_put_float(buf, 20, pressure_dpl);
- _mav_put_float(buf, 24, airspeed_pitot);
- _mav_put_float(buf, 28, altitude_agl);
- _mav_put_float(buf, 32, ada_vert_speed);
- _mav_put_float(buf, 36, mea_mass);
- _mav_put_float(buf, 40, acc_x);
- _mav_put_float(buf, 44, acc_y);
- _mav_put_float(buf, 48, acc_z);
- _mav_put_float(buf, 52, gyro_x);
- _mav_put_float(buf, 56, gyro_y);
- _mav_put_float(buf, 60, gyro_z);
- _mav_put_float(buf, 64, mag_x);
- _mav_put_float(buf, 68, mag_y);
- _mav_put_float(buf, 72, mag_z);
- _mav_put_float(buf, 76, gps_lat);
- _mav_put_float(buf, 80, gps_lon);
- _mav_put_float(buf, 84, gps_alt);
- _mav_put_float(buf, 88, abk_angle);
- _mav_put_float(buf, 92, nas_n);
- _mav_put_float(buf, 96, nas_e);
- _mav_put_float(buf, 100, nas_d);
- _mav_put_float(buf, 104, nas_vn);
- _mav_put_float(buf, 108, nas_ve);
- _mav_put_float(buf, 112, nas_vd);
- _mav_put_float(buf, 116, nas_qx);
- _mav_put_float(buf, 120, nas_qy);
- _mav_put_float(buf, 124, nas_qz);
- _mav_put_float(buf, 128, nas_qw);
- _mav_put_float(buf, 132, nas_bias_x);
- _mav_put_float(buf, 136, nas_bias_y);
- _mav_put_float(buf, 140, nas_bias_z);
- _mav_put_float(buf, 144, pin_quick_connector);
- _mav_put_float(buf, 148, battery_voltage);
- _mav_put_float(buf, 152, cam_battery_voltage);
- _mav_put_float(buf, 156, current_consumption);
- _mav_put_float(buf, 160, temperature);
- _mav_put_uint8_t(buf, 164, ada_state);
- _mav_put_uint8_t(buf, 165, fmm_state);
- _mav_put_uint8_t(buf, 166, dpl_state);
- _mav_put_uint8_t(buf, 167, abk_state);
- _mav_put_uint8_t(buf, 168, nas_state);
- _mav_put_uint8_t(buf, 169, mea_state);
- _mav_put_uint8_t(buf, 170, gps_fix);
- _mav_put_uint8_t(buf, 171, pin_launch);
- _mav_put_uint8_t(buf, 172, pin_nosecone);
- _mav_put_uint8_t(buf, 173, pin_expulsion);
- _mav_put_uint8_t(buf, 174, cutter_presence);
- _mav_put_int8_t(buf, 175, logger_error);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
-#else
- mavlink_rocket_flight_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_ada = pressure_ada;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.pressure_dpl = pressure_dpl;
- packet.airspeed_pitot = airspeed_pitot;
- packet.altitude_agl = altitude_agl;
- packet.ada_vert_speed = ada_vert_speed;
- packet.mea_mass = mea_mass;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.abk_angle = abk_angle;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.pin_quick_connector = pin_quick_connector;
- packet.battery_voltage = battery_voltage;
- packet.cam_battery_voltage = cam_battery_voltage;
- packet.current_consumption = current_consumption;
- packet.temperature = temperature;
- packet.ada_state = ada_state;
- packet.fmm_state = fmm_state;
- packet.dpl_state = dpl_state;
- packet.abk_state = abk_state;
- packet.nas_state = nas_state;
- packet.mea_state = mea_state;
- packet.gps_fix = gps_fix;
- packet.pin_launch = pin_launch;
- packet.pin_nosecone = pin_nosecone;
- packet.pin_expulsion = pin_expulsion;
- packet.cutter_presence = cutter_presence;
- packet.logger_error = logger_error;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ROCKET_FLIGHT_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-}
-
-/**
- * @brief Pack a rocket_flight_tm 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 in microseconds
- * @param ada_state ADA Controller State
- * @param fmm_state Flight Mode Manager State
- * @param dpl_state Deployment Controller State
- * @param abk_state Airbrake FSM state
- * @param nas_state Navigation System FSM State
- * @param mea_state MEA Controller State
- * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane sensor
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param altitude_agl [m] Altitude above ground level
- * @param ada_vert_speed [m/s] Vertical speed estimated by ADA
- * @param mea_mass [kg] Mass estimated by MEA
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param abk_angle [deg] Air Brakes angle
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on y axis
- * @param nas_bias_z Navigation system gyroscope bias on z axis
- * @param pin_quick_connector Quick connector detach pin
- * @param pin_launch Launch pin status (1 = connected, 0 = disconnected)
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param pin_expulsion Servo sensor status (1 = actuated, 0 = idle)
- * @param cutter_presence Cutter presence status (1 = present, 0 = missing)
- * @param battery_voltage [V] Battery voltage
- * @param cam_battery_voltage [V] Camera battery voltage
- * @param current_consumption [A] Battery current
- * @param temperature [degC] Temperature
- * @param logger_error Logger error (0 = no error, -1 otherwise)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t ada_state,uint8_t fmm_state,uint8_t dpl_state,uint8_t abk_state,uint8_t nas_state,uint8_t mea_state,float pressure_ada,float pressure_digi,float pressure_static,float pressure_dpl,float airspeed_pitot,float altitude_agl,float ada_vert_speed,float mea_mass,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float abk_angle,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,float pin_quick_connector,uint8_t pin_launch,uint8_t pin_nosecone,uint8_t pin_expulsion,uint8_t cutter_presence,float battery_voltage,float cam_battery_voltage,float current_consumption,float temperature,int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_ada);
- _mav_put_float(buf, 12, pressure_digi);
- _mav_put_float(buf, 16, pressure_static);
- _mav_put_float(buf, 20, pressure_dpl);
- _mav_put_float(buf, 24, airspeed_pitot);
- _mav_put_float(buf, 28, altitude_agl);
- _mav_put_float(buf, 32, ada_vert_speed);
- _mav_put_float(buf, 36, mea_mass);
- _mav_put_float(buf, 40, acc_x);
- _mav_put_float(buf, 44, acc_y);
- _mav_put_float(buf, 48, acc_z);
- _mav_put_float(buf, 52, gyro_x);
- _mav_put_float(buf, 56, gyro_y);
- _mav_put_float(buf, 60, gyro_z);
- _mav_put_float(buf, 64, mag_x);
- _mav_put_float(buf, 68, mag_y);
- _mav_put_float(buf, 72, mag_z);
- _mav_put_float(buf, 76, gps_lat);
- _mav_put_float(buf, 80, gps_lon);
- _mav_put_float(buf, 84, gps_alt);
- _mav_put_float(buf, 88, abk_angle);
- _mav_put_float(buf, 92, nas_n);
- _mav_put_float(buf, 96, nas_e);
- _mav_put_float(buf, 100, nas_d);
- _mav_put_float(buf, 104, nas_vn);
- _mav_put_float(buf, 108, nas_ve);
- _mav_put_float(buf, 112, nas_vd);
- _mav_put_float(buf, 116, nas_qx);
- _mav_put_float(buf, 120, nas_qy);
- _mav_put_float(buf, 124, nas_qz);
- _mav_put_float(buf, 128, nas_qw);
- _mav_put_float(buf, 132, nas_bias_x);
- _mav_put_float(buf, 136, nas_bias_y);
- _mav_put_float(buf, 140, nas_bias_z);
- _mav_put_float(buf, 144, pin_quick_connector);
- _mav_put_float(buf, 148, battery_voltage);
- _mav_put_float(buf, 152, cam_battery_voltage);
- _mav_put_float(buf, 156, current_consumption);
- _mav_put_float(buf, 160, temperature);
- _mav_put_uint8_t(buf, 164, ada_state);
- _mav_put_uint8_t(buf, 165, fmm_state);
- _mav_put_uint8_t(buf, 166, dpl_state);
- _mav_put_uint8_t(buf, 167, abk_state);
- _mav_put_uint8_t(buf, 168, nas_state);
- _mav_put_uint8_t(buf, 169, mea_state);
- _mav_put_uint8_t(buf, 170, gps_fix);
- _mav_put_uint8_t(buf, 171, pin_launch);
- _mav_put_uint8_t(buf, 172, pin_nosecone);
- _mav_put_uint8_t(buf, 173, pin_expulsion);
- _mav_put_uint8_t(buf, 174, cutter_presence);
- _mav_put_int8_t(buf, 175, logger_error);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
-#else
- mavlink_rocket_flight_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_ada = pressure_ada;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.pressure_dpl = pressure_dpl;
- packet.airspeed_pitot = airspeed_pitot;
- packet.altitude_agl = altitude_agl;
- packet.ada_vert_speed = ada_vert_speed;
- packet.mea_mass = mea_mass;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.abk_angle = abk_angle;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.pin_quick_connector = pin_quick_connector;
- packet.battery_voltage = battery_voltage;
- packet.cam_battery_voltage = cam_battery_voltage;
- packet.current_consumption = current_consumption;
- packet.temperature = temperature;
- packet.ada_state = ada_state;
- packet.fmm_state = fmm_state;
- packet.dpl_state = dpl_state;
- packet.abk_state = abk_state;
- packet.nas_state = nas_state;
- packet.mea_state = mea_state;
- packet.gps_fix = gps_fix;
- packet.pin_launch = pin_launch;
- packet.pin_nosecone = pin_nosecone;
- packet.pin_expulsion = pin_expulsion;
- packet.cutter_presence = cutter_presence;
- packet.logger_error = logger_error;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ROCKET_FLIGHT_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-}
-
-/**
- * @brief Encode a rocket_flight_tm 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 rocket_flight_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_rocket_flight_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rocket_flight_tm_t* rocket_flight_tm)
-{
- return mavlink_msg_rocket_flight_tm_pack(system_id, component_id, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_quick_connector, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->cam_battery_voltage, rocket_flight_tm->current_consumption, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
-}
-
-/**
- * @brief Encode a rocket_flight_tm 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 rocket_flight_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_rocket_flight_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rocket_flight_tm_t* rocket_flight_tm)
-{
- return mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, chan, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_quick_connector, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->cam_battery_voltage, rocket_flight_tm->current_consumption, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
-}
-
-/**
- * @brief Send a rocket_flight_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp in microseconds
- * @param ada_state ADA Controller State
- * @param fmm_state Flight Mode Manager State
- * @param dpl_state Deployment Controller State
- * @param abk_state Airbrake FSM state
- * @param nas_state Navigation System FSM State
- * @param mea_state MEA Controller State
- * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane sensor
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param altitude_agl [m] Altitude above ground level
- * @param ada_vert_speed [m/s] Vertical speed estimated by ADA
- * @param mea_mass [kg] Mass estimated by MEA
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param abk_angle [deg] Air Brakes angle
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on y axis
- * @param nas_bias_z Navigation system gyroscope bias on z axis
- * @param pin_quick_connector Quick connector detach pin
- * @param pin_launch Launch pin status (1 = connected, 0 = disconnected)
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param pin_expulsion Servo sensor status (1 = actuated, 0 = idle)
- * @param cutter_presence Cutter presence status (1 = present, 0 = missing)
- * @param battery_voltage [V] Battery voltage
- * @param cam_battery_voltage [V] Camera battery voltage
- * @param current_consumption [A] Battery current
- * @param temperature [degC] Temperature
- * @param logger_error Logger error (0 = no error, -1 otherwise)
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float pin_quick_connector, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float current_consumption, float temperature, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_ada);
- _mav_put_float(buf, 12, pressure_digi);
- _mav_put_float(buf, 16, pressure_static);
- _mav_put_float(buf, 20, pressure_dpl);
- _mav_put_float(buf, 24, airspeed_pitot);
- _mav_put_float(buf, 28, altitude_agl);
- _mav_put_float(buf, 32, ada_vert_speed);
- _mav_put_float(buf, 36, mea_mass);
- _mav_put_float(buf, 40, acc_x);
- _mav_put_float(buf, 44, acc_y);
- _mav_put_float(buf, 48, acc_z);
- _mav_put_float(buf, 52, gyro_x);
- _mav_put_float(buf, 56, gyro_y);
- _mav_put_float(buf, 60, gyro_z);
- _mav_put_float(buf, 64, mag_x);
- _mav_put_float(buf, 68, mag_y);
- _mav_put_float(buf, 72, mag_z);
- _mav_put_float(buf, 76, gps_lat);
- _mav_put_float(buf, 80, gps_lon);
- _mav_put_float(buf, 84, gps_alt);
- _mav_put_float(buf, 88, abk_angle);
- _mav_put_float(buf, 92, nas_n);
- _mav_put_float(buf, 96, nas_e);
- _mav_put_float(buf, 100, nas_d);
- _mav_put_float(buf, 104, nas_vn);
- _mav_put_float(buf, 108, nas_ve);
- _mav_put_float(buf, 112, nas_vd);
- _mav_put_float(buf, 116, nas_qx);
- _mav_put_float(buf, 120, nas_qy);
- _mav_put_float(buf, 124, nas_qz);
- _mav_put_float(buf, 128, nas_qw);
- _mav_put_float(buf, 132, nas_bias_x);
- _mav_put_float(buf, 136, nas_bias_y);
- _mav_put_float(buf, 140, nas_bias_z);
- _mav_put_float(buf, 144, pin_quick_connector);
- _mav_put_float(buf, 148, battery_voltage);
- _mav_put_float(buf, 152, cam_battery_voltage);
- _mav_put_float(buf, 156, current_consumption);
- _mav_put_float(buf, 160, temperature);
- _mav_put_uint8_t(buf, 164, ada_state);
- _mav_put_uint8_t(buf, 165, fmm_state);
- _mav_put_uint8_t(buf, 166, dpl_state);
- _mav_put_uint8_t(buf, 167, abk_state);
- _mav_put_uint8_t(buf, 168, nas_state);
- _mav_put_uint8_t(buf, 169, mea_state);
- _mav_put_uint8_t(buf, 170, gps_fix);
- _mav_put_uint8_t(buf, 171, pin_launch);
- _mav_put_uint8_t(buf, 172, pin_nosecone);
- _mav_put_uint8_t(buf, 173, pin_expulsion);
- _mav_put_uint8_t(buf, 174, cutter_presence);
- _mav_put_int8_t(buf, 175, logger_error);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-#else
- mavlink_rocket_flight_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_ada = pressure_ada;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.pressure_dpl = pressure_dpl;
- packet.airspeed_pitot = airspeed_pitot;
- packet.altitude_agl = altitude_agl;
- packet.ada_vert_speed = ada_vert_speed;
- packet.mea_mass = mea_mass;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.abk_angle = abk_angle;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.pin_quick_connector = pin_quick_connector;
- packet.battery_voltage = battery_voltage;
- packet.cam_battery_voltage = cam_battery_voltage;
- packet.current_consumption = current_consumption;
- packet.temperature = temperature;
- packet.ada_state = ada_state;
- packet.fmm_state = fmm_state;
- packet.dpl_state = dpl_state;
- packet.abk_state = abk_state;
- packet.nas_state = nas_state;
- packet.mea_state = mea_state;
- packet.gps_fix = gps_fix;
- packet.pin_launch = pin_launch;
- packet.pin_nosecone = pin_nosecone;
- packet.pin_expulsion = pin_expulsion;
- packet.cutter_presence = cutter_presence;
- packet.logger_error = logger_error;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, (const char *)&packet, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a rocket_flight_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_rocket_flight_tm_send_struct(mavlink_channel_t chan, const mavlink_rocket_flight_tm_t* rocket_flight_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_rocket_flight_tm_send(chan, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->mea_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->mea_mass, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_quick_connector, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->battery_voltage, rocket_flight_tm->cam_battery_voltage, rocket_flight_tm->current_consumption, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, (const char *)rocket_flight_tm, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_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_rocket_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, uint8_t mea_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float mea_mass, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float pin_quick_connector, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float battery_voltage, float cam_battery_voltage, float current_consumption, float temperature, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_ada);
- _mav_put_float(buf, 12, pressure_digi);
- _mav_put_float(buf, 16, pressure_static);
- _mav_put_float(buf, 20, pressure_dpl);
- _mav_put_float(buf, 24, airspeed_pitot);
- _mav_put_float(buf, 28, altitude_agl);
- _mav_put_float(buf, 32, ada_vert_speed);
- _mav_put_float(buf, 36, mea_mass);
- _mav_put_float(buf, 40, acc_x);
- _mav_put_float(buf, 44, acc_y);
- _mav_put_float(buf, 48, acc_z);
- _mav_put_float(buf, 52, gyro_x);
- _mav_put_float(buf, 56, gyro_y);
- _mav_put_float(buf, 60, gyro_z);
- _mav_put_float(buf, 64, mag_x);
- _mav_put_float(buf, 68, mag_y);
- _mav_put_float(buf, 72, mag_z);
- _mav_put_float(buf, 76, gps_lat);
- _mav_put_float(buf, 80, gps_lon);
- _mav_put_float(buf, 84, gps_alt);
- _mav_put_float(buf, 88, abk_angle);
- _mav_put_float(buf, 92, nas_n);
- _mav_put_float(buf, 96, nas_e);
- _mav_put_float(buf, 100, nas_d);
- _mav_put_float(buf, 104, nas_vn);
- _mav_put_float(buf, 108, nas_ve);
- _mav_put_float(buf, 112, nas_vd);
- _mav_put_float(buf, 116, nas_qx);
- _mav_put_float(buf, 120, nas_qy);
- _mav_put_float(buf, 124, nas_qz);
- _mav_put_float(buf, 128, nas_qw);
- _mav_put_float(buf, 132, nas_bias_x);
- _mav_put_float(buf, 136, nas_bias_y);
- _mav_put_float(buf, 140, nas_bias_z);
- _mav_put_float(buf, 144, pin_quick_connector);
- _mav_put_float(buf, 148, battery_voltage);
- _mav_put_float(buf, 152, cam_battery_voltage);
- _mav_put_float(buf, 156, current_consumption);
- _mav_put_float(buf, 160, temperature);
- _mav_put_uint8_t(buf, 164, ada_state);
- _mav_put_uint8_t(buf, 165, fmm_state);
- _mav_put_uint8_t(buf, 166, dpl_state);
- _mav_put_uint8_t(buf, 167, abk_state);
- _mav_put_uint8_t(buf, 168, nas_state);
- _mav_put_uint8_t(buf, 169, mea_state);
- _mav_put_uint8_t(buf, 170, gps_fix);
- _mav_put_uint8_t(buf, 171, pin_launch);
- _mav_put_uint8_t(buf, 172, pin_nosecone);
- _mav_put_uint8_t(buf, 173, pin_expulsion);
- _mav_put_uint8_t(buf, 174, cutter_presence);
- _mav_put_int8_t(buf, 175, logger_error);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-#else
- mavlink_rocket_flight_tm_t *packet = (mavlink_rocket_flight_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->pressure_ada = pressure_ada;
- packet->pressure_digi = pressure_digi;
- packet->pressure_static = pressure_static;
- packet->pressure_dpl = pressure_dpl;
- packet->airspeed_pitot = airspeed_pitot;
- packet->altitude_agl = altitude_agl;
- packet->ada_vert_speed = ada_vert_speed;
- packet->mea_mass = mea_mass;
- packet->acc_x = acc_x;
- packet->acc_y = acc_y;
- packet->acc_z = acc_z;
- packet->gyro_x = gyro_x;
- packet->gyro_y = gyro_y;
- packet->gyro_z = gyro_z;
- packet->mag_x = mag_x;
- packet->mag_y = mag_y;
- packet->mag_z = mag_z;
- packet->gps_lat = gps_lat;
- packet->gps_lon = gps_lon;
- packet->gps_alt = gps_alt;
- packet->abk_angle = abk_angle;
- packet->nas_n = nas_n;
- packet->nas_e = nas_e;
- packet->nas_d = nas_d;
- packet->nas_vn = nas_vn;
- packet->nas_ve = nas_ve;
- packet->nas_vd = nas_vd;
- packet->nas_qx = nas_qx;
- packet->nas_qy = nas_qy;
- packet->nas_qz = nas_qz;
- packet->nas_qw = nas_qw;
- packet->nas_bias_x = nas_bias_x;
- packet->nas_bias_y = nas_bias_y;
- packet->nas_bias_z = nas_bias_z;
- packet->pin_quick_connector = pin_quick_connector;
- packet->battery_voltage = battery_voltage;
- packet->cam_battery_voltage = cam_battery_voltage;
- packet->current_consumption = current_consumption;
- packet->temperature = temperature;
- packet->ada_state = ada_state;
- packet->fmm_state = fmm_state;
- packet->dpl_state = dpl_state;
- packet->abk_state = abk_state;
- packet->nas_state = nas_state;
- packet->mea_state = mea_state;
- packet->gps_fix = gps_fix;
- packet->pin_launch = pin_launch;
- packet->pin_nosecone = pin_nosecone;
- packet->pin_expulsion = pin_expulsion;
- packet->cutter_presence = cutter_presence;
- packet->logger_error = logger_error;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, (const char *)packet, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ROCKET_FLIGHT_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from rocket_flight_tm message
- *
- * @return [us] Timestamp in microseconds
- */
-static inline uint64_t mavlink_msg_rocket_flight_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field ada_state from rocket_flight_tm message
- *
- * @return ADA Controller State
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_ada_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 164);
-}
-
-/**
- * @brief Get field fmm_state from rocket_flight_tm message
- *
- * @return Flight Mode Manager State
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_fmm_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 165);
-}
-
-/**
- * @brief Get field dpl_state from rocket_flight_tm message
- *
- * @return Deployment Controller State
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_dpl_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 166);
-}
-
-/**
- * @brief Get field abk_state from rocket_flight_tm message
- *
- * @return Airbrake FSM state
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_abk_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 167);
-}
-
-/**
- * @brief Get field nas_state from rocket_flight_tm message
- *
- * @return Navigation System FSM State
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_nas_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 168);
-}
-
-/**
- * @brief Get field mea_state from rocket_flight_tm message
- *
- * @return MEA Controller State
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_mea_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 169);
-}
-
-/**
- * @brief Get field pressure_ada from rocket_flight_tm message
- *
- * @return [Pa] Atmospheric pressure estimated by ADA
- */
-static inline float mavlink_msg_rocket_flight_tm_get_pressure_ada(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field pressure_digi from rocket_flight_tm message
- *
- * @return [Pa] Pressure from digital sensor
- */
-static inline float mavlink_msg_rocket_flight_tm_get_pressure_digi(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field pressure_static from rocket_flight_tm message
- *
- * @return [Pa] Pressure from static port
- */
-static inline float mavlink_msg_rocket_flight_tm_get_pressure_static(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field pressure_dpl from rocket_flight_tm message
- *
- * @return [Pa] Pressure from deployment vane sensor
- */
-static inline float mavlink_msg_rocket_flight_tm_get_pressure_dpl(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field airspeed_pitot from rocket_flight_tm message
- *
- * @return [m/s] Pitot airspeed
- */
-static inline float mavlink_msg_rocket_flight_tm_get_airspeed_pitot(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field altitude_agl from rocket_flight_tm message
- *
- * @return [m] Altitude above ground level
- */
-static inline float mavlink_msg_rocket_flight_tm_get_altitude_agl(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field ada_vert_speed from rocket_flight_tm message
- *
- * @return [m/s] Vertical speed estimated by ADA
- */
-static inline float mavlink_msg_rocket_flight_tm_get_ada_vert_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field mea_mass from rocket_flight_tm message
- *
- * @return [kg] Mass estimated by MEA
- */
-static inline float mavlink_msg_rocket_flight_tm_get_mea_mass(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field acc_x from rocket_flight_tm message
- *
- * @return [m/s^2] Acceleration on X axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_acc_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field acc_y from rocket_flight_tm message
- *
- * @return [m/s^2] Acceleration on Y axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_acc_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field acc_z from rocket_flight_tm message
- *
- * @return [m/s^2] Acceleration on Z axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_acc_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field gyro_x from rocket_flight_tm message
- *
- * @return [rad/s] Angular speed on X axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_gyro_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field gyro_y from rocket_flight_tm message
- *
- * @return [rad/s] Angular speed on Y axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_gyro_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field gyro_z from rocket_flight_tm message
- *
- * @return [rad/s] Angular speed on Z axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_gyro_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field mag_x from rocket_flight_tm message
- *
- * @return [uT] Magnetic field on X axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_mag_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field mag_y from rocket_flight_tm message
- *
- * @return [uT] Magnetic field on Y axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_mag_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field mag_z from rocket_flight_tm message
- *
- * @return [uT] Magnetic field on Z axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_mag_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 72);
-}
-
-/**
- * @brief Get field gps_fix from rocket_flight_tm message
- *
- * @return GPS fix (1 = fix, 0 = no fix)
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_gps_fix(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 170);
-}
-
-/**
- * @brief Get field gps_lat from rocket_flight_tm message
- *
- * @return [deg] Latitude
- */
-static inline float mavlink_msg_rocket_flight_tm_get_gps_lat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 76);
-}
-
-/**
- * @brief Get field gps_lon from rocket_flight_tm message
- *
- * @return [deg] Longitude
- */
-static inline float mavlink_msg_rocket_flight_tm_get_gps_lon(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 80);
-}
-
-/**
- * @brief Get field gps_alt from rocket_flight_tm message
- *
- * @return [m] GPS Altitude
- */
-static inline float mavlink_msg_rocket_flight_tm_get_gps_alt(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 84);
-}
-
-/**
- * @brief Get field abk_angle from rocket_flight_tm message
- *
- * @return [deg] Air Brakes angle
- */
-static inline float mavlink_msg_rocket_flight_tm_get_abk_angle(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 88);
-}
-
-/**
- * @brief Get field nas_n from rocket_flight_tm message
- *
- * @return [deg] Navigation system estimated noth position
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_n(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 92);
-}
-
-/**
- * @brief Get field nas_e from rocket_flight_tm message
- *
- * @return [deg] Navigation system estimated east position
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_e(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 96);
-}
-
-/**
- * @brief Get field nas_d from rocket_flight_tm message
- *
- * @return [m] Navigation system estimated down position
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_d(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 100);
-}
-
-/**
- * @brief Get field nas_vn from rocket_flight_tm message
- *
- * @return [m/s] Navigation system estimated north velocity
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_vn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 104);
-}
-
-/**
- * @brief Get field nas_ve from rocket_flight_tm message
- *
- * @return [m/s] Navigation system estimated east velocity
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_ve(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 108);
-}
-
-/**
- * @brief Get field nas_vd from rocket_flight_tm message
- *
- * @return [m/s] Navigation system estimated down velocity
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_vd(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 112);
-}
-
-/**
- * @brief Get field nas_qx from rocket_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qx)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_qx(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 116);
-}
-
-/**
- * @brief Get field nas_qy from rocket_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qy)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_qy(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 120);
-}
-
-/**
- * @brief Get field nas_qz from rocket_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qz)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_qz(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 124);
-}
-
-/**
- * @brief Get field nas_qw from rocket_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qw)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_qw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 128);
-}
-
-/**
- * @brief Get field nas_bias_x from rocket_flight_tm message
- *
- * @return Navigation system gyroscope bias on x axis
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 132);
-}
-
-/**
- * @brief Get field nas_bias_y from rocket_flight_tm message
- *
- * @return Navigation system gyroscope bias on y axis
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 136);
-}
-
-/**
- * @brief Get field nas_bias_z from rocket_flight_tm message
- *
- * @return Navigation system gyroscope bias on z axis
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 140);
-}
-
-/**
- * @brief Get field pin_quick_connector from rocket_flight_tm message
- *
- * @return Quick connector detach pin
- */
-static inline float mavlink_msg_rocket_flight_tm_get_pin_quick_connector(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 144);
-}
-
-/**
- * @brief Get field pin_launch from rocket_flight_tm message
- *
- * @return Launch pin status (1 = connected, 0 = disconnected)
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_launch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 171);
-}
-
-/**
- * @brief Get field pin_nosecone from rocket_flight_tm message
- *
- * @return Nosecone pin status (1 = connected, 0 = disconnected)
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_nosecone(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 172);
-}
-
-/**
- * @brief Get field pin_expulsion from rocket_flight_tm message
- *
- * @return Servo sensor status (1 = actuated, 0 = idle)
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_expulsion(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 173);
-}
-
-/**
- * @brief Get field cutter_presence from rocket_flight_tm message
- *
- * @return Cutter presence status (1 = present, 0 = missing)
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_cutter_presence(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 174);
-}
-
-/**
- * @brief Get field battery_voltage from rocket_flight_tm message
- *
- * @return [V] Battery voltage
- */
-static inline float mavlink_msg_rocket_flight_tm_get_battery_voltage(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 148);
-}
-
-/**
- * @brief Get field cam_battery_voltage from rocket_flight_tm message
- *
- * @return [V] Camera battery voltage
- */
-static inline float mavlink_msg_rocket_flight_tm_get_cam_battery_voltage(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 152);
-}
-
-/**
- * @brief Get field current_consumption from rocket_flight_tm message
- *
- * @return [A] Battery current
- */
-static inline float mavlink_msg_rocket_flight_tm_get_current_consumption(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 156);
-}
-
-/**
- * @brief Get field temperature from rocket_flight_tm message
- *
- * @return [degC] Temperature
- */
-static inline float mavlink_msg_rocket_flight_tm_get_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 160);
-}
-
-/**
- * @brief Get field logger_error from rocket_flight_tm message
- *
- * @return Logger error (0 = no error, -1 otherwise)
- */
-static inline int8_t mavlink_msg_rocket_flight_tm_get_logger_error(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int8_t(msg, 175);
-}
-
-/**
- * @brief Decode a rocket_flight_tm message into a struct
- *
- * @param msg The message to decode
- * @param rocket_flight_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_rocket_flight_tm_decode(const mavlink_message_t* msg, mavlink_rocket_flight_tm_t* rocket_flight_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- rocket_flight_tm->timestamp = mavlink_msg_rocket_flight_tm_get_timestamp(msg);
- rocket_flight_tm->pressure_ada = mavlink_msg_rocket_flight_tm_get_pressure_ada(msg);
- rocket_flight_tm->pressure_digi = mavlink_msg_rocket_flight_tm_get_pressure_digi(msg);
- rocket_flight_tm->pressure_static = mavlink_msg_rocket_flight_tm_get_pressure_static(msg);
- rocket_flight_tm->pressure_dpl = mavlink_msg_rocket_flight_tm_get_pressure_dpl(msg);
- rocket_flight_tm->airspeed_pitot = mavlink_msg_rocket_flight_tm_get_airspeed_pitot(msg);
- rocket_flight_tm->altitude_agl = mavlink_msg_rocket_flight_tm_get_altitude_agl(msg);
- rocket_flight_tm->ada_vert_speed = mavlink_msg_rocket_flight_tm_get_ada_vert_speed(msg);
- rocket_flight_tm->mea_mass = mavlink_msg_rocket_flight_tm_get_mea_mass(msg);
- rocket_flight_tm->acc_x = mavlink_msg_rocket_flight_tm_get_acc_x(msg);
- rocket_flight_tm->acc_y = mavlink_msg_rocket_flight_tm_get_acc_y(msg);
- rocket_flight_tm->acc_z = mavlink_msg_rocket_flight_tm_get_acc_z(msg);
- rocket_flight_tm->gyro_x = mavlink_msg_rocket_flight_tm_get_gyro_x(msg);
- rocket_flight_tm->gyro_y = mavlink_msg_rocket_flight_tm_get_gyro_y(msg);
- rocket_flight_tm->gyro_z = mavlink_msg_rocket_flight_tm_get_gyro_z(msg);
- rocket_flight_tm->mag_x = mavlink_msg_rocket_flight_tm_get_mag_x(msg);
- rocket_flight_tm->mag_y = mavlink_msg_rocket_flight_tm_get_mag_y(msg);
- rocket_flight_tm->mag_z = mavlink_msg_rocket_flight_tm_get_mag_z(msg);
- rocket_flight_tm->gps_lat = mavlink_msg_rocket_flight_tm_get_gps_lat(msg);
- rocket_flight_tm->gps_lon = mavlink_msg_rocket_flight_tm_get_gps_lon(msg);
- rocket_flight_tm->gps_alt = mavlink_msg_rocket_flight_tm_get_gps_alt(msg);
- rocket_flight_tm->abk_angle = mavlink_msg_rocket_flight_tm_get_abk_angle(msg);
- rocket_flight_tm->nas_n = mavlink_msg_rocket_flight_tm_get_nas_n(msg);
- rocket_flight_tm->nas_e = mavlink_msg_rocket_flight_tm_get_nas_e(msg);
- rocket_flight_tm->nas_d = mavlink_msg_rocket_flight_tm_get_nas_d(msg);
- rocket_flight_tm->nas_vn = mavlink_msg_rocket_flight_tm_get_nas_vn(msg);
- rocket_flight_tm->nas_ve = mavlink_msg_rocket_flight_tm_get_nas_ve(msg);
- rocket_flight_tm->nas_vd = mavlink_msg_rocket_flight_tm_get_nas_vd(msg);
- rocket_flight_tm->nas_qx = mavlink_msg_rocket_flight_tm_get_nas_qx(msg);
- rocket_flight_tm->nas_qy = mavlink_msg_rocket_flight_tm_get_nas_qy(msg);
- rocket_flight_tm->nas_qz = mavlink_msg_rocket_flight_tm_get_nas_qz(msg);
- rocket_flight_tm->nas_qw = mavlink_msg_rocket_flight_tm_get_nas_qw(msg);
- rocket_flight_tm->nas_bias_x = mavlink_msg_rocket_flight_tm_get_nas_bias_x(msg);
- rocket_flight_tm->nas_bias_y = mavlink_msg_rocket_flight_tm_get_nas_bias_y(msg);
- rocket_flight_tm->nas_bias_z = mavlink_msg_rocket_flight_tm_get_nas_bias_z(msg);
- rocket_flight_tm->pin_quick_connector = mavlink_msg_rocket_flight_tm_get_pin_quick_connector(msg);
- rocket_flight_tm->battery_voltage = mavlink_msg_rocket_flight_tm_get_battery_voltage(msg);
- rocket_flight_tm->cam_battery_voltage = mavlink_msg_rocket_flight_tm_get_cam_battery_voltage(msg);
- rocket_flight_tm->current_consumption = mavlink_msg_rocket_flight_tm_get_current_consumption(msg);
- rocket_flight_tm->temperature = mavlink_msg_rocket_flight_tm_get_temperature(msg);
- rocket_flight_tm->ada_state = mavlink_msg_rocket_flight_tm_get_ada_state(msg);
- rocket_flight_tm->fmm_state = mavlink_msg_rocket_flight_tm_get_fmm_state(msg);
- rocket_flight_tm->dpl_state = mavlink_msg_rocket_flight_tm_get_dpl_state(msg);
- rocket_flight_tm->abk_state = mavlink_msg_rocket_flight_tm_get_abk_state(msg);
- rocket_flight_tm->nas_state = mavlink_msg_rocket_flight_tm_get_nas_state(msg);
- rocket_flight_tm->mea_state = mavlink_msg_rocket_flight_tm_get_mea_state(msg);
- rocket_flight_tm->gps_fix = mavlink_msg_rocket_flight_tm_get_gps_fix(msg);
- rocket_flight_tm->pin_launch = mavlink_msg_rocket_flight_tm_get_pin_launch(msg);
- rocket_flight_tm->pin_nosecone = mavlink_msg_rocket_flight_tm_get_pin_nosecone(msg);
- rocket_flight_tm->pin_expulsion = mavlink_msg_rocket_flight_tm_get_pin_expulsion(msg);
- rocket_flight_tm->cutter_presence = mavlink_msg_rocket_flight_tm_get_cutter_presence(msg);
- rocket_flight_tm->logger_error = mavlink_msg_rocket_flight_tm_get_logger_error(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN? msg->len : MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN;
- memset(rocket_flight_tm, 0, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
- memcpy(rocket_flight_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_rocket_stats_tm.h b/mavlink_lib/lyra/mavlink_msg_rocket_stats_tm.h
deleted file mode 100644
index c878c468511c88c92b03ee5caa9a8f0ce437a766..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_rocket_stats_tm.h
+++ /dev/null
@@ -1,638 +0,0 @@
-#pragma once
-// MESSAGE ROCKET_STATS_TM PACKING
-
-#define MAVLINK_MSG_ID_ROCKET_STATS_TM 210
-
-
-typedef struct __mavlink_rocket_stats_tm_t {
- uint64_t liftoff_ts; /*< [us] System clock at liftoff*/
- uint64_t liftoff_max_acc_ts; /*< [us] System clock at the maximum liftoff acceleration*/
- uint64_t dpl_ts; /*< [us] System clock at drouge deployment*/
- uint64_t max_z_speed_ts; /*< [us] System clock at ADA max vertical speed*/
- uint64_t apogee_ts; /*< [us] System clock at apogee*/
- float liftoff_max_acc; /*< [m/s2] Maximum liftoff acceleration*/
- float dpl_max_acc; /*< [m/s2] Max acceleration during drouge deployment*/
- float max_z_speed; /*< [m/s] Max measured vertical speed - ADA*/
- float max_airspeed_pitot; /*< [m/s] Max speed read by the pitot tube*/
- float max_speed_altitude; /*< [m] Altitude at max speed*/
- float apogee_lat; /*< [deg] Apogee latitude*/
- float apogee_lon; /*< [deg] Apogee longitude*/
- float apogee_alt; /*< [m] Apogee altitude*/
- float min_pressure; /*< [Pa] Apogee pressure - Digital barometer*/
- float ada_min_pressure; /*< [Pa] Apogee pressure - ADA filtered*/
- float dpl_vane_max_pressure; /*< [Pa] Max pressure in the deployment bay during drogue deployment*/
- float cpu_load; /*< CPU load in percentage*/
- uint32_t free_heap; /*< Amount of available heap in memory*/
-} mavlink_rocket_stats_tm_t;
-
-#define MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN 92
-#define MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN 92
-#define MAVLINK_MSG_ID_210_LEN 92
-#define MAVLINK_MSG_ID_210_MIN_LEN 92
-
-#define MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC 245
-#define MAVLINK_MSG_ID_210_CRC 245
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM { \
- 210, \
- "ROCKET_STATS_TM", \
- 18, \
- { { "liftoff_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_stats_tm_t, liftoff_ts) }, \
- { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_rocket_stats_tm_t, liftoff_max_acc_ts) }, \
- { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_rocket_stats_tm_t, liftoff_max_acc) }, \
- { "dpl_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_rocket_stats_tm_t, dpl_ts) }, \
- { "dpl_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_rocket_stats_tm_t, dpl_max_acc) }, \
- { "max_z_speed_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 24, offsetof(mavlink_rocket_stats_tm_t, max_z_speed_ts) }, \
- { "max_z_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_rocket_stats_tm_t, max_z_speed) }, \
- { "max_airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_rocket_stats_tm_t, max_airspeed_pitot) }, \
- { "max_speed_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_rocket_stats_tm_t, max_speed_altitude) }, \
- { "apogee_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 32, offsetof(mavlink_rocket_stats_tm_t, apogee_ts) }, \
- { "apogee_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_rocket_stats_tm_t, apogee_lat) }, \
- { "apogee_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_stats_tm_t, apogee_lon) }, \
- { "apogee_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_stats_tm_t, apogee_alt) }, \
- { "min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_stats_tm_t, min_pressure) }, \
- { "ada_min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_stats_tm_t, ada_min_pressure) }, \
- { "dpl_vane_max_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_stats_tm_t, dpl_vane_max_pressure) }, \
- { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_stats_tm_t, cpu_load) }, \
- { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 88, offsetof(mavlink_rocket_stats_tm_t, free_heap) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM { \
- "ROCKET_STATS_TM", \
- 18, \
- { { "liftoff_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_stats_tm_t, liftoff_ts) }, \
- { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_rocket_stats_tm_t, liftoff_max_acc_ts) }, \
- { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_rocket_stats_tm_t, liftoff_max_acc) }, \
- { "dpl_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_rocket_stats_tm_t, dpl_ts) }, \
- { "dpl_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_rocket_stats_tm_t, dpl_max_acc) }, \
- { "max_z_speed_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 24, offsetof(mavlink_rocket_stats_tm_t, max_z_speed_ts) }, \
- { "max_z_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_rocket_stats_tm_t, max_z_speed) }, \
- { "max_airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_rocket_stats_tm_t, max_airspeed_pitot) }, \
- { "max_speed_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_rocket_stats_tm_t, max_speed_altitude) }, \
- { "apogee_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 32, offsetof(mavlink_rocket_stats_tm_t, apogee_ts) }, \
- { "apogee_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_rocket_stats_tm_t, apogee_lat) }, \
- { "apogee_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_stats_tm_t, apogee_lon) }, \
- { "apogee_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_stats_tm_t, apogee_alt) }, \
- { "min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_stats_tm_t, min_pressure) }, \
- { "ada_min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_stats_tm_t, ada_min_pressure) }, \
- { "dpl_vane_max_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_stats_tm_t, dpl_vane_max_pressure) }, \
- { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_stats_tm_t, cpu_load) }, \
- { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 88, offsetof(mavlink_rocket_stats_tm_t, free_heap) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a rocket_stats_tm 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 liftoff_ts [us] System clock at liftoff
- * @param liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param dpl_ts [us] System clock at drouge deployment
- * @param dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param max_z_speed_ts [us] System clock at ADA max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed - ADA
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [us] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param apogee_alt [m] Apogee altitude
- * @param min_pressure [Pa] Apogee pressure - Digital barometer
- * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered
- * @param dpl_vane_max_pressure [Pa] Max pressure in the deployment bay during drogue deployment
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_rocket_stats_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float ada_min_pressure, float dpl_vane_max_pressure, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_ts);
- _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 16, dpl_ts);
- _mav_put_uint64_t(buf, 24, max_z_speed_ts);
- _mav_put_uint64_t(buf, 32, apogee_ts);
- _mav_put_float(buf, 40, liftoff_max_acc);
- _mav_put_float(buf, 44, dpl_max_acc);
- _mav_put_float(buf, 48, max_z_speed);
- _mav_put_float(buf, 52, max_airspeed_pitot);
- _mav_put_float(buf, 56, max_speed_altitude);
- _mav_put_float(buf, 60, apogee_lat);
- _mav_put_float(buf, 64, apogee_lon);
- _mav_put_float(buf, 68, apogee_alt);
- _mav_put_float(buf, 72, min_pressure);
- _mav_put_float(buf, 76, ada_min_pressure);
- _mav_put_float(buf, 80, dpl_vane_max_pressure);
- _mav_put_float(buf, 84, cpu_load);
- _mav_put_uint32_t(buf, 88, free_heap);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
-#else
- mavlink_rocket_stats_tm_t packet;
- packet.liftoff_ts = liftoff_ts;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.dpl_ts = dpl_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.dpl_max_acc = dpl_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.apogee_alt = apogee_alt;
- packet.min_pressure = min_pressure;
- packet.ada_min_pressure = ada_min_pressure;
- packet.dpl_vane_max_pressure = dpl_vane_max_pressure;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ROCKET_STATS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-}
-
-/**
- * @brief Pack a rocket_stats_tm 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 liftoff_ts [us] System clock at liftoff
- * @param liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param dpl_ts [us] System clock at drouge deployment
- * @param dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param max_z_speed_ts [us] System clock at ADA max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed - ADA
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [us] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param apogee_alt [m] Apogee altitude
- * @param min_pressure [Pa] Apogee pressure - Digital barometer
- * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered
- * @param dpl_vane_max_pressure [Pa] Max pressure in the deployment bay during drogue deployment
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_rocket_stats_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t liftoff_ts,uint64_t liftoff_max_acc_ts,float liftoff_max_acc,uint64_t dpl_ts,float dpl_max_acc,uint64_t max_z_speed_ts,float max_z_speed,float max_airspeed_pitot,float max_speed_altitude,uint64_t apogee_ts,float apogee_lat,float apogee_lon,float apogee_alt,float min_pressure,float ada_min_pressure,float dpl_vane_max_pressure,float cpu_load,uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_ts);
- _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 16, dpl_ts);
- _mav_put_uint64_t(buf, 24, max_z_speed_ts);
- _mav_put_uint64_t(buf, 32, apogee_ts);
- _mav_put_float(buf, 40, liftoff_max_acc);
- _mav_put_float(buf, 44, dpl_max_acc);
- _mav_put_float(buf, 48, max_z_speed);
- _mav_put_float(buf, 52, max_airspeed_pitot);
- _mav_put_float(buf, 56, max_speed_altitude);
- _mav_put_float(buf, 60, apogee_lat);
- _mav_put_float(buf, 64, apogee_lon);
- _mav_put_float(buf, 68, apogee_alt);
- _mav_put_float(buf, 72, min_pressure);
- _mav_put_float(buf, 76, ada_min_pressure);
- _mav_put_float(buf, 80, dpl_vane_max_pressure);
- _mav_put_float(buf, 84, cpu_load);
- _mav_put_uint32_t(buf, 88, free_heap);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
-#else
- mavlink_rocket_stats_tm_t packet;
- packet.liftoff_ts = liftoff_ts;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.dpl_ts = dpl_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.dpl_max_acc = dpl_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.apogee_alt = apogee_alt;
- packet.min_pressure = min_pressure;
- packet.ada_min_pressure = ada_min_pressure;
- packet.dpl_vane_max_pressure = dpl_vane_max_pressure;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ROCKET_STATS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-}
-
-/**
- * @brief Encode a rocket_stats_tm 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 rocket_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_rocket_stats_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rocket_stats_tm_t* rocket_stats_tm)
-{
- return mavlink_msg_rocket_stats_tm_pack(system_id, component_id, msg, rocket_stats_tm->liftoff_ts, rocket_stats_tm->liftoff_max_acc_ts, rocket_stats_tm->liftoff_max_acc, rocket_stats_tm->dpl_ts, rocket_stats_tm->dpl_max_acc, rocket_stats_tm->max_z_speed_ts, rocket_stats_tm->max_z_speed, rocket_stats_tm->max_airspeed_pitot, rocket_stats_tm->max_speed_altitude, rocket_stats_tm->apogee_ts, rocket_stats_tm->apogee_lat, rocket_stats_tm->apogee_lon, rocket_stats_tm->apogee_alt, rocket_stats_tm->min_pressure, rocket_stats_tm->ada_min_pressure, rocket_stats_tm->dpl_vane_max_pressure, rocket_stats_tm->cpu_load, rocket_stats_tm->free_heap);
-}
-
-/**
- * @brief Encode a rocket_stats_tm 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 rocket_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_rocket_stats_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rocket_stats_tm_t* rocket_stats_tm)
-{
- return mavlink_msg_rocket_stats_tm_pack_chan(system_id, component_id, chan, msg, rocket_stats_tm->liftoff_ts, rocket_stats_tm->liftoff_max_acc_ts, rocket_stats_tm->liftoff_max_acc, rocket_stats_tm->dpl_ts, rocket_stats_tm->dpl_max_acc, rocket_stats_tm->max_z_speed_ts, rocket_stats_tm->max_z_speed, rocket_stats_tm->max_airspeed_pitot, rocket_stats_tm->max_speed_altitude, rocket_stats_tm->apogee_ts, rocket_stats_tm->apogee_lat, rocket_stats_tm->apogee_lon, rocket_stats_tm->apogee_alt, rocket_stats_tm->min_pressure, rocket_stats_tm->ada_min_pressure, rocket_stats_tm->dpl_vane_max_pressure, rocket_stats_tm->cpu_load, rocket_stats_tm->free_heap);
-}
-
-/**
- * @brief Send a rocket_stats_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param liftoff_ts [us] System clock at liftoff
- * @param liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param dpl_ts [us] System clock at drouge deployment
- * @param dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param max_z_speed_ts [us] System clock at ADA max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed - ADA
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [us] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param apogee_alt [m] Apogee altitude
- * @param min_pressure [Pa] Apogee pressure - Digital barometer
- * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered
- * @param dpl_vane_max_pressure [Pa] Max pressure in the deployment bay during drogue deployment
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_rocket_stats_tm_send(mavlink_channel_t chan, uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float ada_min_pressure, float dpl_vane_max_pressure, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_ts);
- _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 16, dpl_ts);
- _mav_put_uint64_t(buf, 24, max_z_speed_ts);
- _mav_put_uint64_t(buf, 32, apogee_ts);
- _mav_put_float(buf, 40, liftoff_max_acc);
- _mav_put_float(buf, 44, dpl_max_acc);
- _mav_put_float(buf, 48, max_z_speed);
- _mav_put_float(buf, 52, max_airspeed_pitot);
- _mav_put_float(buf, 56, max_speed_altitude);
- _mav_put_float(buf, 60, apogee_lat);
- _mav_put_float(buf, 64, apogee_lon);
- _mav_put_float(buf, 68, apogee_alt);
- _mav_put_float(buf, 72, min_pressure);
- _mav_put_float(buf, 76, ada_min_pressure);
- _mav_put_float(buf, 80, dpl_vane_max_pressure);
- _mav_put_float(buf, 84, cpu_load);
- _mav_put_uint32_t(buf, 88, free_heap);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_STATS_TM, buf, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-#else
- mavlink_rocket_stats_tm_t packet;
- packet.liftoff_ts = liftoff_ts;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.dpl_ts = dpl_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.dpl_max_acc = dpl_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.apogee_alt = apogee_alt;
- packet.min_pressure = min_pressure;
- packet.ada_min_pressure = ada_min_pressure;
- packet.dpl_vane_max_pressure = dpl_vane_max_pressure;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_STATS_TM, (const char *)&packet, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a rocket_stats_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_rocket_stats_tm_send_struct(mavlink_channel_t chan, const mavlink_rocket_stats_tm_t* rocket_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_rocket_stats_tm_send(chan, rocket_stats_tm->liftoff_ts, rocket_stats_tm->liftoff_max_acc_ts, rocket_stats_tm->liftoff_max_acc, rocket_stats_tm->dpl_ts, rocket_stats_tm->dpl_max_acc, rocket_stats_tm->max_z_speed_ts, rocket_stats_tm->max_z_speed, rocket_stats_tm->max_airspeed_pitot, rocket_stats_tm->max_speed_altitude, rocket_stats_tm->apogee_ts, rocket_stats_tm->apogee_lat, rocket_stats_tm->apogee_lon, rocket_stats_tm->apogee_alt, rocket_stats_tm->min_pressure, rocket_stats_tm->ada_min_pressure, rocket_stats_tm->dpl_vane_max_pressure, rocket_stats_tm->cpu_load, rocket_stats_tm->free_heap);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_STATS_TM, (const char *)rocket_stats_tm, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ROCKET_STATS_TM_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_rocket_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float ada_min_pressure, float dpl_vane_max_pressure, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, liftoff_ts);
- _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 16, dpl_ts);
- _mav_put_uint64_t(buf, 24, max_z_speed_ts);
- _mav_put_uint64_t(buf, 32, apogee_ts);
- _mav_put_float(buf, 40, liftoff_max_acc);
- _mav_put_float(buf, 44, dpl_max_acc);
- _mav_put_float(buf, 48, max_z_speed);
- _mav_put_float(buf, 52, max_airspeed_pitot);
- _mav_put_float(buf, 56, max_speed_altitude);
- _mav_put_float(buf, 60, apogee_lat);
- _mav_put_float(buf, 64, apogee_lon);
- _mav_put_float(buf, 68, apogee_alt);
- _mav_put_float(buf, 72, min_pressure);
- _mav_put_float(buf, 76, ada_min_pressure);
- _mav_put_float(buf, 80, dpl_vane_max_pressure);
- _mav_put_float(buf, 84, cpu_load);
- _mav_put_uint32_t(buf, 88, free_heap);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_STATS_TM, buf, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-#else
- mavlink_rocket_stats_tm_t *packet = (mavlink_rocket_stats_tm_t *)msgbuf;
- packet->liftoff_ts = liftoff_ts;
- packet->liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet->dpl_ts = dpl_ts;
- packet->max_z_speed_ts = max_z_speed_ts;
- packet->apogee_ts = apogee_ts;
- packet->liftoff_max_acc = liftoff_max_acc;
- packet->dpl_max_acc = dpl_max_acc;
- packet->max_z_speed = max_z_speed;
- packet->max_airspeed_pitot = max_airspeed_pitot;
- packet->max_speed_altitude = max_speed_altitude;
- packet->apogee_lat = apogee_lat;
- packet->apogee_lon = apogee_lon;
- packet->apogee_alt = apogee_alt;
- packet->min_pressure = min_pressure;
- packet->ada_min_pressure = ada_min_pressure;
- packet->dpl_vane_max_pressure = dpl_vane_max_pressure;
- packet->cpu_load = cpu_load;
- packet->free_heap = free_heap;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_STATS_TM, (const char *)packet, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ROCKET_STATS_TM UNPACKING
-
-
-/**
- * @brief Get field liftoff_ts from rocket_stats_tm message
- *
- * @return [us] System clock at liftoff
- */
-static inline uint64_t mavlink_msg_rocket_stats_tm_get_liftoff_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field liftoff_max_acc_ts from rocket_stats_tm message
- *
- * @return [us] System clock at the maximum liftoff acceleration
- */
-static inline uint64_t mavlink_msg_rocket_stats_tm_get_liftoff_max_acc_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 8);
-}
-
-/**
- * @brief Get field liftoff_max_acc from rocket_stats_tm message
- *
- * @return [m/s2] Maximum liftoff acceleration
- */
-static inline float mavlink_msg_rocket_stats_tm_get_liftoff_max_acc(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field dpl_ts from rocket_stats_tm message
- *
- * @return [us] System clock at drouge deployment
- */
-static inline uint64_t mavlink_msg_rocket_stats_tm_get_dpl_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 16);
-}
-
-/**
- * @brief Get field dpl_max_acc from rocket_stats_tm message
- *
- * @return [m/s2] Max acceleration during drouge deployment
- */
-static inline float mavlink_msg_rocket_stats_tm_get_dpl_max_acc(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field max_z_speed_ts from rocket_stats_tm message
- *
- * @return [us] System clock at ADA max vertical speed
- */
-static inline uint64_t mavlink_msg_rocket_stats_tm_get_max_z_speed_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 24);
-}
-
-/**
- * @brief Get field max_z_speed from rocket_stats_tm message
- *
- * @return [m/s] Max measured vertical speed - ADA
- */
-static inline float mavlink_msg_rocket_stats_tm_get_max_z_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field max_airspeed_pitot from rocket_stats_tm message
- *
- * @return [m/s] Max speed read by the pitot tube
- */
-static inline float mavlink_msg_rocket_stats_tm_get_max_airspeed_pitot(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field max_speed_altitude from rocket_stats_tm message
- *
- * @return [m] Altitude at max speed
- */
-static inline float mavlink_msg_rocket_stats_tm_get_max_speed_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field apogee_ts from rocket_stats_tm message
- *
- * @return [us] System clock at apogee
- */
-static inline uint64_t mavlink_msg_rocket_stats_tm_get_apogee_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 32);
-}
-
-/**
- * @brief Get field apogee_lat from rocket_stats_tm message
- *
- * @return [deg] Apogee latitude
- */
-static inline float mavlink_msg_rocket_stats_tm_get_apogee_lat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field apogee_lon from rocket_stats_tm message
- *
- * @return [deg] Apogee longitude
- */
-static inline float mavlink_msg_rocket_stats_tm_get_apogee_lon(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field apogee_alt from rocket_stats_tm message
- *
- * @return [m] Apogee altitude
- */
-static inline float mavlink_msg_rocket_stats_tm_get_apogee_alt(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field min_pressure from rocket_stats_tm message
- *
- * @return [Pa] Apogee pressure - Digital barometer
- */
-static inline float mavlink_msg_rocket_stats_tm_get_min_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 72);
-}
-
-/**
- * @brief Get field ada_min_pressure from rocket_stats_tm message
- *
- * @return [Pa] Apogee pressure - ADA filtered
- */
-static inline float mavlink_msg_rocket_stats_tm_get_ada_min_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 76);
-}
-
-/**
- * @brief Get field dpl_vane_max_pressure from rocket_stats_tm message
- *
- * @return [Pa] Max pressure in the deployment bay during drogue deployment
- */
-static inline float mavlink_msg_rocket_stats_tm_get_dpl_vane_max_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 80);
-}
-
-/**
- * @brief Get field cpu_load from rocket_stats_tm message
- *
- * @return CPU load in percentage
- */
-static inline float mavlink_msg_rocket_stats_tm_get_cpu_load(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 84);
-}
-
-/**
- * @brief Get field free_heap from rocket_stats_tm message
- *
- * @return Amount of available heap in memory
- */
-static inline uint32_t mavlink_msg_rocket_stats_tm_get_free_heap(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 88);
-}
-
-/**
- * @brief Decode a rocket_stats_tm message into a struct
- *
- * @param msg The message to decode
- * @param rocket_stats_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_rocket_stats_tm_decode(const mavlink_message_t* msg, mavlink_rocket_stats_tm_t* rocket_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- rocket_stats_tm->liftoff_ts = mavlink_msg_rocket_stats_tm_get_liftoff_ts(msg);
- rocket_stats_tm->liftoff_max_acc_ts = mavlink_msg_rocket_stats_tm_get_liftoff_max_acc_ts(msg);
- rocket_stats_tm->dpl_ts = mavlink_msg_rocket_stats_tm_get_dpl_ts(msg);
- rocket_stats_tm->max_z_speed_ts = mavlink_msg_rocket_stats_tm_get_max_z_speed_ts(msg);
- rocket_stats_tm->apogee_ts = mavlink_msg_rocket_stats_tm_get_apogee_ts(msg);
- rocket_stats_tm->liftoff_max_acc = mavlink_msg_rocket_stats_tm_get_liftoff_max_acc(msg);
- rocket_stats_tm->dpl_max_acc = mavlink_msg_rocket_stats_tm_get_dpl_max_acc(msg);
- rocket_stats_tm->max_z_speed = mavlink_msg_rocket_stats_tm_get_max_z_speed(msg);
- rocket_stats_tm->max_airspeed_pitot = mavlink_msg_rocket_stats_tm_get_max_airspeed_pitot(msg);
- rocket_stats_tm->max_speed_altitude = mavlink_msg_rocket_stats_tm_get_max_speed_altitude(msg);
- rocket_stats_tm->apogee_lat = mavlink_msg_rocket_stats_tm_get_apogee_lat(msg);
- rocket_stats_tm->apogee_lon = mavlink_msg_rocket_stats_tm_get_apogee_lon(msg);
- rocket_stats_tm->apogee_alt = mavlink_msg_rocket_stats_tm_get_apogee_alt(msg);
- rocket_stats_tm->min_pressure = mavlink_msg_rocket_stats_tm_get_min_pressure(msg);
- rocket_stats_tm->ada_min_pressure = mavlink_msg_rocket_stats_tm_get_ada_min_pressure(msg);
- rocket_stats_tm->dpl_vane_max_pressure = mavlink_msg_rocket_stats_tm_get_dpl_vane_max_pressure(msg);
- rocket_stats_tm->cpu_load = mavlink_msg_rocket_stats_tm_get_cpu_load(msg);
- rocket_stats_tm->free_heap = mavlink_msg_rocket_stats_tm_get_free_heap(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN? msg->len : MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN;
- memset(rocket_stats_tm, 0, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
- memcpy(rocket_stats_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_sensor_state_tm.h b/mavlink_lib/lyra/mavlink_msg_sensor_state_tm.h
deleted file mode 100644
index deec614076883a9d0a979da1a7b2c515b2d87361..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_sensor_state_tm.h
+++ /dev/null
@@ -1,230 +0,0 @@
-#pragma once
-// MESSAGE SENSOR_STATE_TM PACKING
-
-#define MAVLINK_MSG_ID_SENSOR_STATE_TM 111
-
-
-typedef struct __mavlink_sensor_state_tm_t {
- char sensor_name[20]; /*< Sensor name*/
- uint8_t state; /*< Boolean that represents the init state*/
-} mavlink_sensor_state_tm_t;
-
-#define MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN 21
-#define MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN 21
-#define MAVLINK_MSG_ID_111_LEN 21
-#define MAVLINK_MSG_ID_111_MIN_LEN 21
-
-#define MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC 155
-#define MAVLINK_MSG_ID_111_CRC 155
-
-#define MAVLINK_MSG_SENSOR_STATE_TM_FIELD_SENSOR_NAME_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM { \
- 111, \
- "SENSOR_STATE_TM", \
- 2, \
- { { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 0, offsetof(mavlink_sensor_state_tm_t, sensor_name) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_sensor_state_tm_t, state) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM { \
- "SENSOR_STATE_TM", \
- 2, \
- { { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 0, offsetof(mavlink_sensor_state_tm_t, sensor_name) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_sensor_state_tm_t, state) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a sensor_state_tm 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 sensor_name Sensor name
- * @param state Boolean that represents the init state
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sensor_state_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- const char *sensor_name, uint8_t state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN];
- _mav_put_uint8_t(buf, 20, state);
- _mav_put_char_array(buf, 0, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
-#else
- mavlink_sensor_state_tm_t packet;
- packet.state = state;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SENSOR_STATE_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-}
-
-/**
- * @brief Pack a sensor_state_tm 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 sensor_name Sensor name
- * @param state Boolean that represents the init state
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sensor_state_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- const char *sensor_name,uint8_t state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN];
- _mav_put_uint8_t(buf, 20, state);
- _mav_put_char_array(buf, 0, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
-#else
- mavlink_sensor_state_tm_t packet;
- packet.state = state;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SENSOR_STATE_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-}
-
-/**
- * @brief Encode a sensor_state_tm 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 sensor_state_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sensor_state_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_state_tm_t* sensor_state_tm)
-{
- return mavlink_msg_sensor_state_tm_pack(system_id, component_id, msg, sensor_state_tm->sensor_name, sensor_state_tm->state);
-}
-
-/**
- * @brief Encode a sensor_state_tm 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 sensor_state_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sensor_state_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sensor_state_tm_t* sensor_state_tm)
-{
- return mavlink_msg_sensor_state_tm_pack_chan(system_id, component_id, chan, msg, sensor_state_tm->sensor_name, sensor_state_tm->state);
-}
-
-/**
- * @brief Send a sensor_state_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param sensor_name Sensor name
- * @param state Boolean that represents the init state
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_sensor_state_tm_send(mavlink_channel_t chan, const char *sensor_name, uint8_t state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN];
- _mav_put_uint8_t(buf, 20, state);
- _mav_put_char_array(buf, 0, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_STATE_TM, buf, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-#else
- mavlink_sensor_state_tm_t packet;
- packet.state = state;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_STATE_TM, (const char *)&packet, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a sensor_state_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_sensor_state_tm_send_struct(mavlink_channel_t chan, const mavlink_sensor_state_tm_t* sensor_state_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_sensor_state_tm_send(chan, sensor_state_tm->sensor_name, sensor_state_tm->state);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_STATE_TM, (const char *)sensor_state_tm, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SENSOR_STATE_TM_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_sensor_state_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *sensor_name, uint8_t state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 20, state);
- _mav_put_char_array(buf, 0, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_STATE_TM, buf, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-#else
- mavlink_sensor_state_tm_t *packet = (mavlink_sensor_state_tm_t *)msgbuf;
- packet->state = state;
- mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_STATE_TM, (const char *)packet, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SENSOR_STATE_TM UNPACKING
-
-
-/**
- * @brief Get field sensor_name from sensor_state_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_sensor_state_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
-{
- return _MAV_RETURN_char_array(msg, sensor_name, 20, 0);
-}
-
-/**
- * @brief Get field state from sensor_state_tm message
- *
- * @return Boolean that represents the init state
- */
-static inline uint8_t mavlink_msg_sensor_state_tm_get_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 20);
-}
-
-/**
- * @brief Decode a sensor_state_tm message into a struct
- *
- * @param msg The message to decode
- * @param sensor_state_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_sensor_state_tm_decode(const mavlink_message_t* msg, mavlink_sensor_state_tm_t* sensor_state_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_sensor_state_tm_get_sensor_name(msg, sensor_state_tm->sensor_name);
- sensor_state_tm->state = mavlink_msg_sensor_state_tm_get_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN? msg->len : MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN;
- memset(sensor_state_tm, 0, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
- memcpy(sensor_state_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_sensor_tm_request_tc.h b/mavlink_lib/lyra/mavlink_msg_sensor_tm_request_tc.h
deleted file mode 100644
index bdf4a43617f74e9ba284ef8613ba5f01e808b707..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_sensor_tm_request_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SENSOR_TM_REQUEST_TC PACKING
-
-#define MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC 4
-
-
-typedef struct __mavlink_sensor_tm_request_tc_t {
- uint8_t sensor_name; /*< A member of the SensorTMList enum*/
-} mavlink_sensor_tm_request_tc_t;
-
-#define MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN 1
-#define MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_4_LEN 1
-#define MAVLINK_MSG_ID_4_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC 248
-#define MAVLINK_MSG_ID_4_CRC 248
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC { \
- 4, \
- "SENSOR_TM_REQUEST_TC", \
- 1, \
- { { "sensor_name", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_sensor_tm_request_tc_t, sensor_name) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC { \
- "SENSOR_TM_REQUEST_TC", \
- 1, \
- { { "sensor_name", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_sensor_tm_request_tc_t, sensor_name) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a sensor_tm_request_tc 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 sensor_name A member of the SensorTMList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sensor_tm_request_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t sensor_name)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, sensor_name);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN);
-#else
- mavlink_sensor_tm_request_tc_t packet;
- packet.sensor_name = sensor_name;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Pack a sensor_tm_request_tc 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 sensor_name A member of the SensorTMList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sensor_tm_request_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t sensor_name)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, sensor_name);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN);
-#else
- mavlink_sensor_tm_request_tc_t packet;
- packet.sensor_name = sensor_name;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Encode a sensor_tm_request_tc 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 sensor_tm_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sensor_tm_request_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_tm_request_tc_t* sensor_tm_request_tc)
-{
- return mavlink_msg_sensor_tm_request_tc_pack(system_id, component_id, msg, sensor_tm_request_tc->sensor_name);
-}
-
-/**
- * @brief Encode a sensor_tm_request_tc 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 sensor_tm_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sensor_tm_request_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sensor_tm_request_tc_t* sensor_tm_request_tc)
-{
- return mavlink_msg_sensor_tm_request_tc_pack_chan(system_id, component_id, chan, msg, sensor_tm_request_tc->sensor_name);
-}
-
-/**
- * @brief Send a sensor_tm_request_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param sensor_name A member of the SensorTMList enum
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_sensor_tm_request_tc_send(mavlink_channel_t chan, uint8_t sensor_name)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, sensor_name);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC, buf, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-#else
- mavlink_sensor_tm_request_tc_t packet;
- packet.sensor_name = sensor_name;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC, (const char *)&packet, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a sensor_tm_request_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_sensor_tm_request_tc_send_struct(mavlink_channel_t chan, const mavlink_sensor_tm_request_tc_t* sensor_tm_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_sensor_tm_request_tc_send(chan, sensor_tm_request_tc->sensor_name);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC, (const char *)sensor_tm_request_tc, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_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_sensor_tm_request_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t sensor_name)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, sensor_name);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC, buf, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-#else
- mavlink_sensor_tm_request_tc_t *packet = (mavlink_sensor_tm_request_tc_t *)msgbuf;
- packet->sensor_name = sensor_name;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC, (const char *)packet, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SENSOR_TM_REQUEST_TC UNPACKING
-
-
-/**
- * @brief Get field sensor_name from sensor_tm_request_tc message
- *
- * @return A member of the SensorTMList enum
- */
-static inline uint8_t mavlink_msg_sensor_tm_request_tc_get_sensor_name(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a sensor_tm_request_tc message into a struct
- *
- * @param msg The message to decode
- * @param sensor_tm_request_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_sensor_tm_request_tc_decode(const mavlink_message_t* msg, mavlink_sensor_tm_request_tc_t* sensor_tm_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- sensor_tm_request_tc->sensor_name = mavlink_msg_sensor_tm_request_tc_get_sensor_name(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN? msg->len : MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN;
- memset(sensor_tm_request_tc, 0, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN);
- memcpy(sensor_tm_request_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_servo_tm.h b/mavlink_lib/lyra/mavlink_msg_servo_tm.h
deleted file mode 100644
index 0ffe705d7c4094e1d82b537e2c7977a64b12c86a..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_servo_tm.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SERVO_TM PACKING
-
-#define MAVLINK_MSG_ID_SERVO_TM 112
-
-
-typedef struct __mavlink_servo_tm_t {
- float servo_position; /*< Position of the servo [0-1]*/
- uint8_t servo_id; /*< A member of the ServosList enum*/
-} mavlink_servo_tm_t;
-
-#define MAVLINK_MSG_ID_SERVO_TM_LEN 5
-#define MAVLINK_MSG_ID_SERVO_TM_MIN_LEN 5
-#define MAVLINK_MSG_ID_112_LEN 5
-#define MAVLINK_MSG_ID_112_MIN_LEN 5
-
-#define MAVLINK_MSG_ID_SERVO_TM_CRC 87
-#define MAVLINK_MSG_ID_112_CRC 87
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SERVO_TM { \
- 112, \
- "SERVO_TM", \
- 2, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_servo_tm_t, servo_id) }, \
- { "servo_position", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_servo_tm_t, servo_position) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SERVO_TM { \
- "SERVO_TM", \
- 2, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_servo_tm_t, servo_id) }, \
- { "servo_position", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_servo_tm_t, servo_position) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a servo_tm 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 servo_id A member of the ServosList enum
- * @param servo_position Position of the servo [0-1]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_servo_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t servo_id, float servo_position)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SERVO_TM_LEN];
- _mav_put_float(buf, 0, servo_position);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_TM_LEN);
-#else
- mavlink_servo_tm_t packet;
- packet.servo_position = servo_position;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SERVO_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-}
-
-/**
- * @brief Pack a servo_tm 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 servo_id A member of the ServosList enum
- * @param servo_position Position of the servo [0-1]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_servo_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t servo_id,float servo_position)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SERVO_TM_LEN];
- _mav_put_float(buf, 0, servo_position);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_TM_LEN);
-#else
- mavlink_servo_tm_t packet;
- packet.servo_position = servo_position;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SERVO_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-}
-
-/**
- * @brief Encode a servo_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_servo_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_servo_tm_t* servo_tm)
-{
- return mavlink_msg_servo_tm_pack(system_id, component_id, msg, servo_tm->servo_id, servo_tm->servo_position);
-}
-
-/**
- * @brief Encode a servo_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_servo_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_servo_tm_t* servo_tm)
-{
- return mavlink_msg_servo_tm_pack_chan(system_id, component_id, chan, msg, servo_tm->servo_id, servo_tm->servo_position);
-}
-
-/**
- * @brief Send a servo_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param servo_id A member of the ServosList enum
- * @param servo_position Position of the servo [0-1]
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_servo_tm_send(mavlink_channel_t chan, uint8_t servo_id, float servo_position)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SERVO_TM_LEN];
- _mav_put_float(buf, 0, servo_position);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM, buf, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-#else
- mavlink_servo_tm_t packet;
- packet.servo_position = servo_position;
- packet.servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM, (const char *)&packet, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a servo_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_servo_tm_send_struct(mavlink_channel_t chan, const mavlink_servo_tm_t* servo_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_servo_tm_send(chan, servo_tm->servo_id, servo_tm->servo_position);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM, (const char *)servo_tm, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SERVO_TM_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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t servo_id, float servo_position)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, servo_position);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM, buf, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-#else
- mavlink_servo_tm_t *packet = (mavlink_servo_tm_t *)msgbuf;
- packet->servo_position = servo_position;
- packet->servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM, (const char *)packet, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SERVO_TM UNPACKING
-
-
-/**
- * @brief Get field servo_id from servo_tm message
- *
- * @return A member of the ServosList enum
- */
-static inline uint8_t mavlink_msg_servo_tm_get_servo_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 4);
-}
-
-/**
- * @brief Get field servo_position from servo_tm message
- *
- * @return Position of the servo [0-1]
- */
-static inline float mavlink_msg_servo_tm_get_servo_position(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a servo_tm message into a struct
- *
- * @param msg The message to decode
- * @param servo_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_servo_tm_decode(const mavlink_message_t* msg, mavlink_servo_tm_t* servo_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- servo_tm->servo_position = mavlink_msg_servo_tm_get_servo_position(msg);
- servo_tm->servo_id = mavlink_msg_servo_tm_get_servo_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SERVO_TM_LEN? msg->len : MAVLINK_MSG_ID_SERVO_TM_LEN;
- memset(servo_tm, 0, MAVLINK_MSG_ID_SERVO_TM_LEN);
- memcpy(servo_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_servo_tm_request_tc.h b/mavlink_lib/lyra/mavlink_msg_servo_tm_request_tc.h
deleted file mode 100644
index 6ac27824c3a9ac7df9d8bf0a0983c552f689cb71..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_servo_tm_request_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SERVO_TM_REQUEST_TC PACKING
-
-#define MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC 5
-
-
-typedef struct __mavlink_servo_tm_request_tc_t {
- uint8_t servo_id; /*< A member of the ServosList enum*/
-} mavlink_servo_tm_request_tc_t;
-
-#define MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN 1
-#define MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_5_LEN 1
-#define MAVLINK_MSG_ID_5_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC 184
-#define MAVLINK_MSG_ID_5_CRC 184
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC { \
- 5, \
- "SERVO_TM_REQUEST_TC", \
- 1, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_servo_tm_request_tc_t, servo_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC { \
- "SERVO_TM_REQUEST_TC", \
- 1, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_servo_tm_request_tc_t, servo_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a servo_tm_request_tc 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 servo_id A member of the ServosList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_servo_tm_request_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN);
-#else
- mavlink_servo_tm_request_tc_t packet;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Pack a servo_tm_request_tc 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 servo_id A member of the ServosList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_servo_tm_request_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN);
-#else
- mavlink_servo_tm_request_tc_t packet;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Encode a servo_tm_request_tc 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_tm_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_servo_tm_request_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_servo_tm_request_tc_t* servo_tm_request_tc)
-{
- return mavlink_msg_servo_tm_request_tc_pack(system_id, component_id, msg, servo_tm_request_tc->servo_id);
-}
-
-/**
- * @brief Encode a servo_tm_request_tc 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_tm_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_servo_tm_request_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_servo_tm_request_tc_t* servo_tm_request_tc)
-{
- return mavlink_msg_servo_tm_request_tc_pack_chan(system_id, component_id, chan, msg, servo_tm_request_tc->servo_id);
-}
-
-/**
- * @brief Send a servo_tm_request_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param servo_id A member of the ServosList enum
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_servo_tm_request_tc_send(mavlink_channel_t chan, uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC, buf, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-#else
- mavlink_servo_tm_request_tc_t packet;
- packet.servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC, (const char *)&packet, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a servo_tm_request_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_servo_tm_request_tc_send_struct(mavlink_channel_t chan, const mavlink_servo_tm_request_tc_t* servo_tm_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_servo_tm_request_tc_send(chan, servo_tm_request_tc->servo_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC, (const char *)servo_tm_request_tc, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_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_tm_request_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC, buf, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-#else
- mavlink_servo_tm_request_tc_t *packet = (mavlink_servo_tm_request_tc_t *)msgbuf;
- packet->servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC, (const char *)packet, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SERVO_TM_REQUEST_TC UNPACKING
-
-
-/**
- * @brief Get field servo_id from servo_tm_request_tc message
- *
- * @return A member of the ServosList enum
- */
-static inline uint8_t mavlink_msg_servo_tm_request_tc_get_servo_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a servo_tm_request_tc message into a struct
- *
- * @param msg The message to decode
- * @param servo_tm_request_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_servo_tm_request_tc_decode(const mavlink_message_t* msg, mavlink_servo_tm_request_tc_t* servo_tm_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- servo_tm_request_tc->servo_id = mavlink_msg_servo_tm_request_tc_get_servo_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN? msg->len : MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN;
- memset(servo_tm_request_tc, 0, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN);
- memcpy(servo_tm_request_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_set_algorithm_tc.h b/mavlink_lib/lyra/mavlink_msg_set_algorithm_tc.h
deleted file mode 100644
index 68de47900b54c4ba2dd2d8243250d5a1474d57e2..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_set_algorithm_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SET_ALGORITHM_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_ALGORITHM_TC 16
-
-
-typedef struct __mavlink_set_algorithm_tc_t {
- uint8_t algorithm_number; /*< Algorithm number*/
-} mavlink_set_algorithm_tc_t;
-
-#define MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN 1
-#define MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_16_LEN 1
-#define MAVLINK_MSG_ID_16_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC 181
-#define MAVLINK_MSG_ID_16_CRC 181
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC { \
- 16, \
- "SET_ALGORITHM_TC", \
- 1, \
- { { "algorithm_number", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_algorithm_tc_t, algorithm_number) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC { \
- "SET_ALGORITHM_TC", \
- 1, \
- { { "algorithm_number", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_algorithm_tc_t, algorithm_number) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_algorithm_tc 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 algorithm_number Algorithm number
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_algorithm_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t algorithm_number)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN];
- _mav_put_uint8_t(buf, 0, algorithm_number);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN);
-#else
- mavlink_set_algorithm_tc_t packet;
- packet.algorithm_number = algorithm_number;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_ALGORITHM_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-}
-
-/**
- * @brief Pack a set_algorithm_tc 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 algorithm_number Algorithm number
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_algorithm_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t algorithm_number)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN];
- _mav_put_uint8_t(buf, 0, algorithm_number);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN);
-#else
- mavlink_set_algorithm_tc_t packet;
- packet.algorithm_number = algorithm_number;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_ALGORITHM_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-}
-
-/**
- * @brief Encode a set_algorithm_tc 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_algorithm_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_algorithm_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_algorithm_tc_t* set_algorithm_tc)
-{
- return mavlink_msg_set_algorithm_tc_pack(system_id, component_id, msg, set_algorithm_tc->algorithm_number);
-}
-
-/**
- * @brief Encode a set_algorithm_tc 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_algorithm_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_algorithm_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_algorithm_tc_t* set_algorithm_tc)
-{
- return mavlink_msg_set_algorithm_tc_pack_chan(system_id, component_id, chan, msg, set_algorithm_tc->algorithm_number);
-}
-
-/**
- * @brief Send a set_algorithm_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param algorithm_number Algorithm number
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_algorithm_tc_send(mavlink_channel_t chan, uint8_t algorithm_number)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN];
- _mav_put_uint8_t(buf, 0, algorithm_number);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ALGORITHM_TC, buf, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-#else
- mavlink_set_algorithm_tc_t packet;
- packet.algorithm_number = algorithm_number;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ALGORITHM_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_algorithm_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_algorithm_tc_send_struct(mavlink_channel_t chan, const mavlink_set_algorithm_tc_t* set_algorithm_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_algorithm_tc_send(chan, set_algorithm_tc->algorithm_number);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ALGORITHM_TC, (const char *)set_algorithm_tc, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_ALGORITHM_TC_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_algorithm_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t algorithm_number)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, algorithm_number);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ALGORITHM_TC, buf, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-#else
- mavlink_set_algorithm_tc_t *packet = (mavlink_set_algorithm_tc_t *)msgbuf;
- packet->algorithm_number = algorithm_number;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ALGORITHM_TC, (const char *)packet, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_ALGORITHM_TC UNPACKING
-
-
-/**
- * @brief Get field algorithm_number from set_algorithm_tc message
- *
- * @return Algorithm number
- */
-static inline uint8_t mavlink_msg_set_algorithm_tc_get_algorithm_number(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a set_algorithm_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_algorithm_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_algorithm_tc_decode(const mavlink_message_t* msg, mavlink_set_algorithm_tc_t* set_algorithm_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_algorithm_tc->algorithm_number = mavlink_msg_set_algorithm_tc_get_algorithm_number(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN;
- memset(set_algorithm_tc, 0, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN);
- memcpy(set_algorithm_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_set_antenna_coordinates_arp_tc.h b/mavlink_lib/lyra/mavlink_msg_set_antenna_coordinates_arp_tc.h
deleted file mode 100644
index f24281f4327bf2e569f908cac94a679c428be1c2..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_set_antenna_coordinates_arp_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SET_ANTENNA_COORDINATES_ARP_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC 170
-
-
-typedef struct __mavlink_set_antenna_coordinates_arp_tc_t {
- float latitude; /*< [deg] Latitude*/
- float longitude; /*< [deg] Longitude*/
-} mavlink_set_antenna_coordinates_arp_tc_t;
-
-#define MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN 8
-#define MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_170_LEN 8
-#define MAVLINK_MSG_ID_170_MIN_LEN 8
-
-#define MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC 202
-#define MAVLINK_MSG_ID_170_CRC 202
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_ANTENNA_COORDINATES_ARP_TC { \
- 170, \
- "SET_ANTENNA_COORDINATES_ARP_TC", \
- 2, \
- { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_antenna_coordinates_arp_tc_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_antenna_coordinates_arp_tc_t, longitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_ANTENNA_COORDINATES_ARP_TC { \
- "SET_ANTENNA_COORDINATES_ARP_TC", \
- 2, \
- { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_antenna_coordinates_arp_tc_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_antenna_coordinates_arp_tc_t, longitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_antenna_coordinates_arp_tc 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 [deg] Latitude
- * @param longitude [deg] Longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN);
-#else
- mavlink_set_antenna_coordinates_arp_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC);
-}
-
-/**
- * @brief Pack a set_antenna_coordinates_arp_tc 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 [deg] Latitude
- * @param longitude [deg] Longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float latitude,float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN);
-#else
- mavlink_set_antenna_coordinates_arp_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC);
-}
-
-/**
- * @brief Encode a set_antenna_coordinates_arp_tc 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_antenna_coordinates_arp_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_antenna_coordinates_arp_tc_t* set_antenna_coordinates_arp_tc)
-{
- return mavlink_msg_set_antenna_coordinates_arp_tc_pack(system_id, component_id, msg, set_antenna_coordinates_arp_tc->latitude, set_antenna_coordinates_arp_tc->longitude);
-}
-
-/**
- * @brief Encode a set_antenna_coordinates_arp_tc 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_antenna_coordinates_arp_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_antenna_coordinates_arp_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_antenna_coordinates_arp_tc_t* set_antenna_coordinates_arp_tc)
-{
- return mavlink_msg_set_antenna_coordinates_arp_tc_pack_chan(system_id, component_id, chan, msg, set_antenna_coordinates_arp_tc->latitude, set_antenna_coordinates_arp_tc->longitude);
-}
-
-/**
- * @brief Send a set_antenna_coordinates_arp_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param latitude [deg] Latitude
- * @param longitude [deg] Longitude
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_antenna_coordinates_arp_tc_send(mavlink_channel_t chan, float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC, buf, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC);
-#else
- mavlink_set_antenna_coordinates_arp_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_antenna_coordinates_arp_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_antenna_coordinates_arp_tc_send_struct(mavlink_channel_t chan, const mavlink_set_antenna_coordinates_arp_tc_t* set_antenna_coordinates_arp_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_antenna_coordinates_arp_tc_send(chan, set_antenna_coordinates_arp_tc->latitude, set_antenna_coordinates_arp_tc->longitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC, (const char *)set_antenna_coordinates_arp_tc, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_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_antenna_coordinates_arp_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC, buf, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC);
-#else
- mavlink_set_antenna_coordinates_arp_tc_t *packet = (mavlink_set_antenna_coordinates_arp_tc_t *)msgbuf;
- packet->latitude = latitude;
- packet->longitude = longitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC, (const char *)packet, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_ANTENNA_COORDINATES_ARP_TC UNPACKING
-
-
-/**
- * @brief Get field latitude from set_antenna_coordinates_arp_tc message
- *
- * @return [deg] Latitude
- */
-static inline float mavlink_msg_set_antenna_coordinates_arp_tc_get_latitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Get field longitude from set_antenna_coordinates_arp_tc message
- *
- * @return [deg] Longitude
- */
-static inline float mavlink_msg_set_antenna_coordinates_arp_tc_get_longitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 4);
-}
-
-/**
- * @brief Decode a set_antenna_coordinates_arp_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_antenna_coordinates_arp_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_antenna_coordinates_arp_tc_decode(const mavlink_message_t* msg, mavlink_set_antenna_coordinates_arp_tc_t* set_antenna_coordinates_arp_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_antenna_coordinates_arp_tc->latitude = mavlink_msg_set_antenna_coordinates_arp_tc_get_latitude(msg);
- set_antenna_coordinates_arp_tc->longitude = mavlink_msg_set_antenna_coordinates_arp_tc_get_longitude(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN;
- memset(set_antenna_coordinates_arp_tc, 0, MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_LEN);
- memcpy(set_antenna_coordinates_arp_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_set_atomic_valve_timing_tc.h b/mavlink_lib/lyra/mavlink_msg_set_atomic_valve_timing_tc.h
deleted file mode 100644
index 767be290e5f5524ce02c1663f7eaedcd12a5a34f..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_set_atomic_valve_timing_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SET_ATOMIC_VALVE_TIMING_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC 17
-
-
-typedef struct __mavlink_set_atomic_valve_timing_tc_t {
- uint32_t maximum_timing; /*< [ms] Maximum timing in [ms]*/
- uint8_t servo_id; /*< A member of the ServosList enum*/
-} mavlink_set_atomic_valve_timing_tc_t;
-
-#define MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN 5
-#define MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN 5
-#define MAVLINK_MSG_ID_17_LEN 5
-#define MAVLINK_MSG_ID_17_MIN_LEN 5
-
-#define MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_CRC 110
-#define MAVLINK_MSG_ID_17_CRC 110
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_ATOMIC_VALVE_TIMING_TC { \
- 17, \
- "SET_ATOMIC_VALVE_TIMING_TC", \
- 2, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_atomic_valve_timing_tc_t, servo_id) }, \
- { "maximum_timing", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_atomic_valve_timing_tc_t, maximum_timing) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_ATOMIC_VALVE_TIMING_TC { \
- "SET_ATOMIC_VALVE_TIMING_TC", \
- 2, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_atomic_valve_timing_tc_t, servo_id) }, \
- { "maximum_timing", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_atomic_valve_timing_tc_t, maximum_timing) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_atomic_valve_timing_tc 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 servo_id A member of the ServosList enum
- * @param maximum_timing [ms] Maximum timing in [ms]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_atomic_valve_timing_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t servo_id, uint32_t maximum_timing)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN];
- _mav_put_uint32_t(buf, 0, maximum_timing);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN);
-#else
- mavlink_set_atomic_valve_timing_tc_t packet;
- packet.maximum_timing = maximum_timing;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_CRC);
-}
-
-/**
- * @brief Pack a set_atomic_valve_timing_tc 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 servo_id A member of the ServosList enum
- * @param maximum_timing [ms] Maximum timing in [ms]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_atomic_valve_timing_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t servo_id,uint32_t maximum_timing)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN];
- _mav_put_uint32_t(buf, 0, maximum_timing);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN);
-#else
- mavlink_set_atomic_valve_timing_tc_t packet;
- packet.maximum_timing = maximum_timing;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_CRC);
-}
-
-/**
- * @brief Encode a set_atomic_valve_timing_tc 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_atomic_valve_timing_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_atomic_valve_timing_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_atomic_valve_timing_tc_t* set_atomic_valve_timing_tc)
-{
- return mavlink_msg_set_atomic_valve_timing_tc_pack(system_id, component_id, msg, set_atomic_valve_timing_tc->servo_id, set_atomic_valve_timing_tc->maximum_timing);
-}
-
-/**
- * @brief Encode a set_atomic_valve_timing_tc 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_atomic_valve_timing_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_atomic_valve_timing_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_atomic_valve_timing_tc_t* set_atomic_valve_timing_tc)
-{
- return mavlink_msg_set_atomic_valve_timing_tc_pack_chan(system_id, component_id, chan, msg, set_atomic_valve_timing_tc->servo_id, set_atomic_valve_timing_tc->maximum_timing);
-}
-
-/**
- * @brief Send a set_atomic_valve_timing_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param servo_id A member of the ServosList enum
- * @param maximum_timing [ms] Maximum timing in [ms]
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_atomic_valve_timing_tc_send(mavlink_channel_t chan, uint8_t servo_id, uint32_t maximum_timing)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN];
- _mav_put_uint32_t(buf, 0, maximum_timing);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC, buf, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_CRC);
-#else
- mavlink_set_atomic_valve_timing_tc_t packet;
- packet.maximum_timing = maximum_timing;
- packet.servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_atomic_valve_timing_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_atomic_valve_timing_tc_send_struct(mavlink_channel_t chan, const mavlink_set_atomic_valve_timing_tc_t* set_atomic_valve_timing_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_atomic_valve_timing_tc_send(chan, set_atomic_valve_timing_tc->servo_id, set_atomic_valve_timing_tc->maximum_timing);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC, (const char *)set_atomic_valve_timing_tc, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_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_atomic_valve_timing_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t servo_id, uint32_t maximum_timing)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint32_t(buf, 0, maximum_timing);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC, buf, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_CRC);
-#else
- mavlink_set_atomic_valve_timing_tc_t *packet = (mavlink_set_atomic_valve_timing_tc_t *)msgbuf;
- packet->maximum_timing = maximum_timing;
- packet->servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC, (const char *)packet, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_ATOMIC_VALVE_TIMING_TC UNPACKING
-
-
-/**
- * @brief Get field servo_id from set_atomic_valve_timing_tc message
- *
- * @return A member of the ServosList enum
- */
-static inline uint8_t mavlink_msg_set_atomic_valve_timing_tc_get_servo_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 4);
-}
-
-/**
- * @brief Get field maximum_timing from set_atomic_valve_timing_tc message
- *
- * @return [ms] Maximum timing in [ms]
- */
-static inline uint32_t mavlink_msg_set_atomic_valve_timing_tc_get_maximum_timing(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 0);
-}
-
-/**
- * @brief Decode a set_atomic_valve_timing_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_atomic_valve_timing_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_atomic_valve_timing_tc_decode(const mavlink_message_t* msg, mavlink_set_atomic_valve_timing_tc_t* set_atomic_valve_timing_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_atomic_valve_timing_tc->maximum_timing = mavlink_msg_set_atomic_valve_timing_tc_get_maximum_timing(msg);
- set_atomic_valve_timing_tc->servo_id = mavlink_msg_set_atomic_valve_timing_tc_get_servo_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN;
- memset(set_atomic_valve_timing_tc, 0, MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_LEN);
- memcpy(set_atomic_valve_timing_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_set_coordinates_tc.h b/mavlink_lib/lyra/mavlink_msg_set_coordinates_tc.h
deleted file mode 100644
index 827f0ec42e8f8ca2cc283732f06ebc1f9a966af0..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_set_coordinates_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SET_COORDINATES_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_COORDINATES_TC 12
-
-
-typedef struct __mavlink_set_coordinates_tc_t {
- float latitude; /*< [deg] Latitude*/
- float longitude; /*< [deg] Longitude*/
-} mavlink_set_coordinates_tc_t;
-
-#define MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN 8
-#define MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_12_LEN 8
-#define MAVLINK_MSG_ID_12_MIN_LEN 8
-
-#define MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC 67
-#define MAVLINK_MSG_ID_12_CRC 67
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC { \
- 12, \
- "SET_COORDINATES_TC", \
- 2, \
- { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_coordinates_tc_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_coordinates_tc_t, longitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC { \
- "SET_COORDINATES_TC", \
- 2, \
- { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_coordinates_tc_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_coordinates_tc_t, longitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_coordinates_tc 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 [deg] Latitude
- * @param longitude [deg] Longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_coordinates_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN);
-#else
- mavlink_set_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_COORDINATES_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-}
-
-/**
- * @brief Pack a set_coordinates_tc 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 [deg] Latitude
- * @param longitude [deg] Longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_coordinates_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float latitude,float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN);
-#else
- mavlink_set_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_COORDINATES_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-}
-
-/**
- * @brief Encode a set_coordinates_tc 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_coordinates_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_coordinates_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_coordinates_tc_t* set_coordinates_tc)
-{
- return mavlink_msg_set_coordinates_tc_pack(system_id, component_id, msg, set_coordinates_tc->latitude, set_coordinates_tc->longitude);
-}
-
-/**
- * @brief Encode a set_coordinates_tc 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_coordinates_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_coordinates_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_coordinates_tc_t* set_coordinates_tc)
-{
- return mavlink_msg_set_coordinates_tc_pack_chan(system_id, component_id, chan, msg, set_coordinates_tc->latitude, set_coordinates_tc->longitude);
-}
-
-/**
- * @brief Send a set_coordinates_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param latitude [deg] Latitude
- * @param longitude [deg] Longitude
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_coordinates_tc_send(mavlink_channel_t chan, float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_COORDINATES_TC, buf, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-#else
- mavlink_set_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_COORDINATES_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_coordinates_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_coordinates_tc_send_struct(mavlink_channel_t chan, const mavlink_set_coordinates_tc_t* set_coordinates_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_coordinates_tc_send(chan, set_coordinates_tc->latitude, set_coordinates_tc->longitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_COORDINATES_TC, (const char *)set_coordinates_tc, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_COORDINATES_TC_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_coordinates_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_COORDINATES_TC, buf, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-#else
- mavlink_set_coordinates_tc_t *packet = (mavlink_set_coordinates_tc_t *)msgbuf;
- packet->latitude = latitude;
- packet->longitude = longitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_COORDINATES_TC, (const char *)packet, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_COORDINATES_TC UNPACKING
-
-
-/**
- * @brief Get field latitude from set_coordinates_tc message
- *
- * @return [deg] Latitude
- */
-static inline float mavlink_msg_set_coordinates_tc_get_latitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Get field longitude from set_coordinates_tc message
- *
- * @return [deg] Longitude
- */
-static inline float mavlink_msg_set_coordinates_tc_get_longitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 4);
-}
-
-/**
- * @brief Decode a set_coordinates_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_coordinates_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_coordinates_tc_decode(const mavlink_message_t* msg, mavlink_set_coordinates_tc_t* set_coordinates_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_coordinates_tc->latitude = mavlink_msg_set_coordinates_tc_get_latitude(msg);
- set_coordinates_tc->longitude = mavlink_msg_set_coordinates_tc_get_longitude(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN;
- memset(set_coordinates_tc, 0, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN);
- memcpy(set_coordinates_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_set_deployment_altitude_tc.h b/mavlink_lib/lyra/mavlink_msg_set_deployment_altitude_tc.h
deleted file mode 100644
index 38c61267d4498fb5f1924eaf8a83b701d0d37677..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_set_deployment_altitude_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SET_DEPLOYMENT_ALTITUDE_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC 14
-
-
-typedef struct __mavlink_set_deployment_altitude_tc_t {
- float dpl_altitude; /*< [m] Deployment altitude*/
-} mavlink_set_deployment_altitude_tc_t;
-
-#define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN 4
-#define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN 4
-#define MAVLINK_MSG_ID_14_LEN 4
-#define MAVLINK_MSG_ID_14_MIN_LEN 4
-
-#define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC 44
-#define MAVLINK_MSG_ID_14_CRC 44
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC { \
- 14, \
- "SET_DEPLOYMENT_ALTITUDE_TC", \
- 1, \
- { { "dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_deployment_altitude_tc_t, dpl_altitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC { \
- "SET_DEPLOYMENT_ALTITUDE_TC", \
- 1, \
- { { "dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_deployment_altitude_tc_t, dpl_altitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_deployment_altitude_tc 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 dpl_altitude [m] Deployment altitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_deployment_altitude_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, dpl_altitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
-#else
- mavlink_set_deployment_altitude_tc_t packet;
- packet.dpl_altitude = dpl_altitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-}
-
-/**
- * @brief Pack a set_deployment_altitude_tc 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 dpl_altitude [m] Deployment altitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_deployment_altitude_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, dpl_altitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
-#else
- mavlink_set_deployment_altitude_tc_t packet;
- packet.dpl_altitude = dpl_altitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-}
-
-/**
- * @brief Encode a set_deployment_altitude_tc 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_deployment_altitude_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_deployment_altitude_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_deployment_altitude_tc_t* set_deployment_altitude_tc)
-{
- return mavlink_msg_set_deployment_altitude_tc_pack(system_id, component_id, msg, set_deployment_altitude_tc->dpl_altitude);
-}
-
-/**
- * @brief Encode a set_deployment_altitude_tc 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_deployment_altitude_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_deployment_altitude_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_deployment_altitude_tc_t* set_deployment_altitude_tc)
-{
- return mavlink_msg_set_deployment_altitude_tc_pack_chan(system_id, component_id, chan, msg, set_deployment_altitude_tc->dpl_altitude);
-}
-
-/**
- * @brief Send a set_deployment_altitude_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param dpl_altitude [m] Deployment altitude
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_deployment_altitude_tc_send(mavlink_channel_t chan, float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, dpl_altitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC, buf, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-#else
- mavlink_set_deployment_altitude_tc_t packet;
- packet.dpl_altitude = dpl_altitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_deployment_altitude_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_deployment_altitude_tc_send_struct(mavlink_channel_t chan, const mavlink_set_deployment_altitude_tc_t* set_deployment_altitude_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_deployment_altitude_tc_send(chan, set_deployment_altitude_tc->dpl_altitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC, (const char *)set_deployment_altitude_tc, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_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_deployment_altitude_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, dpl_altitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC, buf, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-#else
- mavlink_set_deployment_altitude_tc_t *packet = (mavlink_set_deployment_altitude_tc_t *)msgbuf;
- packet->dpl_altitude = dpl_altitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC, (const char *)packet, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_DEPLOYMENT_ALTITUDE_TC UNPACKING
-
-
-/**
- * @brief Get field dpl_altitude from set_deployment_altitude_tc message
- *
- * @return [m] Deployment altitude
- */
-static inline float mavlink_msg_set_deployment_altitude_tc_get_dpl_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a set_deployment_altitude_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_deployment_altitude_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_deployment_altitude_tc_decode(const mavlink_message_t* msg, mavlink_set_deployment_altitude_tc_t* set_deployment_altitude_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_deployment_altitude_tc->dpl_altitude = mavlink_msg_set_deployment_altitude_tc_get_dpl_altitude(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN;
- memset(set_deployment_altitude_tc, 0, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
- memcpy(set_deployment_altitude_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_set_ignition_time_tc.h b/mavlink_lib/lyra/mavlink_msg_set_ignition_time_tc.h
deleted file mode 100644
index 8ca91d61d9f9331adcf84943b20765cc5b65bc74..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_set_ignition_time_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SET_IGNITION_TIME_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_IGNITION_TIME_TC 20
-
-
-typedef struct __mavlink_set_ignition_time_tc_t {
- uint32_t timing; /*< [ms] Timing in [ms]*/
-} mavlink_set_ignition_time_tc_t;
-
-#define MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN 4
-#define MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN 4
-#define MAVLINK_MSG_ID_20_LEN 4
-#define MAVLINK_MSG_ID_20_MIN_LEN 4
-
-#define MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC 79
-#define MAVLINK_MSG_ID_20_CRC 79
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC { \
- 20, \
- "SET_IGNITION_TIME_TC", \
- 1, \
- { { "timing", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_ignition_time_tc_t, timing) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC { \
- "SET_IGNITION_TIME_TC", \
- 1, \
- { { "timing", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_ignition_time_tc_t, timing) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_ignition_time_tc 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 timing [ms] Timing in [ms]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_ignition_time_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint32_t timing)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN];
- _mav_put_uint32_t(buf, 0, timing);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN);
-#else
- mavlink_set_ignition_time_tc_t packet;
- packet.timing = timing;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_IGNITION_TIME_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC);
-}
-
-/**
- * @brief Pack a set_ignition_time_tc 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 timing [ms] Timing in [ms]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_ignition_time_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint32_t timing)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN];
- _mav_put_uint32_t(buf, 0, timing);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN);
-#else
- mavlink_set_ignition_time_tc_t packet;
- packet.timing = timing;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_IGNITION_TIME_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC);
-}
-
-/**
- * @brief Encode a set_ignition_time_tc 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_ignition_time_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_ignition_time_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_ignition_time_tc_t* set_ignition_time_tc)
-{
- return mavlink_msg_set_ignition_time_tc_pack(system_id, component_id, msg, set_ignition_time_tc->timing);
-}
-
-/**
- * @brief Encode a set_ignition_time_tc 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_ignition_time_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_ignition_time_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_ignition_time_tc_t* set_ignition_time_tc)
-{
- return mavlink_msg_set_ignition_time_tc_pack_chan(system_id, component_id, chan, msg, set_ignition_time_tc->timing);
-}
-
-/**
- * @brief Send a set_ignition_time_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param timing [ms] Timing in [ms]
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_ignition_time_tc_send(mavlink_channel_t chan, uint32_t timing)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN];
- _mav_put_uint32_t(buf, 0, timing);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC, buf, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC);
-#else
- mavlink_set_ignition_time_tc_t packet;
- packet.timing = timing;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_ignition_time_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_ignition_time_tc_send_struct(mavlink_channel_t chan, const mavlink_set_ignition_time_tc_t* set_ignition_time_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_ignition_time_tc_send(chan, set_ignition_time_tc->timing);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC, (const char *)set_ignition_time_tc, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_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_ignition_time_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t timing)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint32_t(buf, 0, timing);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC, buf, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC);
-#else
- mavlink_set_ignition_time_tc_t *packet = (mavlink_set_ignition_time_tc_t *)msgbuf;
- packet->timing = timing;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC, (const char *)packet, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_IGNITION_TIME_TC UNPACKING
-
-
-/**
- * @brief Get field timing from set_ignition_time_tc message
- *
- * @return [ms] Timing in [ms]
- */
-static inline uint32_t mavlink_msg_set_ignition_time_tc_get_timing(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 0);
-}
-
-/**
- * @brief Decode a set_ignition_time_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_ignition_time_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_ignition_time_tc_decode(const mavlink_message_t* msg, mavlink_set_ignition_time_tc_t* set_ignition_time_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_ignition_time_tc->timing = mavlink_msg_set_ignition_time_tc_get_timing(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN;
- memset(set_ignition_time_tc, 0, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN);
- memcpy(set_ignition_time_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_set_orientation_tc.h b/mavlink_lib/lyra/mavlink_msg_set_orientation_tc.h
deleted file mode 100644
index 5169814cd4c7a7afbe6e204bf82fb2d049078fc7..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_set_orientation_tc.h
+++ /dev/null
@@ -1,263 +0,0 @@
-#pragma once
-// MESSAGE SET_ORIENTATION_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_ORIENTATION_TC 11
-
-
-typedef struct __mavlink_set_orientation_tc_t {
- float yaw; /*< [deg] Yaw angle*/
- float pitch; /*< [deg] Pitch angle*/
- float roll; /*< [deg] Roll angle*/
-} mavlink_set_orientation_tc_t;
-
-#define MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN 12
-#define MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN 12
-#define MAVLINK_MSG_ID_11_LEN 12
-#define MAVLINK_MSG_ID_11_MIN_LEN 12
-
-#define MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC 71
-#define MAVLINK_MSG_ID_11_CRC 71
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC { \
- 11, \
- "SET_ORIENTATION_TC", \
- 3, \
- { { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_orientation_tc_t, yaw) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_orientation_tc_t, pitch) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_orientation_tc_t, roll) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC { \
- "SET_ORIENTATION_TC", \
- 3, \
- { { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_orientation_tc_t, yaw) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_orientation_tc_t, pitch) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_orientation_tc_t, roll) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_orientation_tc 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 yaw [deg] Yaw angle
- * @param pitch [deg] Pitch angle
- * @param roll [deg] Roll angle
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_orientation_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float yaw, float pitch, float roll)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN];
- _mav_put_float(buf, 0, yaw);
- _mav_put_float(buf, 4, pitch);
- _mav_put_float(buf, 8, roll);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN);
-#else
- mavlink_set_orientation_tc_t packet;
- packet.yaw = yaw;
- packet.pitch = pitch;
- packet.roll = roll;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_ORIENTATION_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-}
-
-/**
- * @brief Pack a set_orientation_tc 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 yaw [deg] Yaw angle
- * @param pitch [deg] Pitch angle
- * @param roll [deg] Roll angle
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_orientation_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float yaw,float pitch,float roll)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN];
- _mav_put_float(buf, 0, yaw);
- _mav_put_float(buf, 4, pitch);
- _mav_put_float(buf, 8, roll);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN);
-#else
- mavlink_set_orientation_tc_t packet;
- packet.yaw = yaw;
- packet.pitch = pitch;
- packet.roll = roll;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_ORIENTATION_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-}
-
-/**
- * @brief Encode a set_orientation_tc 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_orientation_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_orientation_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_orientation_tc_t* set_orientation_tc)
-{
- return mavlink_msg_set_orientation_tc_pack(system_id, component_id, msg, set_orientation_tc->yaw, set_orientation_tc->pitch, set_orientation_tc->roll);
-}
-
-/**
- * @brief Encode a set_orientation_tc 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_orientation_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_orientation_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_orientation_tc_t* set_orientation_tc)
-{
- return mavlink_msg_set_orientation_tc_pack_chan(system_id, component_id, chan, msg, set_orientation_tc->yaw, set_orientation_tc->pitch, set_orientation_tc->roll);
-}
-
-/**
- * @brief Send a set_orientation_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param yaw [deg] Yaw angle
- * @param pitch [deg] Pitch angle
- * @param roll [deg] Roll angle
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_orientation_tc_send(mavlink_channel_t chan, float yaw, float pitch, float roll)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN];
- _mav_put_float(buf, 0, yaw);
- _mav_put_float(buf, 4, pitch);
- _mav_put_float(buf, 8, roll);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ORIENTATION_TC, buf, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-#else
- mavlink_set_orientation_tc_t packet;
- packet.yaw = yaw;
- packet.pitch = pitch;
- packet.roll = roll;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ORIENTATION_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_orientation_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_orientation_tc_send_struct(mavlink_channel_t chan, const mavlink_set_orientation_tc_t* set_orientation_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_orientation_tc_send(chan, set_orientation_tc->yaw, set_orientation_tc->pitch, set_orientation_tc->roll);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ORIENTATION_TC, (const char *)set_orientation_tc, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_ORIENTATION_TC_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_orientation_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float yaw, float pitch, float roll)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, yaw);
- _mav_put_float(buf, 4, pitch);
- _mav_put_float(buf, 8, roll);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ORIENTATION_TC, buf, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-#else
- mavlink_set_orientation_tc_t *packet = (mavlink_set_orientation_tc_t *)msgbuf;
- packet->yaw = yaw;
- packet->pitch = pitch;
- packet->roll = roll;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ORIENTATION_TC, (const char *)packet, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_ORIENTATION_TC UNPACKING
-
-
-/**
- * @brief Get field yaw from set_orientation_tc message
- *
- * @return [deg] Yaw angle
- */
-static inline float mavlink_msg_set_orientation_tc_get_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Get field pitch from set_orientation_tc message
- *
- * @return [deg] Pitch angle
- */
-static inline float mavlink_msg_set_orientation_tc_get_pitch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 4);
-}
-
-/**
- * @brief Get field roll from set_orientation_tc message
- *
- * @return [deg] Roll angle
- */
-static inline float mavlink_msg_set_orientation_tc_get_roll(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Decode a set_orientation_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_orientation_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_orientation_tc_decode(const mavlink_message_t* msg, mavlink_set_orientation_tc_t* set_orientation_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_orientation_tc->yaw = mavlink_msg_set_orientation_tc_get_yaw(msg);
- set_orientation_tc->pitch = mavlink_msg_set_orientation_tc_get_pitch(msg);
- set_orientation_tc->roll = mavlink_msg_set_orientation_tc_get_roll(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN;
- memset(set_orientation_tc, 0, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN);
- memcpy(set_orientation_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_set_reference_altitude_tc.h b/mavlink_lib/lyra/mavlink_msg_set_reference_altitude_tc.h
deleted file mode 100644
index a291b0b8da0d1d60e7e30767ade22abc5f35402a..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_set_reference_altitude_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SET_REFERENCE_ALTITUDE_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC 9
-
-
-typedef struct __mavlink_set_reference_altitude_tc_t {
- float ref_altitude; /*< [m] Reference altitude*/
-} mavlink_set_reference_altitude_tc_t;
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN 4
-#define MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN 4
-#define MAVLINK_MSG_ID_9_LEN 4
-#define MAVLINK_MSG_ID_9_MIN_LEN 4
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC 113
-#define MAVLINK_MSG_ID_9_CRC 113
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC { \
- 9, \
- "SET_REFERENCE_ALTITUDE_TC", \
- 1, \
- { { "ref_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_reference_altitude_tc_t, ref_altitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC { \
- "SET_REFERENCE_ALTITUDE_TC", \
- 1, \
- { { "ref_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_reference_altitude_tc_t, ref_altitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_reference_altitude_tc 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 ref_altitude [m] Reference altitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_reference_altitude_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float ref_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, ref_altitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN);
-#else
- mavlink_set_reference_altitude_tc_t packet;
- packet.ref_altitude = ref_altitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-}
-
-/**
- * @brief Pack a set_reference_altitude_tc 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 ref_altitude [m] Reference altitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_reference_altitude_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float ref_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, ref_altitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN);
-#else
- mavlink_set_reference_altitude_tc_t packet;
- packet.ref_altitude = ref_altitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-}
-
-/**
- * @brief Encode a set_reference_altitude_tc 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_reference_altitude_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_reference_altitude_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_reference_altitude_tc_t* set_reference_altitude_tc)
-{
- return mavlink_msg_set_reference_altitude_tc_pack(system_id, component_id, msg, set_reference_altitude_tc->ref_altitude);
-}
-
-/**
- * @brief Encode a set_reference_altitude_tc 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_reference_altitude_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_reference_altitude_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_reference_altitude_tc_t* set_reference_altitude_tc)
-{
- return mavlink_msg_set_reference_altitude_tc_pack_chan(system_id, component_id, chan, msg, set_reference_altitude_tc->ref_altitude);
-}
-
-/**
- * @brief Send a set_reference_altitude_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param ref_altitude [m] Reference altitude
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_reference_altitude_tc_send(mavlink_channel_t chan, float ref_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, ref_altitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC, buf, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-#else
- mavlink_set_reference_altitude_tc_t packet;
- packet.ref_altitude = ref_altitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_reference_altitude_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_reference_altitude_tc_send_struct(mavlink_channel_t chan, const mavlink_set_reference_altitude_tc_t* set_reference_altitude_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_reference_altitude_tc_send(chan, set_reference_altitude_tc->ref_altitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC, (const char *)set_reference_altitude_tc, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_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_reference_altitude_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float ref_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, ref_altitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC, buf, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-#else
- mavlink_set_reference_altitude_tc_t *packet = (mavlink_set_reference_altitude_tc_t *)msgbuf;
- packet->ref_altitude = ref_altitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC, (const char *)packet, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_REFERENCE_ALTITUDE_TC UNPACKING
-
-
-/**
- * @brief Get field ref_altitude from set_reference_altitude_tc message
- *
- * @return [m] Reference altitude
- */
-static inline float mavlink_msg_set_reference_altitude_tc_get_ref_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a set_reference_altitude_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_reference_altitude_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_reference_altitude_tc_decode(const mavlink_message_t* msg, mavlink_set_reference_altitude_tc_t* set_reference_altitude_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_reference_altitude_tc->ref_altitude = mavlink_msg_set_reference_altitude_tc_get_ref_altitude(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN;
- memset(set_reference_altitude_tc, 0, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN);
- memcpy(set_reference_altitude_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_set_reference_temperature_tc.h b/mavlink_lib/lyra/mavlink_msg_set_reference_temperature_tc.h
deleted file mode 100644
index 5bb1c529477606617b93eca65726e9580259f832..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_set_reference_temperature_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SET_REFERENCE_TEMPERATURE_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC 10
-
-
-typedef struct __mavlink_set_reference_temperature_tc_t {
- float ref_temp; /*< [degC] Reference temperature*/
-} mavlink_set_reference_temperature_tc_t;
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN 4
-#define MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN 4
-#define MAVLINK_MSG_ID_10_LEN 4
-#define MAVLINK_MSG_ID_10_MIN_LEN 4
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC 38
-#define MAVLINK_MSG_ID_10_CRC 38
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC { \
- 10, \
- "SET_REFERENCE_TEMPERATURE_TC", \
- 1, \
- { { "ref_temp", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_reference_temperature_tc_t, ref_temp) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC { \
- "SET_REFERENCE_TEMPERATURE_TC", \
- 1, \
- { { "ref_temp", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_reference_temperature_tc_t, ref_temp) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_reference_temperature_tc 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 ref_temp [degC] Reference temperature
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_reference_temperature_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float ref_temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN];
- _mav_put_float(buf, 0, ref_temp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
-#else
- mavlink_set_reference_temperature_tc_t packet;
- packet.ref_temp = ref_temp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-}
-
-/**
- * @brief Pack a set_reference_temperature_tc 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 ref_temp [degC] Reference temperature
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_reference_temperature_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float ref_temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN];
- _mav_put_float(buf, 0, ref_temp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
-#else
- mavlink_set_reference_temperature_tc_t packet;
- packet.ref_temp = ref_temp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-}
-
-/**
- * @brief Encode a set_reference_temperature_tc 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_reference_temperature_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_reference_temperature_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_reference_temperature_tc_t* set_reference_temperature_tc)
-{
- return mavlink_msg_set_reference_temperature_tc_pack(system_id, component_id, msg, set_reference_temperature_tc->ref_temp);
-}
-
-/**
- * @brief Encode a set_reference_temperature_tc 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_reference_temperature_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_reference_temperature_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_reference_temperature_tc_t* set_reference_temperature_tc)
-{
- return mavlink_msg_set_reference_temperature_tc_pack_chan(system_id, component_id, chan, msg, set_reference_temperature_tc->ref_temp);
-}
-
-/**
- * @brief Send a set_reference_temperature_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param ref_temp [degC] Reference temperature
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_reference_temperature_tc_send(mavlink_channel_t chan, float ref_temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN];
- _mav_put_float(buf, 0, ref_temp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC, buf, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-#else
- mavlink_set_reference_temperature_tc_t packet;
- packet.ref_temp = ref_temp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_reference_temperature_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_reference_temperature_tc_send_struct(mavlink_channel_t chan, const mavlink_set_reference_temperature_tc_t* set_reference_temperature_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_reference_temperature_tc_send(chan, set_reference_temperature_tc->ref_temp);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC, (const char *)set_reference_temperature_tc, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_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_reference_temperature_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float ref_temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, ref_temp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC, buf, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-#else
- mavlink_set_reference_temperature_tc_t *packet = (mavlink_set_reference_temperature_tc_t *)msgbuf;
- packet->ref_temp = ref_temp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC, (const char *)packet, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_REFERENCE_TEMPERATURE_TC UNPACKING
-
-
-/**
- * @brief Get field ref_temp from set_reference_temperature_tc message
- *
- * @return [degC] Reference temperature
- */
-static inline float mavlink_msg_set_reference_temperature_tc_get_ref_temp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a set_reference_temperature_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_reference_temperature_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_reference_temperature_tc_decode(const mavlink_message_t* msg, mavlink_set_reference_temperature_tc_t* set_reference_temperature_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_reference_temperature_tc->ref_temp = mavlink_msg_set_reference_temperature_tc_get_ref_temp(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN;
- memset(set_reference_temperature_tc, 0, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
- memcpy(set_reference_temperature_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_set_rocket_coordinates_arp_tc.h b/mavlink_lib/lyra/mavlink_msg_set_rocket_coordinates_arp_tc.h
deleted file mode 100644
index 0cca27cd5973de3fb8d91fc9743ffa980aaf41ba..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_set_rocket_coordinates_arp_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SET_ROCKET_COORDINATES_ARP_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC 171
-
-
-typedef struct __mavlink_set_rocket_coordinates_arp_tc_t {
- float latitude; /*< [deg] Latitude*/
- float longitude; /*< [deg] Longitude*/
-} mavlink_set_rocket_coordinates_arp_tc_t;
-
-#define MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN 8
-#define MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_171_LEN 8
-#define MAVLINK_MSG_ID_171_MIN_LEN 8
-
-#define MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC 164
-#define MAVLINK_MSG_ID_171_CRC 164
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_ROCKET_COORDINATES_ARP_TC { \
- 171, \
- "SET_ROCKET_COORDINATES_ARP_TC", \
- 2, \
- { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_rocket_coordinates_arp_tc_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_rocket_coordinates_arp_tc_t, longitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_ROCKET_COORDINATES_ARP_TC { \
- "SET_ROCKET_COORDINATES_ARP_TC", \
- 2, \
- { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_rocket_coordinates_arp_tc_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_rocket_coordinates_arp_tc_t, longitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_rocket_coordinates_arp_tc 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 [deg] Latitude
- * @param longitude [deg] Longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN);
-#else
- mavlink_set_rocket_coordinates_arp_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC);
-}
-
-/**
- * @brief Pack a set_rocket_coordinates_arp_tc 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 [deg] Latitude
- * @param longitude [deg] Longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float latitude,float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN);
-#else
- mavlink_set_rocket_coordinates_arp_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC);
-}
-
-/**
- * @brief Encode a set_rocket_coordinates_arp_tc 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_rocket_coordinates_arp_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_rocket_coordinates_arp_tc_t* set_rocket_coordinates_arp_tc)
-{
- return mavlink_msg_set_rocket_coordinates_arp_tc_pack(system_id, component_id, msg, set_rocket_coordinates_arp_tc->latitude, set_rocket_coordinates_arp_tc->longitude);
-}
-
-/**
- * @brief Encode a set_rocket_coordinates_arp_tc 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_rocket_coordinates_arp_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_rocket_coordinates_arp_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_rocket_coordinates_arp_tc_t* set_rocket_coordinates_arp_tc)
-{
- return mavlink_msg_set_rocket_coordinates_arp_tc_pack_chan(system_id, component_id, chan, msg, set_rocket_coordinates_arp_tc->latitude, set_rocket_coordinates_arp_tc->longitude);
-}
-
-/**
- * @brief Send a set_rocket_coordinates_arp_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param latitude [deg] Latitude
- * @param longitude [deg] Longitude
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_rocket_coordinates_arp_tc_send(mavlink_channel_t chan, float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC, buf, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC);
-#else
- mavlink_set_rocket_coordinates_arp_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_rocket_coordinates_arp_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_rocket_coordinates_arp_tc_send_struct(mavlink_channel_t chan, const mavlink_set_rocket_coordinates_arp_tc_t* set_rocket_coordinates_arp_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_rocket_coordinates_arp_tc_send(chan, set_rocket_coordinates_arp_tc->latitude, set_rocket_coordinates_arp_tc->longitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC, (const char *)set_rocket_coordinates_arp_tc, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_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_rocket_coordinates_arp_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC, buf, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC);
-#else
- mavlink_set_rocket_coordinates_arp_tc_t *packet = (mavlink_set_rocket_coordinates_arp_tc_t *)msgbuf;
- packet->latitude = latitude;
- packet->longitude = longitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC, (const char *)packet, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_ROCKET_COORDINATES_ARP_TC UNPACKING
-
-
-/**
- * @brief Get field latitude from set_rocket_coordinates_arp_tc message
- *
- * @return [deg] Latitude
- */
-static inline float mavlink_msg_set_rocket_coordinates_arp_tc_get_latitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Get field longitude from set_rocket_coordinates_arp_tc message
- *
- * @return [deg] Longitude
- */
-static inline float mavlink_msg_set_rocket_coordinates_arp_tc_get_longitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 4);
-}
-
-/**
- * @brief Decode a set_rocket_coordinates_arp_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_rocket_coordinates_arp_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_rocket_coordinates_arp_tc_decode(const mavlink_message_t* msg, mavlink_set_rocket_coordinates_arp_tc_t* set_rocket_coordinates_arp_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_rocket_coordinates_arp_tc->latitude = mavlink_msg_set_rocket_coordinates_arp_tc_get_latitude(msg);
- set_rocket_coordinates_arp_tc->longitude = mavlink_msg_set_rocket_coordinates_arp_tc_get_longitude(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN;
- memset(set_rocket_coordinates_arp_tc, 0, MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_LEN);
- memcpy(set_rocket_coordinates_arp_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_set_servo_angle_tc.h b/mavlink_lib/lyra/mavlink_msg_set_servo_angle_tc.h
deleted file mode 100644
index 74f2888721a7ed79d479df991d640deb064d50cc..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_set_servo_angle_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SET_SERVO_ANGLE_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC 6
-
-
-typedef struct __mavlink_set_servo_angle_tc_t {
- float angle; /*< Servo angle in normalized value [0-1]*/
- uint8_t servo_id; /*< A member of the ServosList enum*/
-} mavlink_set_servo_angle_tc_t;
-
-#define MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN 5
-#define MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN 5
-#define MAVLINK_MSG_ID_6_LEN 5
-#define MAVLINK_MSG_ID_6_MIN_LEN 5
-
-#define MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC 215
-#define MAVLINK_MSG_ID_6_CRC 215
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC { \
- 6, \
- "SET_SERVO_ANGLE_TC", \
- 2, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_servo_angle_tc_t, servo_id) }, \
- { "angle", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_servo_angle_tc_t, angle) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC { \
- "SET_SERVO_ANGLE_TC", \
- 2, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_servo_angle_tc_t, servo_id) }, \
- { "angle", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_servo_angle_tc_t, angle) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_servo_angle_tc 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 servo_id A member of the ServosList enum
- * @param angle Servo angle in normalized value [0-1]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_servo_angle_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t servo_id, float angle)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN];
- _mav_put_float(buf, 0, angle);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN);
-#else
- mavlink_set_servo_angle_tc_t packet;
- packet.angle = angle;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-}
-
-/**
- * @brief Pack a set_servo_angle_tc 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 servo_id A member of the ServosList enum
- * @param angle Servo angle in normalized value [0-1]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_servo_angle_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t servo_id,float angle)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN];
- _mav_put_float(buf, 0, angle);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN);
-#else
- mavlink_set_servo_angle_tc_t packet;
- packet.angle = angle;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-}
-
-/**
- * @brief Encode a set_servo_angle_tc 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_servo_angle_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_servo_angle_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_servo_angle_tc_t* set_servo_angle_tc)
-{
- return mavlink_msg_set_servo_angle_tc_pack(system_id, component_id, msg, set_servo_angle_tc->servo_id, set_servo_angle_tc->angle);
-}
-
-/**
- * @brief Encode a set_servo_angle_tc 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_servo_angle_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_servo_angle_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_servo_angle_tc_t* set_servo_angle_tc)
-{
- return mavlink_msg_set_servo_angle_tc_pack_chan(system_id, component_id, chan, msg, set_servo_angle_tc->servo_id, set_servo_angle_tc->angle);
-}
-
-/**
- * @brief Send a set_servo_angle_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param servo_id A member of the ServosList enum
- * @param angle Servo angle in normalized value [0-1]
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_servo_angle_tc_send(mavlink_channel_t chan, uint8_t servo_id, float angle)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN];
- _mav_put_float(buf, 0, angle);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC, buf, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-#else
- mavlink_set_servo_angle_tc_t packet;
- packet.angle = angle;
- packet.servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_servo_angle_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_servo_angle_tc_send_struct(mavlink_channel_t chan, const mavlink_set_servo_angle_tc_t* set_servo_angle_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_servo_angle_tc_send(chan, set_servo_angle_tc->servo_id, set_servo_angle_tc->angle);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC, (const char *)set_servo_angle_tc, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_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_servo_angle_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t servo_id, float angle)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, angle);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC, buf, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-#else
- mavlink_set_servo_angle_tc_t *packet = (mavlink_set_servo_angle_tc_t *)msgbuf;
- packet->angle = angle;
- packet->servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC, (const char *)packet, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_SERVO_ANGLE_TC UNPACKING
-
-
-/**
- * @brief Get field servo_id from set_servo_angle_tc message
- *
- * @return A member of the ServosList enum
- */
-static inline uint8_t mavlink_msg_set_servo_angle_tc_get_servo_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 4);
-}
-
-/**
- * @brief Get field angle from set_servo_angle_tc message
- *
- * @return Servo angle in normalized value [0-1]
- */
-static inline float mavlink_msg_set_servo_angle_tc_get_angle(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a set_servo_angle_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_servo_angle_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_servo_angle_tc_decode(const mavlink_message_t* msg, mavlink_set_servo_angle_tc_t* set_servo_angle_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_servo_angle_tc->angle = mavlink_msg_set_servo_angle_tc_get_angle(msg);
- set_servo_angle_tc->servo_id = mavlink_msg_set_servo_angle_tc_get_servo_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN;
- memset(set_servo_angle_tc, 0, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN);
- memcpy(set_servo_angle_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_set_stepper_angle_tc.h b/mavlink_lib/lyra/mavlink_msg_set_stepper_angle_tc.h
deleted file mode 100644
index 332d79f8156a93e4a4952b37d93caecd593a7507..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_set_stepper_angle_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SET_STEPPER_ANGLE_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC 21
-
-
-typedef struct __mavlink_set_stepper_angle_tc_t {
- float angle; /*< Stepper angle in degrees*/
- uint8_t stepper_id; /*< A member of the StepperList enum*/
-} mavlink_set_stepper_angle_tc_t;
-
-#define MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN 5
-#define MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_MIN_LEN 5
-#define MAVLINK_MSG_ID_21_LEN 5
-#define MAVLINK_MSG_ID_21_MIN_LEN 5
-
-#define MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_CRC 180
-#define MAVLINK_MSG_ID_21_CRC 180
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_STEPPER_ANGLE_TC { \
- 21, \
- "SET_STEPPER_ANGLE_TC", \
- 2, \
- { { "stepper_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_stepper_angle_tc_t, stepper_id) }, \
- { "angle", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_stepper_angle_tc_t, angle) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_STEPPER_ANGLE_TC { \
- "SET_STEPPER_ANGLE_TC", \
- 2, \
- { { "stepper_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_stepper_angle_tc_t, stepper_id) }, \
- { "angle", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_stepper_angle_tc_t, angle) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_stepper_angle_tc 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 stepper_id A member of the StepperList enum
- * @param angle Stepper angle in degrees
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_stepper_angle_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t stepper_id, float angle)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN];
- _mav_put_float(buf, 0, angle);
- _mav_put_uint8_t(buf, 4, stepper_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN);
-#else
- mavlink_set_stepper_angle_tc_t packet;
- packet.angle = angle;
- packet.stepper_id = stepper_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_CRC);
-}
-
-/**
- * @brief Pack a set_stepper_angle_tc 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 stepper_id A member of the StepperList enum
- * @param angle Stepper angle in degrees
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_stepper_angle_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t stepper_id,float angle)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN];
- _mav_put_float(buf, 0, angle);
- _mav_put_uint8_t(buf, 4, stepper_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN);
-#else
- mavlink_set_stepper_angle_tc_t packet;
- packet.angle = angle;
- packet.stepper_id = stepper_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_CRC);
-}
-
-/**
- * @brief Encode a set_stepper_angle_tc 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_stepper_angle_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_stepper_angle_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_stepper_angle_tc_t* set_stepper_angle_tc)
-{
- return mavlink_msg_set_stepper_angle_tc_pack(system_id, component_id, msg, set_stepper_angle_tc->stepper_id, set_stepper_angle_tc->angle);
-}
-
-/**
- * @brief Encode a set_stepper_angle_tc 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_stepper_angle_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_stepper_angle_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_stepper_angle_tc_t* set_stepper_angle_tc)
-{
- return mavlink_msg_set_stepper_angle_tc_pack_chan(system_id, component_id, chan, msg, set_stepper_angle_tc->stepper_id, set_stepper_angle_tc->angle);
-}
-
-/**
- * @brief Send a set_stepper_angle_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param stepper_id A member of the StepperList enum
- * @param angle Stepper angle in degrees
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_stepper_angle_tc_send(mavlink_channel_t chan, uint8_t stepper_id, float angle)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN];
- _mav_put_float(buf, 0, angle);
- _mav_put_uint8_t(buf, 4, stepper_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC, buf, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_CRC);
-#else
- mavlink_set_stepper_angle_tc_t packet;
- packet.angle = angle;
- packet.stepper_id = stepper_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_stepper_angle_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_stepper_angle_tc_send_struct(mavlink_channel_t chan, const mavlink_set_stepper_angle_tc_t* set_stepper_angle_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_stepper_angle_tc_send(chan, set_stepper_angle_tc->stepper_id, set_stepper_angle_tc->angle);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC, (const char *)set_stepper_angle_tc, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_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_stepper_angle_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t stepper_id, float angle)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, angle);
- _mav_put_uint8_t(buf, 4, stepper_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC, buf, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_CRC);
-#else
- mavlink_set_stepper_angle_tc_t *packet = (mavlink_set_stepper_angle_tc_t *)msgbuf;
- packet->angle = angle;
- packet->stepper_id = stepper_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC, (const char *)packet, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_STEPPER_ANGLE_TC UNPACKING
-
-
-/**
- * @brief Get field stepper_id from set_stepper_angle_tc message
- *
- * @return A member of the StepperList enum
- */
-static inline uint8_t mavlink_msg_set_stepper_angle_tc_get_stepper_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 4);
-}
-
-/**
- * @brief Get field angle from set_stepper_angle_tc message
- *
- * @return Stepper angle in degrees
- */
-static inline float mavlink_msg_set_stepper_angle_tc_get_angle(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a set_stepper_angle_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_stepper_angle_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_stepper_angle_tc_decode(const mavlink_message_t* msg, mavlink_set_stepper_angle_tc_t* set_stepper_angle_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_stepper_angle_tc->angle = mavlink_msg_set_stepper_angle_tc_get_angle(msg);
- set_stepper_angle_tc->stepper_id = mavlink_msg_set_stepper_angle_tc_get_stepper_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN;
- memset(set_stepper_angle_tc, 0, MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_LEN);
- memcpy(set_stepper_angle_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_set_stepper_steps_tc.h b/mavlink_lib/lyra/mavlink_msg_set_stepper_steps_tc.h
deleted file mode 100644
index 5381c0fea9043603df6814431bbe96e1276221da..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_set_stepper_steps_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SET_STEPPER_STEPS_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC 22
-
-
-typedef struct __mavlink_set_stepper_steps_tc_t {
- float steps; /*< Number of steps*/
- uint8_t stepper_id; /*< A member of the StepperList enum*/
-} mavlink_set_stepper_steps_tc_t;
-
-#define MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN 5
-#define MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_MIN_LEN 5
-#define MAVLINK_MSG_ID_22_LEN 5
-#define MAVLINK_MSG_ID_22_MIN_LEN 5
-
-#define MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_CRC 246
-#define MAVLINK_MSG_ID_22_CRC 246
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_STEPPER_STEPS_TC { \
- 22, \
- "SET_STEPPER_STEPS_TC", \
- 2, \
- { { "stepper_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_stepper_steps_tc_t, stepper_id) }, \
- { "steps", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_stepper_steps_tc_t, steps) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_STEPPER_STEPS_TC { \
- "SET_STEPPER_STEPS_TC", \
- 2, \
- { { "stepper_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_stepper_steps_tc_t, stepper_id) }, \
- { "steps", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_stepper_steps_tc_t, steps) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_stepper_steps_tc 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 stepper_id A member of the StepperList enum
- * @param steps Number of steps
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_stepper_steps_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t stepper_id, float steps)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN];
- _mav_put_float(buf, 0, steps);
- _mav_put_uint8_t(buf, 4, stepper_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN);
-#else
- mavlink_set_stepper_steps_tc_t packet;
- packet.steps = steps;
- packet.stepper_id = stepper_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_CRC);
-}
-
-/**
- * @brief Pack a set_stepper_steps_tc 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 stepper_id A member of the StepperList enum
- * @param steps Number of steps
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_stepper_steps_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t stepper_id,float steps)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN];
- _mav_put_float(buf, 0, steps);
- _mav_put_uint8_t(buf, 4, stepper_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN);
-#else
- mavlink_set_stepper_steps_tc_t packet;
- packet.steps = steps;
- packet.stepper_id = stepper_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_CRC);
-}
-
-/**
- * @brief Encode a set_stepper_steps_tc 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_stepper_steps_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_stepper_steps_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_stepper_steps_tc_t* set_stepper_steps_tc)
-{
- return mavlink_msg_set_stepper_steps_tc_pack(system_id, component_id, msg, set_stepper_steps_tc->stepper_id, set_stepper_steps_tc->steps);
-}
-
-/**
- * @brief Encode a set_stepper_steps_tc 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_stepper_steps_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_stepper_steps_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_stepper_steps_tc_t* set_stepper_steps_tc)
-{
- return mavlink_msg_set_stepper_steps_tc_pack_chan(system_id, component_id, chan, msg, set_stepper_steps_tc->stepper_id, set_stepper_steps_tc->steps);
-}
-
-/**
- * @brief Send a set_stepper_steps_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param stepper_id A member of the StepperList enum
- * @param steps Number of steps
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_stepper_steps_tc_send(mavlink_channel_t chan, uint8_t stepper_id, float steps)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN];
- _mav_put_float(buf, 0, steps);
- _mav_put_uint8_t(buf, 4, stepper_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC, buf, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_CRC);
-#else
- mavlink_set_stepper_steps_tc_t packet;
- packet.steps = steps;
- packet.stepper_id = stepper_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_stepper_steps_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_stepper_steps_tc_send_struct(mavlink_channel_t chan, const mavlink_set_stepper_steps_tc_t* set_stepper_steps_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_stepper_steps_tc_send(chan, set_stepper_steps_tc->stepper_id, set_stepper_steps_tc->steps);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC, (const char *)set_stepper_steps_tc, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_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_stepper_steps_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t stepper_id, float steps)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, steps);
- _mav_put_uint8_t(buf, 4, stepper_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC, buf, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_CRC);
-#else
- mavlink_set_stepper_steps_tc_t *packet = (mavlink_set_stepper_steps_tc_t *)msgbuf;
- packet->steps = steps;
- packet->stepper_id = stepper_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC, (const char *)packet, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_MIN_LEN, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_STEPPER_STEPS_TC UNPACKING
-
-
-/**
- * @brief Get field stepper_id from set_stepper_steps_tc message
- *
- * @return A member of the StepperList enum
- */
-static inline uint8_t mavlink_msg_set_stepper_steps_tc_get_stepper_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 4);
-}
-
-/**
- * @brief Get field steps from set_stepper_steps_tc message
- *
- * @return Number of steps
- */
-static inline float mavlink_msg_set_stepper_steps_tc_get_steps(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a set_stepper_steps_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_stepper_steps_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_stepper_steps_tc_decode(const mavlink_message_t* msg, mavlink_set_stepper_steps_tc_t* set_stepper_steps_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_stepper_steps_tc->steps = mavlink_msg_set_stepper_steps_tc_get_steps(msg);
- set_stepper_steps_tc->stepper_id = mavlink_msg_set_stepper_steps_tc_get_stepper_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN;
- memset(set_stepper_steps_tc, 0, MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_LEN);
- memcpy(set_stepper_steps_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_set_target_coordinates_tc.h b/mavlink_lib/lyra/mavlink_msg_set_target_coordinates_tc.h
deleted file mode 100644
index 40394b728f76ebb99dfb689a467c28474a457fee..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_set_target_coordinates_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SET_TARGET_COORDINATES_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC 15
-
-
-typedef struct __mavlink_set_target_coordinates_tc_t {
- float latitude; /*< [deg] Latitude*/
- float longitude; /*< [deg] Longitude*/
-} mavlink_set_target_coordinates_tc_t;
-
-#define MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN 8
-#define MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_15_LEN 8
-#define MAVLINK_MSG_ID_15_MIN_LEN 8
-
-#define MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC 81
-#define MAVLINK_MSG_ID_15_CRC 81
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC { \
- 15, \
- "SET_TARGET_COORDINATES_TC", \
- 2, \
- { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_target_coordinates_tc_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_target_coordinates_tc_t, longitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC { \
- "SET_TARGET_COORDINATES_TC", \
- 2, \
- { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_target_coordinates_tc_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_target_coordinates_tc_t, longitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_target_coordinates_tc 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 [deg] Latitude
- * @param longitude [deg] Longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_target_coordinates_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN);
-#else
- mavlink_set_target_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-}
-
-/**
- * @brief Pack a set_target_coordinates_tc 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 [deg] Latitude
- * @param longitude [deg] Longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_target_coordinates_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float latitude,float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN);
-#else
- mavlink_set_target_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-}
-
-/**
- * @brief Encode a set_target_coordinates_tc 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_target_coordinates_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_target_coordinates_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_target_coordinates_tc_t* set_target_coordinates_tc)
-{
- return mavlink_msg_set_target_coordinates_tc_pack(system_id, component_id, msg, set_target_coordinates_tc->latitude, set_target_coordinates_tc->longitude);
-}
-
-/**
- * @brief Encode a set_target_coordinates_tc 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_target_coordinates_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_target_coordinates_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_target_coordinates_tc_t* set_target_coordinates_tc)
-{
- return mavlink_msg_set_target_coordinates_tc_pack_chan(system_id, component_id, chan, msg, set_target_coordinates_tc->latitude, set_target_coordinates_tc->longitude);
-}
-
-/**
- * @brief Send a set_target_coordinates_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param latitude [deg] Latitude
- * @param longitude [deg] Longitude
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_target_coordinates_tc_send(mavlink_channel_t chan, float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC, buf, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-#else
- mavlink_set_target_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_target_coordinates_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_target_coordinates_tc_send_struct(mavlink_channel_t chan, const mavlink_set_target_coordinates_tc_t* set_target_coordinates_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_target_coordinates_tc_send(chan, set_target_coordinates_tc->latitude, set_target_coordinates_tc->longitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC, (const char *)set_target_coordinates_tc, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_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_target_coordinates_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC, buf, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-#else
- mavlink_set_target_coordinates_tc_t *packet = (mavlink_set_target_coordinates_tc_t *)msgbuf;
- packet->latitude = latitude;
- packet->longitude = longitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC, (const char *)packet, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_TARGET_COORDINATES_TC UNPACKING
-
-
-/**
- * @brief Get field latitude from set_target_coordinates_tc message
- *
- * @return [deg] Latitude
- */
-static inline float mavlink_msg_set_target_coordinates_tc_get_latitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Get field longitude from set_target_coordinates_tc message
- *
- * @return [deg] Longitude
- */
-static inline float mavlink_msg_set_target_coordinates_tc_get_longitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 4);
-}
-
-/**
- * @brief Decode a set_target_coordinates_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_target_coordinates_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_target_coordinates_tc_decode(const mavlink_message_t* msg, mavlink_set_target_coordinates_tc_t* set_target_coordinates_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_target_coordinates_tc->latitude = mavlink_msg_set_target_coordinates_tc_get_latitude(msg);
- set_target_coordinates_tc->longitude = mavlink_msg_set_target_coordinates_tc_get_longitude(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN;
- memset(set_target_coordinates_tc, 0, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN);
- memcpy(set_target_coordinates_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_set_valve_maximum_aperture_tc.h b/mavlink_lib/lyra/mavlink_msg_set_valve_maximum_aperture_tc.h
deleted file mode 100644
index 6c13b3e2c6ec3002dd7dbef75785ae68f89ab5aa..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_set_valve_maximum_aperture_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SET_VALVE_MAXIMUM_APERTURE_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC 18
-
-
-typedef struct __mavlink_set_valve_maximum_aperture_tc_t {
- float maximum_aperture; /*< Maximum aperture*/
- uint8_t servo_id; /*< A member of the ServosList enum*/
-} mavlink_set_valve_maximum_aperture_tc_t;
-
-#define MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN 5
-#define MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN 5
-#define MAVLINK_MSG_ID_18_LEN 5
-#define MAVLINK_MSG_ID_18_MIN_LEN 5
-
-#define MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_CRC 22
-#define MAVLINK_MSG_ID_18_CRC 22
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_VALVE_MAXIMUM_APERTURE_TC { \
- 18, \
- "SET_VALVE_MAXIMUM_APERTURE_TC", \
- 2, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_valve_maximum_aperture_tc_t, servo_id) }, \
- { "maximum_aperture", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_valve_maximum_aperture_tc_t, maximum_aperture) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_VALVE_MAXIMUM_APERTURE_TC { \
- "SET_VALVE_MAXIMUM_APERTURE_TC", \
- 2, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_valve_maximum_aperture_tc_t, servo_id) }, \
- { "maximum_aperture", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_valve_maximum_aperture_tc_t, maximum_aperture) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_valve_maximum_aperture_tc 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 servo_id A member of the ServosList enum
- * @param maximum_aperture Maximum aperture
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_valve_maximum_aperture_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t servo_id, float maximum_aperture)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN];
- _mav_put_float(buf, 0, maximum_aperture);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN);
-#else
- mavlink_set_valve_maximum_aperture_tc_t packet;
- packet.maximum_aperture = maximum_aperture;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_CRC);
-}
-
-/**
- * @brief Pack a set_valve_maximum_aperture_tc 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 servo_id A member of the ServosList enum
- * @param maximum_aperture Maximum aperture
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_valve_maximum_aperture_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t servo_id,float maximum_aperture)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN];
- _mav_put_float(buf, 0, maximum_aperture);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN);
-#else
- mavlink_set_valve_maximum_aperture_tc_t packet;
- packet.maximum_aperture = maximum_aperture;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_CRC);
-}
-
-/**
- * @brief Encode a set_valve_maximum_aperture_tc 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_valve_maximum_aperture_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_valve_maximum_aperture_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_valve_maximum_aperture_tc_t* set_valve_maximum_aperture_tc)
-{
- return mavlink_msg_set_valve_maximum_aperture_tc_pack(system_id, component_id, msg, set_valve_maximum_aperture_tc->servo_id, set_valve_maximum_aperture_tc->maximum_aperture);
-}
-
-/**
- * @brief Encode a set_valve_maximum_aperture_tc 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_valve_maximum_aperture_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_valve_maximum_aperture_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_valve_maximum_aperture_tc_t* set_valve_maximum_aperture_tc)
-{
- return mavlink_msg_set_valve_maximum_aperture_tc_pack_chan(system_id, component_id, chan, msg, set_valve_maximum_aperture_tc->servo_id, set_valve_maximum_aperture_tc->maximum_aperture);
-}
-
-/**
- * @brief Send a set_valve_maximum_aperture_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param servo_id A member of the ServosList enum
- * @param maximum_aperture Maximum aperture
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_valve_maximum_aperture_tc_send(mavlink_channel_t chan, uint8_t servo_id, float maximum_aperture)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN];
- _mav_put_float(buf, 0, maximum_aperture);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC, buf, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_CRC);
-#else
- mavlink_set_valve_maximum_aperture_tc_t packet;
- packet.maximum_aperture = maximum_aperture;
- packet.servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_valve_maximum_aperture_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_valve_maximum_aperture_tc_send_struct(mavlink_channel_t chan, const mavlink_set_valve_maximum_aperture_tc_t* set_valve_maximum_aperture_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_valve_maximum_aperture_tc_send(chan, set_valve_maximum_aperture_tc->servo_id, set_valve_maximum_aperture_tc->maximum_aperture);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC, (const char *)set_valve_maximum_aperture_tc, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_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_valve_maximum_aperture_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t servo_id, float maximum_aperture)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, maximum_aperture);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC, buf, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_CRC);
-#else
- mavlink_set_valve_maximum_aperture_tc_t *packet = (mavlink_set_valve_maximum_aperture_tc_t *)msgbuf;
- packet->maximum_aperture = maximum_aperture;
- packet->servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC, (const char *)packet, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_VALVE_MAXIMUM_APERTURE_TC UNPACKING
-
-
-/**
- * @brief Get field servo_id from set_valve_maximum_aperture_tc message
- *
- * @return A member of the ServosList enum
- */
-static inline uint8_t mavlink_msg_set_valve_maximum_aperture_tc_get_servo_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 4);
-}
-
-/**
- * @brief Get field maximum_aperture from set_valve_maximum_aperture_tc message
- *
- * @return Maximum aperture
- */
-static inline float mavlink_msg_set_valve_maximum_aperture_tc_get_maximum_aperture(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a set_valve_maximum_aperture_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_valve_maximum_aperture_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_valve_maximum_aperture_tc_decode(const mavlink_message_t* msg, mavlink_set_valve_maximum_aperture_tc_t* set_valve_maximum_aperture_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_valve_maximum_aperture_tc->maximum_aperture = mavlink_msg_set_valve_maximum_aperture_tc_get_maximum_aperture(msg);
- set_valve_maximum_aperture_tc->servo_id = mavlink_msg_set_valve_maximum_aperture_tc_get_servo_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN;
- memset(set_valve_maximum_aperture_tc, 0, MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_LEN);
- memcpy(set_valve_maximum_aperture_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_sys_tm.h b/mavlink_lib/lyra/mavlink_msg_sys_tm.h
deleted file mode 100644
index 460e076f05dcf8b83836d80a887f0c77b074c517..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_sys_tm.h
+++ /dev/null
@@ -1,363 +0,0 @@
-#pragma once
-// MESSAGE SYS_TM PACKING
-
-#define MAVLINK_MSG_ID_SYS_TM 200
-
-
-typedef struct __mavlink_sys_tm_t {
- uint64_t timestamp; /*< [us] Timestamp*/
- uint8_t logger; /*< True if the logger started correctly*/
- uint8_t event_broker; /*< True if the event broker started correctly*/
- uint8_t radio; /*< True if the radio started correctly*/
- uint8_t pin_observer; /*< True if the pin observer started correctly*/
- uint8_t sensors; /*< True if the sensors started correctly*/
- uint8_t board_scheduler; /*< True if the board scheduler is running*/
-} mavlink_sys_tm_t;
-
-#define MAVLINK_MSG_ID_SYS_TM_LEN 14
-#define MAVLINK_MSG_ID_SYS_TM_MIN_LEN 14
-#define MAVLINK_MSG_ID_200_LEN 14
-#define MAVLINK_MSG_ID_200_MIN_LEN 14
-
-#define MAVLINK_MSG_ID_SYS_TM_CRC 183
-#define MAVLINK_MSG_ID_200_CRC 183
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SYS_TM { \
- 200, \
- "SYS_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_sys_tm_t, timestamp) }, \
- { "logger", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_sys_tm_t, logger) }, \
- { "event_broker", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_sys_tm_t, event_broker) }, \
- { "radio", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_sys_tm_t, radio) }, \
- { "pin_observer", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_sys_tm_t, pin_observer) }, \
- { "sensors", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_sys_tm_t, sensors) }, \
- { "board_scheduler", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_sys_tm_t, board_scheduler) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SYS_TM { \
- "SYS_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_sys_tm_t, timestamp) }, \
- { "logger", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_sys_tm_t, logger) }, \
- { "event_broker", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_sys_tm_t, event_broker) }, \
- { "radio", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_sys_tm_t, radio) }, \
- { "pin_observer", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_sys_tm_t, pin_observer) }, \
- { "sensors", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_sys_tm_t, sensors) }, \
- { "board_scheduler", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_sys_tm_t, board_scheduler) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a sys_tm 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
- * @param logger True if the logger started correctly
- * @param event_broker True if the event broker started correctly
- * @param radio True if the radio started correctly
- * @param pin_observer True if the pin observer started correctly
- * @param sensors True if the sensors started correctly
- * @param board_scheduler True if the board scheduler is running
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sys_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t logger, uint8_t event_broker, uint8_t radio, uint8_t pin_observer, uint8_t sensors, uint8_t board_scheduler)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, logger);
- _mav_put_uint8_t(buf, 9, event_broker);
- _mav_put_uint8_t(buf, 10, radio);
- _mav_put_uint8_t(buf, 11, pin_observer);
- _mav_put_uint8_t(buf, 12, sensors);
- _mav_put_uint8_t(buf, 13, board_scheduler);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_TM_LEN);
-#else
- mavlink_sys_tm_t packet;
- packet.timestamp = timestamp;
- packet.logger = logger;
- packet.event_broker = event_broker;
- packet.radio = radio;
- packet.pin_observer = pin_observer;
- packet.sensors = sensors;
- packet.board_scheduler = board_scheduler;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SYS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-}
-
-/**
- * @brief Pack a sys_tm 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
- * @param logger True if the logger started correctly
- * @param event_broker True if the event broker started correctly
- * @param radio True if the radio started correctly
- * @param pin_observer True if the pin observer started correctly
- * @param sensors True if the sensors started correctly
- * @param board_scheduler True if the board scheduler is running
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sys_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t logger,uint8_t event_broker,uint8_t radio,uint8_t pin_observer,uint8_t sensors,uint8_t board_scheduler)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, logger);
- _mav_put_uint8_t(buf, 9, event_broker);
- _mav_put_uint8_t(buf, 10, radio);
- _mav_put_uint8_t(buf, 11, pin_observer);
- _mav_put_uint8_t(buf, 12, sensors);
- _mav_put_uint8_t(buf, 13, board_scheduler);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_TM_LEN);
-#else
- mavlink_sys_tm_t packet;
- packet.timestamp = timestamp;
- packet.logger = logger;
- packet.event_broker = event_broker;
- packet.radio = radio;
- packet.pin_observer = pin_observer;
- packet.sensors = sensors;
- packet.board_scheduler = board_scheduler;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SYS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-}
-
-/**
- * @brief Encode a sys_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sys_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_tm_t* sys_tm)
-{
- return mavlink_msg_sys_tm_pack(system_id, component_id, msg, sys_tm->timestamp, sys_tm->logger, sys_tm->event_broker, sys_tm->radio, sys_tm->pin_observer, sys_tm->sensors, sys_tm->board_scheduler);
-}
-
-/**
- * @brief Encode a sys_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sys_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sys_tm_t* sys_tm)
-{
- return mavlink_msg_sys_tm_pack_chan(system_id, component_id, chan, msg, sys_tm->timestamp, sys_tm->logger, sys_tm->event_broker, sys_tm->radio, sys_tm->pin_observer, sys_tm->sensors, sys_tm->board_scheduler);
-}
-
-/**
- * @brief Send a sys_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp
- * @param logger True if the logger started correctly
- * @param event_broker True if the event broker started correctly
- * @param radio True if the radio started correctly
- * @param pin_observer True if the pin observer started correctly
- * @param sensors True if the sensors started correctly
- * @param board_scheduler True if the board scheduler is running
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_sys_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t logger, uint8_t event_broker, uint8_t radio, uint8_t pin_observer, uint8_t sensors, uint8_t board_scheduler)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, logger);
- _mav_put_uint8_t(buf, 9, event_broker);
- _mav_put_uint8_t(buf, 10, radio);
- _mav_put_uint8_t(buf, 11, pin_observer);
- _mav_put_uint8_t(buf, 12, sensors);
- _mav_put_uint8_t(buf, 13, board_scheduler);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, buf, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#else
- mavlink_sys_tm_t packet;
- packet.timestamp = timestamp;
- packet.logger = logger;
- packet.event_broker = event_broker;
- packet.radio = radio;
- packet.pin_observer = pin_observer;
- packet.sensors = sensors;
- packet.board_scheduler = board_scheduler;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, (const char *)&packet, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a sys_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_sys_tm_send_struct(mavlink_channel_t chan, const mavlink_sys_tm_t* sys_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_sys_tm_send(chan, sys_tm->timestamp, sys_tm->logger, sys_tm->event_broker, sys_tm->radio, sys_tm->pin_observer, sys_tm->sensors, sys_tm->board_scheduler);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, (const char *)sys_tm, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SYS_TM_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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t logger, uint8_t event_broker, uint8_t radio, uint8_t pin_observer, uint8_t sensors, uint8_t board_scheduler)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, logger);
- _mav_put_uint8_t(buf, 9, event_broker);
- _mav_put_uint8_t(buf, 10, radio);
- _mav_put_uint8_t(buf, 11, pin_observer);
- _mav_put_uint8_t(buf, 12, sensors);
- _mav_put_uint8_t(buf, 13, board_scheduler);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, buf, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#else
- mavlink_sys_tm_t *packet = (mavlink_sys_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->logger = logger;
- packet->event_broker = event_broker;
- packet->radio = radio;
- packet->pin_observer = pin_observer;
- packet->sensors = sensors;
- packet->board_scheduler = board_scheduler;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, (const char *)packet, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SYS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from sys_tm message
- *
- * @return [us] Timestamp
- */
-static inline uint64_t mavlink_msg_sys_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field logger from sys_tm message
- *
- * @return True if the logger started correctly
- */
-static inline uint8_t mavlink_msg_sys_tm_get_logger(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 8);
-}
-
-/**
- * @brief Get field event_broker from sys_tm message
- *
- * @return True if the event broker started correctly
- */
-static inline uint8_t mavlink_msg_sys_tm_get_event_broker(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 9);
-}
-
-/**
- * @brief Get field radio from sys_tm message
- *
- * @return True if the radio started correctly
- */
-static inline uint8_t mavlink_msg_sys_tm_get_radio(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 10);
-}
-
-/**
- * @brief Get field pin_observer from sys_tm message
- *
- * @return True if the pin observer started correctly
- */
-static inline uint8_t mavlink_msg_sys_tm_get_pin_observer(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 11);
-}
-
-/**
- * @brief Get field sensors from sys_tm message
- *
- * @return True if the sensors started correctly
- */
-static inline uint8_t mavlink_msg_sys_tm_get_sensors(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 12);
-}
-
-/**
- * @brief Get field board_scheduler from sys_tm message
- *
- * @return True if the board scheduler is running
- */
-static inline uint8_t mavlink_msg_sys_tm_get_board_scheduler(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 13);
-}
-
-/**
- * @brief Decode a sys_tm message into a struct
- *
- * @param msg The message to decode
- * @param sys_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_sys_tm_decode(const mavlink_message_t* msg, mavlink_sys_tm_t* sys_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- sys_tm->timestamp = mavlink_msg_sys_tm_get_timestamp(msg);
- sys_tm->logger = mavlink_msg_sys_tm_get_logger(msg);
- sys_tm->event_broker = mavlink_msg_sys_tm_get_event_broker(msg);
- sys_tm->radio = mavlink_msg_sys_tm_get_radio(msg);
- sys_tm->pin_observer = mavlink_msg_sys_tm_get_pin_observer(msg);
- sys_tm->sensors = mavlink_msg_sys_tm_get_sensors(msg);
- sys_tm->board_scheduler = mavlink_msg_sys_tm_get_board_scheduler(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SYS_TM_LEN? msg->len : MAVLINK_MSG_ID_SYS_TM_LEN;
- memset(sys_tm, 0, MAVLINK_MSG_ID_SYS_TM_LEN);
- memcpy(sys_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_system_tm_request_tc.h b/mavlink_lib/lyra/mavlink_msg_system_tm_request_tc.h
deleted file mode 100644
index de5a083eed2404c27df5ad34524fcac401fe3b6f..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_system_tm_request_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SYSTEM_TM_REQUEST_TC PACKING
-
-#define MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC 3
-
-
-typedef struct __mavlink_system_tm_request_tc_t {
- uint8_t tm_id; /*< A member of the SystemTMList enum*/
-} mavlink_system_tm_request_tc_t;
-
-#define MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN 1
-#define MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_3_LEN 1
-#define MAVLINK_MSG_ID_3_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC 165
-#define MAVLINK_MSG_ID_3_CRC 165
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC { \
- 3, \
- "SYSTEM_TM_REQUEST_TC", \
- 1, \
- { { "tm_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_system_tm_request_tc_t, tm_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC { \
- "SYSTEM_TM_REQUEST_TC", \
- 1, \
- { { "tm_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_system_tm_request_tc_t, tm_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a system_tm_request_tc 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 tm_id A member of the SystemTMList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_system_tm_request_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t tm_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, tm_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN);
-#else
- mavlink_system_tm_request_tc_t packet;
- packet.tm_id = tm_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Pack a system_tm_request_tc 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 tm_id A member of the SystemTMList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_system_tm_request_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t tm_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, tm_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN);
-#else
- mavlink_system_tm_request_tc_t packet;
- packet.tm_id = tm_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Encode a system_tm_request_tc 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_tm_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_system_tm_request_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_tm_request_tc_t* system_tm_request_tc)
-{
- return mavlink_msg_system_tm_request_tc_pack(system_id, component_id, msg, system_tm_request_tc->tm_id);
-}
-
-/**
- * @brief Encode a system_tm_request_tc 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_tm_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_system_tm_request_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_system_tm_request_tc_t* system_tm_request_tc)
-{
- return mavlink_msg_system_tm_request_tc_pack_chan(system_id, component_id, chan, msg, system_tm_request_tc->tm_id);
-}
-
-/**
- * @brief Send a system_tm_request_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param tm_id A member of the SystemTMList enum
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_system_tm_request_tc_send(mavlink_channel_t chan, uint8_t tm_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, tm_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC, buf, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-#else
- mavlink_system_tm_request_tc_t packet;
- packet.tm_id = tm_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC, (const char *)&packet, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a system_tm_request_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_system_tm_request_tc_send_struct(mavlink_channel_t chan, const mavlink_system_tm_request_tc_t* system_tm_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_system_tm_request_tc_send(chan, system_tm_request_tc->tm_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC, (const char *)system_tm_request_tc, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_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_tm_request_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t tm_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, tm_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC, buf, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-#else
- mavlink_system_tm_request_tc_t *packet = (mavlink_system_tm_request_tc_t *)msgbuf;
- packet->tm_id = tm_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC, (const char *)packet, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SYSTEM_TM_REQUEST_TC UNPACKING
-
-
-/**
- * @brief Get field tm_id from system_tm_request_tc message
- *
- * @return A member of the SystemTMList enum
- */
-static inline uint8_t mavlink_msg_system_tm_request_tc_get_tm_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a system_tm_request_tc message into a struct
- *
- * @param msg The message to decode
- * @param system_tm_request_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_system_tm_request_tc_decode(const mavlink_message_t* msg, mavlink_system_tm_request_tc_t* system_tm_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- system_tm_request_tc->tm_id = mavlink_msg_system_tm_request_tc_get_tm_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN? msg->len : MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN;
- memset(system_tm_request_tc, 0, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN);
- memcpy(system_tm_request_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_task_stats_tm.h b/mavlink_lib/lyra/mavlink_msg_task_stats_tm.h
deleted file mode 100644
index 81727059a4f8f5ed68fc83870afb0b99ab064bba..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_task_stats_tm.h
+++ /dev/null
@@ -1,363 +0,0 @@
-#pragma once
-// MESSAGE TASK_STATS_TM PACKING
-
-#define MAVLINK_MSG_ID_TASK_STATS_TM 204
-
-
-typedef struct __mavlink_task_stats_tm_t {
- uint64_t timestamp; /*< [us] When was this logged */
- float task_min; /*< Task min period*/
- float task_max; /*< Task max period*/
- float task_mean; /*< Task mean period*/
- float task_stddev; /*< Task period std deviation*/
- uint16_t task_period; /*< [ms] Period of the task*/
- uint8_t task_id; /*< Task ID*/
-} mavlink_task_stats_tm_t;
-
-#define MAVLINK_MSG_ID_TASK_STATS_TM_LEN 27
-#define MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN 27
-#define MAVLINK_MSG_ID_204_LEN 27
-#define MAVLINK_MSG_ID_204_MIN_LEN 27
-
-#define MAVLINK_MSG_ID_TASK_STATS_TM_CRC 133
-#define MAVLINK_MSG_ID_204_CRC 133
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_TASK_STATS_TM { \
- 204, \
- "TASK_STATS_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_task_stats_tm_t, timestamp) }, \
- { "task_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_task_stats_tm_t, task_id) }, \
- { "task_period", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_task_stats_tm_t, task_period) }, \
- { "task_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_task_stats_tm_t, task_min) }, \
- { "task_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_task_stats_tm_t, task_max) }, \
- { "task_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_task_stats_tm_t, task_mean) }, \
- { "task_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_task_stats_tm_t, task_stddev) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_TASK_STATS_TM { \
- "TASK_STATS_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_task_stats_tm_t, timestamp) }, \
- { "task_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_task_stats_tm_t, task_id) }, \
- { "task_period", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_task_stats_tm_t, task_period) }, \
- { "task_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_task_stats_tm_t, task_min) }, \
- { "task_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_task_stats_tm_t, task_max) }, \
- { "task_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_task_stats_tm_t, task_mean) }, \
- { "task_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_task_stats_tm_t, task_stddev) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a task_stats_tm 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] When was this logged
- * @param task_id Task ID
- * @param task_period [ms] Period of the task
- * @param task_min Task min period
- * @param task_max Task max period
- * @param task_mean Task mean period
- * @param task_stddev Task period std deviation
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_task_stats_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t task_id, uint16_t task_period, float task_min, float task_max, float task_mean, float task_stddev)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TASK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, task_min);
- _mav_put_float(buf, 12, task_max);
- _mav_put_float(buf, 16, task_mean);
- _mav_put_float(buf, 20, task_stddev);
- _mav_put_uint16_t(buf, 24, task_period);
- _mav_put_uint8_t(buf, 26, task_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
-#else
- mavlink_task_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.task_min = task_min;
- packet.task_max = task_max;
- packet.task_mean = task_mean;
- packet.task_stddev = task_stddev;
- packet.task_period = task_period;
- packet.task_id = task_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TASK_STATS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-}
-
-/**
- * @brief Pack a task_stats_tm 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] When was this logged
- * @param task_id Task ID
- * @param task_period [ms] Period of the task
- * @param task_min Task min period
- * @param task_max Task max period
- * @param task_mean Task mean period
- * @param task_stddev Task period std deviation
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_task_stats_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t task_id,uint16_t task_period,float task_min,float task_max,float task_mean,float task_stddev)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TASK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, task_min);
- _mav_put_float(buf, 12, task_max);
- _mav_put_float(buf, 16, task_mean);
- _mav_put_float(buf, 20, task_stddev);
- _mav_put_uint16_t(buf, 24, task_period);
- _mav_put_uint8_t(buf, 26, task_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
-#else
- mavlink_task_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.task_min = task_min;
- packet.task_max = task_max;
- packet.task_mean = task_mean;
- packet.task_stddev = task_stddev;
- packet.task_period = task_period;
- packet.task_id = task_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TASK_STATS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-}
-
-/**
- * @brief Encode a task_stats_tm 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 task_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_task_stats_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_task_stats_tm_t* task_stats_tm)
-{
- return mavlink_msg_task_stats_tm_pack(system_id, component_id, msg, task_stats_tm->timestamp, task_stats_tm->task_id, task_stats_tm->task_period, task_stats_tm->task_min, task_stats_tm->task_max, task_stats_tm->task_mean, task_stats_tm->task_stddev);
-}
-
-/**
- * @brief Encode a task_stats_tm 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 task_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_task_stats_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_task_stats_tm_t* task_stats_tm)
-{
- return mavlink_msg_task_stats_tm_pack_chan(system_id, component_id, chan, msg, task_stats_tm->timestamp, task_stats_tm->task_id, task_stats_tm->task_period, task_stats_tm->task_min, task_stats_tm->task_max, task_stats_tm->task_mean, task_stats_tm->task_stddev);
-}
-
-/**
- * @brief Send a task_stats_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param task_id Task ID
- * @param task_period [ms] Period of the task
- * @param task_min Task min period
- * @param task_max Task max period
- * @param task_mean Task mean period
- * @param task_stddev Task period std deviation
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_task_stats_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t task_id, uint16_t task_period, float task_min, float task_max, float task_mean, float task_stddev)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TASK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, task_min);
- _mav_put_float(buf, 12, task_max);
- _mav_put_float(buf, 16, task_mean);
- _mav_put_float(buf, 20, task_stddev);
- _mav_put_uint16_t(buf, 24, task_period);
- _mav_put_uint8_t(buf, 26, task_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, buf, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-#else
- mavlink_task_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.task_min = task_min;
- packet.task_max = task_max;
- packet.task_mean = task_mean;
- packet.task_stddev = task_stddev;
- packet.task_period = task_period;
- packet.task_id = task_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, (const char *)&packet, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a task_stats_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_task_stats_tm_send_struct(mavlink_channel_t chan, const mavlink_task_stats_tm_t* task_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_task_stats_tm_send(chan, task_stats_tm->timestamp, task_stats_tm->task_id, task_stats_tm->task_period, task_stats_tm->task_min, task_stats_tm->task_max, task_stats_tm->task_mean, task_stats_tm->task_stddev);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, (const char *)task_stats_tm, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_TASK_STATS_TM_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_task_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t task_id, uint16_t task_period, float task_min, float task_max, float task_mean, float task_stddev)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, task_min);
- _mav_put_float(buf, 12, task_max);
- _mav_put_float(buf, 16, task_mean);
- _mav_put_float(buf, 20, task_stddev);
- _mav_put_uint16_t(buf, 24, task_period);
- _mav_put_uint8_t(buf, 26, task_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, buf, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-#else
- mavlink_task_stats_tm_t *packet = (mavlink_task_stats_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->task_min = task_min;
- packet->task_max = task_max;
- packet->task_mean = task_mean;
- packet->task_stddev = task_stddev;
- packet->task_period = task_period;
- packet->task_id = task_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, (const char *)packet, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE TASK_STATS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from task_stats_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_task_stats_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field task_id from task_stats_tm message
- *
- * @return Task ID
- */
-static inline uint8_t mavlink_msg_task_stats_tm_get_task_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 26);
-}
-
-/**
- * @brief Get field task_period from task_stats_tm message
- *
- * @return [ms] Period of the task
- */
-static inline uint16_t mavlink_msg_task_stats_tm_get_task_period(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 24);
-}
-
-/**
- * @brief Get field task_min from task_stats_tm message
- *
- * @return Task min period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_min(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field task_max from task_stats_tm message
- *
- * @return Task max period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_max(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field task_mean from task_stats_tm message
- *
- * @return Task mean period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_mean(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field task_stddev from task_stats_tm message
- *
- * @return Task period std deviation
- */
-static inline float mavlink_msg_task_stats_tm_get_task_stddev(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Decode a task_stats_tm message into a struct
- *
- * @param msg The message to decode
- * @param task_stats_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_task_stats_tm_decode(const mavlink_message_t* msg, mavlink_task_stats_tm_t* task_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- task_stats_tm->timestamp = mavlink_msg_task_stats_tm_get_timestamp(msg);
- task_stats_tm->task_min = mavlink_msg_task_stats_tm_get_task_min(msg);
- task_stats_tm->task_max = mavlink_msg_task_stats_tm_get_task_max(msg);
- task_stats_tm->task_mean = mavlink_msg_task_stats_tm_get_task_mean(msg);
- task_stats_tm->task_stddev = mavlink_msg_task_stats_tm_get_task_stddev(msg);
- task_stats_tm->task_period = mavlink_msg_task_stats_tm_get_task_period(msg);
- task_stats_tm->task_id = mavlink_msg_task_stats_tm_get_task_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_TASK_STATS_TM_LEN? msg->len : MAVLINK_MSG_ID_TASK_STATS_TM_LEN;
- memset(task_stats_tm, 0, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
- memcpy(task_stats_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_temp_tm.h b/mavlink_lib/lyra/mavlink_msg_temp_tm.h
deleted file mode 100644
index 1334d436975a961e918b50ed4b8d04f058faab3f..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_temp_tm.h
+++ /dev/null
@@ -1,255 +0,0 @@
-#pragma once
-// MESSAGE TEMP_TM PACKING
-
-#define MAVLINK_MSG_ID_TEMP_TM 108
-
-
-typedef struct __mavlink_temp_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float temperature; /*< [deg] Temperature*/
- char sensor_name[20]; /*< Sensor name*/
-} mavlink_temp_tm_t;
-
-#define MAVLINK_MSG_ID_TEMP_TM_LEN 32
-#define MAVLINK_MSG_ID_TEMP_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_108_LEN 32
-#define MAVLINK_MSG_ID_108_MIN_LEN 32
-
-#define MAVLINK_MSG_ID_TEMP_TM_CRC 140
-#define MAVLINK_MSG_ID_108_CRC 140
-
-#define MAVLINK_MSG_TEMP_TM_FIELD_SENSOR_NAME_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_TEMP_TM { \
- 108, \
- "TEMP_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_temp_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_temp_tm_t, sensor_name) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_temp_tm_t, temperature) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_TEMP_TM { \
- "TEMP_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_temp_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_temp_tm_t, sensor_name) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_temp_tm_t, temperature) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a temp_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param temperature [deg] Temperature
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_temp_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_name, float temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TEMP_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, temperature);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TEMP_TM_LEN);
-#else
- mavlink_temp_tm_t packet;
- packet.timestamp = timestamp;
- packet.temperature = temperature;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TEMP_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TEMP_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-}
-
-/**
- * @brief Pack a temp_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param temperature [deg] Temperature
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_temp_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_name,float temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TEMP_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, temperature);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TEMP_TM_LEN);
-#else
- mavlink_temp_tm_t packet;
- packet.timestamp = timestamp;
- packet.temperature = temperature;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TEMP_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TEMP_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-}
-
-/**
- * @brief Encode a temp_tm 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 temp_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_temp_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_temp_tm_t* temp_tm)
-{
- return mavlink_msg_temp_tm_pack(system_id, component_id, msg, temp_tm->timestamp, temp_tm->sensor_name, temp_tm->temperature);
-}
-
-/**
- * @brief Encode a temp_tm 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 temp_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_temp_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_temp_tm_t* temp_tm)
-{
- return mavlink_msg_temp_tm_pack_chan(system_id, component_id, chan, msg, temp_tm->timestamp, temp_tm->sensor_name, temp_tm->temperature);
-}
-
-/**
- * @brief Send a temp_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_name Sensor name
- * @param temperature [deg] Temperature
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_temp_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TEMP_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, temperature);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEMP_TM, buf, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-#else
- mavlink_temp_tm_t packet;
- packet.timestamp = timestamp;
- packet.temperature = temperature;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEMP_TM, (const char *)&packet, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a temp_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_temp_tm_send_struct(mavlink_channel_t chan, const mavlink_temp_tm_t* temp_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_temp_tm_send(chan, temp_tm->timestamp, temp_tm->sensor_name, temp_tm->temperature);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEMP_TM, (const char *)temp_tm, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_TEMP_TM_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_temp_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, temperature);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEMP_TM, buf, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-#else
- mavlink_temp_tm_t *packet = (mavlink_temp_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->temperature = temperature;
- mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEMP_TM, (const char *)packet, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE TEMP_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from temp_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_temp_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_name from temp_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_temp_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
-{
- return _MAV_RETURN_char_array(msg, sensor_name, 20, 12);
-}
-
-/**
- * @brief Get field temperature from temp_tm message
- *
- * @return [deg] Temperature
- */
-static inline float mavlink_msg_temp_tm_get_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Decode a temp_tm message into a struct
- *
- * @param msg The message to decode
- * @param temp_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_temp_tm_decode(const mavlink_message_t* msg, mavlink_temp_tm_t* temp_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- temp_tm->timestamp = mavlink_msg_temp_tm_get_timestamp(msg);
- temp_tm->temperature = mavlink_msg_temp_tm_get_temperature(msg);
- mavlink_msg_temp_tm_get_sensor_name(msg, temp_tm->sensor_name);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_TEMP_TM_LEN? msg->len : MAVLINK_MSG_ID_TEMP_TM_LEN;
- memset(temp_tm, 0, MAVLINK_MSG_ID_TEMP_TM_LEN);
- memcpy(temp_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_voltage_tm.h b/mavlink_lib/lyra/mavlink_msg_voltage_tm.h
deleted file mode 100644
index 5a391cee271737b01330a5546290d5ba21f3c3a8..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_voltage_tm.h
+++ /dev/null
@@ -1,255 +0,0 @@
-#pragma once
-// MESSAGE VOLTAGE_TM PACKING
-
-#define MAVLINK_MSG_ID_VOLTAGE_TM 106
-
-
-typedef struct __mavlink_voltage_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float voltage; /*< [V] Voltage*/
- char sensor_name[20]; /*< Sensor name*/
-} mavlink_voltage_tm_t;
-
-#define MAVLINK_MSG_ID_VOLTAGE_TM_LEN 32
-#define MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_106_LEN 32
-#define MAVLINK_MSG_ID_106_MIN_LEN 32
-
-#define MAVLINK_MSG_ID_VOLTAGE_TM_CRC 245
-#define MAVLINK_MSG_ID_106_CRC 245
-
-#define MAVLINK_MSG_VOLTAGE_TM_FIELD_SENSOR_NAME_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_VOLTAGE_TM { \
- 106, \
- "VOLTAGE_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_voltage_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_voltage_tm_t, sensor_name) }, \
- { "voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_voltage_tm_t, voltage) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_VOLTAGE_TM { \
- "VOLTAGE_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_voltage_tm_t, timestamp) }, \
- { "sensor_name", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_voltage_tm_t, sensor_name) }, \
- { "voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_voltage_tm_t, voltage) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a voltage_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param voltage [V] Voltage
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_voltage_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_name, float voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_VOLTAGE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, voltage);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VOLTAGE_TM_LEN);
-#else
- mavlink_voltage_tm_t packet;
- packet.timestamp = timestamp;
- packet.voltage = voltage;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VOLTAGE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_VOLTAGE_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-}
-
-/**
- * @brief Pack a voltage_tm 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] When was this logged
- * @param sensor_name Sensor name
- * @param voltage [V] Voltage
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_voltage_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_name,float voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_VOLTAGE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, voltage);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VOLTAGE_TM_LEN);
-#else
- mavlink_voltage_tm_t packet;
- packet.timestamp = timestamp;
- packet.voltage = voltage;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VOLTAGE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_VOLTAGE_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-}
-
-/**
- * @brief Encode a voltage_tm 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 voltage_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_voltage_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_voltage_tm_t* voltage_tm)
-{
- return mavlink_msg_voltage_tm_pack(system_id, component_id, msg, voltage_tm->timestamp, voltage_tm->sensor_name, voltage_tm->voltage);
-}
-
-/**
- * @brief Encode a voltage_tm 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 voltage_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_voltage_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_voltage_tm_t* voltage_tm)
-{
- return mavlink_msg_voltage_tm_pack_chan(system_id, component_id, chan, msg, voltage_tm->timestamp, voltage_tm->sensor_name, voltage_tm->voltage);
-}
-
-/**
- * @brief Send a voltage_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_name Sensor name
- * @param voltage [V] Voltage
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_voltage_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_VOLTAGE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, voltage);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLTAGE_TM, buf, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-#else
- mavlink_voltage_tm_t packet;
- packet.timestamp = timestamp;
- packet.voltage = voltage;
- mav_array_memcpy(packet.sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLTAGE_TM, (const char *)&packet, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a voltage_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_voltage_tm_send_struct(mavlink_channel_t chan, const mavlink_voltage_tm_t* voltage_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_voltage_tm_send(chan, voltage_tm->timestamp, voltage_tm->sensor_name, voltage_tm->voltage);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLTAGE_TM, (const char *)voltage_tm, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_VOLTAGE_TM_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_voltage_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_name, float voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, voltage);
- _mav_put_char_array(buf, 12, sensor_name, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLTAGE_TM, buf, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-#else
- mavlink_voltage_tm_t *packet = (mavlink_voltage_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->voltage = voltage;
- mav_array_memcpy(packet->sensor_name, sensor_name, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLTAGE_TM, (const char *)packet, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE VOLTAGE_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from voltage_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_voltage_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_name from voltage_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_voltage_tm_get_sensor_name(const mavlink_message_t* msg, char *sensor_name)
-{
- return _MAV_RETURN_char_array(msg, sensor_name, 20, 12);
-}
-
-/**
- * @brief Get field voltage from voltage_tm message
- *
- * @return [V] Voltage
- */
-static inline float mavlink_msg_voltage_tm_get_voltage(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Decode a voltage_tm message into a struct
- *
- * @param msg The message to decode
- * @param voltage_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_voltage_tm_decode(const mavlink_message_t* msg, mavlink_voltage_tm_t* voltage_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- voltage_tm->timestamp = mavlink_msg_voltage_tm_get_timestamp(msg);
- voltage_tm->voltage = mavlink_msg_voltage_tm_get_voltage(msg);
- mavlink_msg_voltage_tm_get_sensor_name(msg, voltage_tm->sensor_name);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_VOLTAGE_TM_LEN? msg->len : MAVLINK_MSG_ID_VOLTAGE_TM_LEN;
- memset(voltage_tm, 0, MAVLINK_MSG_ID_VOLTAGE_TM_LEN);
- memcpy(voltage_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/mavlink_msg_wiggle_servo_tc.h b/mavlink_lib/lyra/mavlink_msg_wiggle_servo_tc.h
deleted file mode 100644
index b9e333c4ed5bde71c947b204fee64987ed98b2ad..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/mavlink_msg_wiggle_servo_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE WIGGLE_SERVO_TC PACKING
-
-#define MAVLINK_MSG_ID_WIGGLE_SERVO_TC 7
-
-
-typedef struct __mavlink_wiggle_servo_tc_t {
- uint8_t servo_id; /*< A member of the ServosList enum*/
-} mavlink_wiggle_servo_tc_t;
-
-#define MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN 1
-#define MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_7_LEN 1
-#define MAVLINK_MSG_ID_7_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC 160
-#define MAVLINK_MSG_ID_7_CRC 160
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC { \
- 7, \
- "WIGGLE_SERVO_TC", \
- 1, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_wiggle_servo_tc_t, servo_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC { \
- "WIGGLE_SERVO_TC", \
- 1, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_wiggle_servo_tc_t, servo_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a wiggle_servo_tc 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 servo_id A member of the ServosList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_wiggle_servo_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN);
-#else
- mavlink_wiggle_servo_tc_t packet;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_WIGGLE_SERVO_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-}
-
-/**
- * @brief Pack a wiggle_servo_tc 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 servo_id A member of the ServosList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_wiggle_servo_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN);
-#else
- mavlink_wiggle_servo_tc_t packet;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_WIGGLE_SERVO_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-}
-
-/**
- * @brief Encode a wiggle_servo_tc 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 wiggle_servo_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_wiggle_servo_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_wiggle_servo_tc_t* wiggle_servo_tc)
-{
- return mavlink_msg_wiggle_servo_tc_pack(system_id, component_id, msg, wiggle_servo_tc->servo_id);
-}
-
-/**
- * @brief Encode a wiggle_servo_tc 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 wiggle_servo_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_wiggle_servo_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_wiggle_servo_tc_t* wiggle_servo_tc)
-{
- return mavlink_msg_wiggle_servo_tc_pack_chan(system_id, component_id, chan, msg, wiggle_servo_tc->servo_id);
-}
-
-/**
- * @brief Send a wiggle_servo_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param servo_id A member of the ServosList enum
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_wiggle_servo_tc_send(mavlink_channel_t chan, uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIGGLE_SERVO_TC, buf, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-#else
- mavlink_wiggle_servo_tc_t packet;
- packet.servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIGGLE_SERVO_TC, (const char *)&packet, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a wiggle_servo_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_wiggle_servo_tc_send_struct(mavlink_channel_t chan, const mavlink_wiggle_servo_tc_t* wiggle_servo_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_wiggle_servo_tc_send(chan, wiggle_servo_tc->servo_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIGGLE_SERVO_TC, (const char *)wiggle_servo_tc, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_WIGGLE_SERVO_TC_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_wiggle_servo_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIGGLE_SERVO_TC, buf, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-#else
- mavlink_wiggle_servo_tc_t *packet = (mavlink_wiggle_servo_tc_t *)msgbuf;
- packet->servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIGGLE_SERVO_TC, (const char *)packet, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE WIGGLE_SERVO_TC UNPACKING
-
-
-/**
- * @brief Get field servo_id from wiggle_servo_tc message
- *
- * @return A member of the ServosList enum
- */
-static inline uint8_t mavlink_msg_wiggle_servo_tc_get_servo_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a wiggle_servo_tc message into a struct
- *
- * @param msg The message to decode
- * @param wiggle_servo_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_wiggle_servo_tc_decode(const mavlink_message_t* msg, mavlink_wiggle_servo_tc_t* wiggle_servo_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- wiggle_servo_tc->servo_id = mavlink_msg_wiggle_servo_tc_get_servo_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN? msg->len : MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN;
- memset(wiggle_servo_tc, 0, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN);
- memcpy(wiggle_servo_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/lyra/testsuite.h b/mavlink_lib/lyra/testsuite.h
deleted file mode 100644
index cc485ecebc1914107c152c22331824516ca1683c..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/testsuite.h
+++ /dev/null
@@ -1,3620 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol testsuite generated from lyra.xml
- * @see https://mavlink.io/en/
- */
-#pragma once
-#ifndef LYRA_TESTSUITE_H
-#define LYRA_TESTSUITE_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#ifndef MAVLINK_TEST_ALL
-#define MAVLINK_TEST_ALL
-
-static void mavlink_test_lyra(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_lyra(system_id, component_id, last_msg);
-}
-#endif
-
-
-
-
-static void mavlink_test_ping_tc(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_PING_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ping_tc_t packet_in = {
- 93372036854775807ULL
- };
- mavlink_ping_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_PING_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PING_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ping_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_pack(system_id, component_id, &msg , packet1.timestamp );
- mavlink_msg_ping_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp );
- mavlink_msg_ping_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ping_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_send(MAVLINK_COMM_1 , packet1.timestamp );
- mavlink_msg_ping_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("PING_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_PING_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_command_tc(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_COMMAND_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_command_tc_t packet_in = {
- 5
- };
- mavlink_command_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.command_id = packet_in.command_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_command_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_command_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_command_tc_pack(system_id, component_id, &msg , packet1.command_id );
- mavlink_msg_command_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_command_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.command_id );
- mavlink_msg_command_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_command_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_command_tc_send(MAVLINK_COMM_1 , packet1.command_id );
- mavlink_msg_command_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("COMMAND_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_COMMAND_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_system_tm_request_tc(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_SYSTEM_TM_REQUEST_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_system_tm_request_tc_t packet_in = {
- 5
- };
- mavlink_system_tm_request_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.tm_id = packet_in.tm_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_system_tm_request_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_system_tm_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_system_tm_request_tc_pack(system_id, component_id, &msg , packet1.tm_id );
- mavlink_msg_system_tm_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_system_tm_request_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.tm_id );
- mavlink_msg_system_tm_request_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_system_tm_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_system_tm_request_tc_send(MAVLINK_COMM_1 , packet1.tm_id );
- mavlink_msg_system_tm_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SYSTEM_TM_REQUEST_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_sensor_tm_request_tc(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_SENSOR_TM_REQUEST_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_sensor_tm_request_tc_t packet_in = {
- 5
- };
- mavlink_sensor_tm_request_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.sensor_name = packet_in.sensor_name;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_tm_request_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_sensor_tm_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_tm_request_tc_pack(system_id, component_id, &msg , packet1.sensor_name );
- mavlink_msg_sensor_tm_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_tm_request_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.sensor_name );
- mavlink_msg_sensor_tm_request_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_sensor_tm_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_tm_request_tc_send(MAVLINK_COMM_1 , packet1.sensor_name );
- mavlink_msg_sensor_tm_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SENSOR_TM_REQUEST_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_servo_tm_request_tc(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_SERVO_TM_REQUEST_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_servo_tm_request_tc_t packet_in = {
- 5
- };
- mavlink_servo_tm_request_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.servo_id = packet_in.servo_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_request_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_servo_tm_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_request_tc_pack(system_id, component_id, &msg , packet1.servo_id );
- mavlink_msg_servo_tm_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_request_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id );
- mavlink_msg_servo_tm_request_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_servo_tm_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_request_tc_send(MAVLINK_COMM_1 , packet1.servo_id );
- mavlink_msg_servo_tm_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SERVO_TM_REQUEST_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_servo_angle_tc(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_SET_SERVO_ANGLE_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_servo_angle_tc_t packet_in = {
- 17.0,17
- };
- mavlink_set_servo_angle_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.angle = packet_in.angle;
- packet1.servo_id = packet_in.servo_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_servo_angle_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_servo_angle_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_servo_angle_tc_pack(system_id, component_id, &msg , packet1.servo_id , packet1.angle );
- mavlink_msg_set_servo_angle_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_servo_angle_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id , packet1.angle );
- mavlink_msg_set_servo_angle_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_servo_angle_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_servo_angle_tc_send(MAVLINK_COMM_1 , packet1.servo_id , packet1.angle );
- mavlink_msg_set_servo_angle_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_SERVO_ANGLE_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_wiggle_servo_tc(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_WIGGLE_SERVO_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_wiggle_servo_tc_t packet_in = {
- 5
- };
- mavlink_wiggle_servo_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.servo_id = packet_in.servo_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_wiggle_servo_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_wiggle_servo_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_wiggle_servo_tc_pack(system_id, component_id, &msg , packet1.servo_id );
- mavlink_msg_wiggle_servo_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_wiggle_servo_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id );
- mavlink_msg_wiggle_servo_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_wiggle_servo_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_wiggle_servo_tc_send(MAVLINK_COMM_1 , packet1.servo_id );
- mavlink_msg_wiggle_servo_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("WIGGLE_SERVO_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_WIGGLE_SERVO_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_reset_servo_tc(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_RESET_SERVO_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_reset_servo_tc_t packet_in = {
- 5
- };
- mavlink_reset_servo_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.servo_id = packet_in.servo_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_reset_servo_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_reset_servo_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_reset_servo_tc_pack(system_id, component_id, &msg , packet1.servo_id );
- mavlink_msg_reset_servo_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_reset_servo_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id );
- mavlink_msg_reset_servo_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_reset_servo_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_reset_servo_tc_send(MAVLINK_COMM_1 , packet1.servo_id );
- mavlink_msg_reset_servo_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("RESET_SERVO_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_RESET_SERVO_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_reference_altitude_tc(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_SET_REFERENCE_ALTITUDE_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_reference_altitude_tc_t packet_in = {
- 17.0
- };
- mavlink_set_reference_altitude_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.ref_altitude = packet_in.ref_altitude;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_altitude_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_reference_altitude_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_altitude_tc_pack(system_id, component_id, &msg , packet1.ref_altitude );
- mavlink_msg_set_reference_altitude_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_altitude_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.ref_altitude );
- mavlink_msg_set_reference_altitude_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_reference_altitude_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_altitude_tc_send(MAVLINK_COMM_1 , packet1.ref_altitude );
- mavlink_msg_set_reference_altitude_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_REFERENCE_ALTITUDE_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_reference_temperature_tc(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_SET_REFERENCE_TEMPERATURE_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_reference_temperature_tc_t packet_in = {
- 17.0
- };
- mavlink_set_reference_temperature_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.ref_temp = packet_in.ref_temp;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_temperature_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_reference_temperature_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_temperature_tc_pack(system_id, component_id, &msg , packet1.ref_temp );
- mavlink_msg_set_reference_temperature_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_temperature_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.ref_temp );
- mavlink_msg_set_reference_temperature_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_reference_temperature_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_temperature_tc_send(MAVLINK_COMM_1 , packet1.ref_temp );
- mavlink_msg_set_reference_temperature_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_REFERENCE_TEMPERATURE_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_orientation_tc(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_SET_ORIENTATION_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_orientation_tc_t packet_in = {
- 17.0,45.0,73.0
- };
- mavlink_set_orientation_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.yaw = packet_in.yaw;
- packet1.pitch = packet_in.pitch;
- packet1.roll = packet_in.roll;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_orientation_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_orientation_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_orientation_tc_pack(system_id, component_id, &msg , packet1.yaw , packet1.pitch , packet1.roll );
- mavlink_msg_set_orientation_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_orientation_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.yaw , packet1.pitch , packet1.roll );
- mavlink_msg_set_orientation_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_orientation_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_orientation_tc_send(MAVLINK_COMM_1 , packet1.yaw , packet1.pitch , packet1.roll );
- mavlink_msg_set_orientation_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_ORIENTATION_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_ORIENTATION_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_coordinates_tc(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_SET_COORDINATES_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_coordinates_tc_t packet_in = {
- 17.0,45.0
- };
- mavlink_set_coordinates_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.latitude = packet_in.latitude;
- packet1.longitude = packet_in.longitude;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_coordinates_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_coordinates_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_coordinates_tc_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude );
- mavlink_msg_set_coordinates_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_coordinates_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude );
- mavlink_msg_set_coordinates_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_coordinates_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_coordinates_tc_send(MAVLINK_COMM_1 , packet1.latitude , packet1.longitude );
- mavlink_msg_set_coordinates_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_COORDINATES_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_COORDINATES_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_raw_event_tc(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_RAW_EVENT_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_raw_event_tc_t packet_in = {
- 5,72
- };
- mavlink_raw_event_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.topic_id = packet_in.topic_id;
- packet1.event_id = packet_in.event_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_raw_event_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_pack(system_id, component_id, &msg , packet1.topic_id , packet1.event_id );
- mavlink_msg_raw_event_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.topic_id , packet1.event_id );
- mavlink_msg_raw_event_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_raw_event_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_send(MAVLINK_COMM_1 , packet1.topic_id , packet1.event_id );
- mavlink_msg_raw_event_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("RAW_EVENT_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_RAW_EVENT_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_deployment_altitude_tc(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_SET_DEPLOYMENT_ALTITUDE_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_deployment_altitude_tc_t packet_in = {
- 17.0
- };
- mavlink_set_deployment_altitude_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.dpl_altitude = packet_in.dpl_altitude;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_deployment_altitude_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_deployment_altitude_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_deployment_altitude_tc_pack(system_id, component_id, &msg , packet1.dpl_altitude );
- mavlink_msg_set_deployment_altitude_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_deployment_altitude_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.dpl_altitude );
- mavlink_msg_set_deployment_altitude_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_deployment_altitude_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_deployment_altitude_tc_send(MAVLINK_COMM_1 , packet1.dpl_altitude );
- mavlink_msg_set_deployment_altitude_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_DEPLOYMENT_ALTITUDE_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_target_coordinates_tc(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_SET_TARGET_COORDINATES_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_target_coordinates_tc_t packet_in = {
- 17.0,45.0
- };
- mavlink_set_target_coordinates_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.latitude = packet_in.latitude;
- packet1.longitude = packet_in.longitude;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_target_coordinates_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_target_coordinates_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_target_coordinates_tc_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude );
- mavlink_msg_set_target_coordinates_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_target_coordinates_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude );
- mavlink_msg_set_target_coordinates_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_target_coordinates_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_target_coordinates_tc_send(MAVLINK_COMM_1 , packet1.latitude , packet1.longitude );
- mavlink_msg_set_target_coordinates_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_TARGET_COORDINATES_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_algorithm_tc(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_SET_ALGORITHM_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_algorithm_tc_t packet_in = {
- 5
- };
- mavlink_set_algorithm_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.algorithm_number = packet_in.algorithm_number;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_algorithm_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_algorithm_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_algorithm_tc_pack(system_id, component_id, &msg , packet1.algorithm_number );
- mavlink_msg_set_algorithm_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_algorithm_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.algorithm_number );
- mavlink_msg_set_algorithm_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_algorithm_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_algorithm_tc_send(MAVLINK_COMM_1 , packet1.algorithm_number );
- mavlink_msg_set_algorithm_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_ALGORITHM_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_ALGORITHM_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_atomic_valve_timing_tc(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_SET_ATOMIC_VALVE_TIMING_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_atomic_valve_timing_tc_t packet_in = {
- 963497464,17
- };
- mavlink_set_atomic_valve_timing_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.maximum_timing = packet_in.maximum_timing;
- packet1.servo_id = packet_in.servo_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_atomic_valve_timing_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_atomic_valve_timing_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_atomic_valve_timing_tc_pack(system_id, component_id, &msg , packet1.servo_id , packet1.maximum_timing );
- mavlink_msg_set_atomic_valve_timing_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_atomic_valve_timing_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id , packet1.maximum_timing );
- mavlink_msg_set_atomic_valve_timing_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_atomic_valve_timing_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_atomic_valve_timing_tc_send(MAVLINK_COMM_1 , packet1.servo_id , packet1.maximum_timing );
- mavlink_msg_set_atomic_valve_timing_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_ATOMIC_VALVE_TIMING_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_ATOMIC_VALVE_TIMING_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_valve_maximum_aperture_tc(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_SET_VALVE_MAXIMUM_APERTURE_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_valve_maximum_aperture_tc_t packet_in = {
- 17.0,17
- };
- mavlink_set_valve_maximum_aperture_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.maximum_aperture = packet_in.maximum_aperture;
- packet1.servo_id = packet_in.servo_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_valve_maximum_aperture_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_valve_maximum_aperture_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_valve_maximum_aperture_tc_pack(system_id, component_id, &msg , packet1.servo_id , packet1.maximum_aperture );
- mavlink_msg_set_valve_maximum_aperture_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_valve_maximum_aperture_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id , packet1.maximum_aperture );
- mavlink_msg_set_valve_maximum_aperture_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_valve_maximum_aperture_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_valve_maximum_aperture_tc_send(MAVLINK_COMM_1 , packet1.servo_id , packet1.maximum_aperture );
- mavlink_msg_set_valve_maximum_aperture_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_VALVE_MAXIMUM_APERTURE_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_VALVE_MAXIMUM_APERTURE_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_conrig_state_tc(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_CONRIG_STATE_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_conrig_state_tc_t packet_in = {
- 5,72,139,206,17,84,151
- };
- mavlink_conrig_state_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.ignition_btn = packet_in.ignition_btn;
- packet1.filling_valve_btn = packet_in.filling_valve_btn;
- packet1.venting_valve_btn = packet_in.venting_valve_btn;
- packet1.release_pressure_btn = packet_in.release_pressure_btn;
- packet1.quick_connector_btn = packet_in.quick_connector_btn;
- packet1.start_tars_btn = packet_in.start_tars_btn;
- packet1.arm_switch = packet_in.arm_switch;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CONRIG_STATE_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_conrig_state_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_conrig_state_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_conrig_state_tc_pack(system_id, component_id, &msg , packet1.ignition_btn , packet1.filling_valve_btn , packet1.venting_valve_btn , packet1.release_pressure_btn , packet1.quick_connector_btn , packet1.start_tars_btn , packet1.arm_switch );
- mavlink_msg_conrig_state_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_conrig_state_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.ignition_btn , packet1.filling_valve_btn , packet1.venting_valve_btn , packet1.release_pressure_btn , packet1.quick_connector_btn , packet1.start_tars_btn , packet1.arm_switch );
- mavlink_msg_conrig_state_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_conrig_state_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_conrig_state_tc_send(MAVLINK_COMM_1 , packet1.ignition_btn , packet1.filling_valve_btn , packet1.venting_valve_btn , packet1.release_pressure_btn , packet1.quick_connector_btn , packet1.start_tars_btn , packet1.arm_switch );
- mavlink_msg_conrig_state_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("CONRIG_STATE_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_CONRIG_STATE_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_ignition_time_tc(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_SET_IGNITION_TIME_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_ignition_time_tc_t packet_in = {
- 963497464
- };
- mavlink_set_ignition_time_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timing = packet_in.timing;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_ignition_time_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_ignition_time_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_ignition_time_tc_pack(system_id, component_id, &msg , packet1.timing );
- mavlink_msg_set_ignition_time_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_ignition_time_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timing );
- mavlink_msg_set_ignition_time_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_ignition_time_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_ignition_time_tc_send(MAVLINK_COMM_1 , packet1.timing );
- mavlink_msg_set_ignition_time_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_IGNITION_TIME_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_IGNITION_TIME_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_stepper_angle_tc(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_SET_STEPPER_ANGLE_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_stepper_angle_tc_t packet_in = {
- 17.0,17
- };
- mavlink_set_stepper_angle_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.angle = packet_in.angle;
- packet1.stepper_id = packet_in.stepper_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_stepper_angle_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_stepper_angle_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_stepper_angle_tc_pack(system_id, component_id, &msg , packet1.stepper_id , packet1.angle );
- mavlink_msg_set_stepper_angle_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_stepper_angle_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.stepper_id , packet1.angle );
- mavlink_msg_set_stepper_angle_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_stepper_angle_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_stepper_angle_tc_send(MAVLINK_COMM_1 , packet1.stepper_id , packet1.angle );
- mavlink_msg_set_stepper_angle_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_STEPPER_ANGLE_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_STEPPER_ANGLE_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_stepper_steps_tc(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_SET_STEPPER_STEPS_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_stepper_steps_tc_t packet_in = {
- 17.0,17
- };
- mavlink_set_stepper_steps_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.steps = packet_in.steps;
- packet1.stepper_id = packet_in.stepper_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_stepper_steps_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_stepper_steps_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_stepper_steps_tc_pack(system_id, component_id, &msg , packet1.stepper_id , packet1.steps );
- mavlink_msg_set_stepper_steps_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_stepper_steps_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.stepper_id , packet1.steps );
- mavlink_msg_set_stepper_steps_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_stepper_steps_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_stepper_steps_tc_send(MAVLINK_COMM_1 , packet1.stepper_id , packet1.steps );
- mavlink_msg_set_stepper_steps_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_STEPPER_STEPS_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_STEPPER_STEPS_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_ack_tm(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_ACK_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ack_tm_t packet_in = {
- 5,72
- };
- mavlink_ack_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.recv_msgid = packet_in.recv_msgid;
- packet1.seq_ack = packet_in.seq_ack;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_ACK_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ACK_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_pack(system_id, component_id, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_ack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_ack_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_send(MAVLINK_COMM_1 , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_ack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("ACK_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ACK_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_nack_tm(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_NACK_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_nack_tm_t packet_in = {
- 5,72
- };
- mavlink_nack_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.recv_msgid = packet_in.recv_msgid;
- packet1.seq_ack = packet_in.seq_ack;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_NACK_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NACK_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nack_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_nack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nack_tm_pack(system_id, component_id, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_nack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nack_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_nack_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_nack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nack_tm_send(MAVLINK_COMM_1 , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_nack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("NACK_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_NACK_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_gps_tm(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_GPS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_gps_tm_t packet_in = {
- 93372036854775807ULL,179.0,235.0,291.0,241.0,269.0,297.0,325.0,353.0,"ABCDEFGHIJKLMNOPQRS",221,32
- };
- mavlink_gps_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.latitude = packet_in.latitude;
- packet1.longitude = packet_in.longitude;
- packet1.height = packet_in.height;
- packet1.vel_north = packet_in.vel_north;
- packet1.vel_east = packet_in.vel_east;
- packet1.vel_down = packet_in.vel_down;
- packet1.speed = packet_in.speed;
- packet1.track = packet_in.track;
- packet1.fix = packet_in.fix;
- packet1.n_satellites = packet_in.n_satellites;
-
- mav_array_memcpy(packet1.sensor_name, packet_in.sensor_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_GPS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gps_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_gps_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gps_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_name , packet1.fix , packet1.latitude , packet1.longitude , packet1.height , packet1.vel_north , packet1.vel_east , packet1.vel_down , packet1.speed , packet1.track , packet1.n_satellites );
- mavlink_msg_gps_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gps_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_name , packet1.fix , packet1.latitude , packet1.longitude , packet1.height , packet1.vel_north , packet1.vel_east , packet1.vel_down , packet1.speed , packet1.track , packet1.n_satellites );
- mavlink_msg_gps_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_gps_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gps_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_name , packet1.fix , packet1.latitude , packet1.longitude , packet1.height , packet1.vel_north , packet1.vel_east , packet1.vel_down , packet1.speed , packet1.track , packet1.n_satellites );
- mavlink_msg_gps_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("GPS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_GPS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_imu_tm(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_IMU_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_imu_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,"STUVWXYZABCDEFGHIJK"
- };
- mavlink_imu_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.acc_x = packet_in.acc_x;
- packet1.acc_y = packet_in.acc_y;
- packet1.acc_z = packet_in.acc_z;
- packet1.gyro_x = packet_in.gyro_x;
- packet1.gyro_y = packet_in.gyro_y;
- packet1.gyro_z = packet_in.gyro_z;
- packet1.mag_x = packet_in.mag_x;
- packet1.mag_y = packet_in.mag_y;
- packet1.mag_z = packet_in.mag_z;
-
- mav_array_memcpy(packet1.sensor_name, packet_in.sensor_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_IMU_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_IMU_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_imu_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_imu_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_imu_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_name , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z );
- mavlink_msg_imu_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_imu_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_name , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z );
- mavlink_msg_imu_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_imu_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_imu_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_name , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z );
- mavlink_msg_imu_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("IMU_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_IMU_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_pressure_tm(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_PRESSURE_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_pressure_tm_t packet_in = {
- 93372036854775807ULL,73.0,"MNOPQRSTUVWXYZABCDE"
- };
- mavlink_pressure_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.pressure = packet_in.pressure;
-
- mav_array_memcpy(packet1.sensor_name, packet_in.sensor_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_PRESSURE_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pressure_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_pressure_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pressure_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_name , packet1.pressure );
- mavlink_msg_pressure_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pressure_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_name , packet1.pressure );
- mavlink_msg_pressure_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_pressure_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pressure_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_name , packet1.pressure );
- mavlink_msg_pressure_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("PRESSURE_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_PRESSURE_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_adc_tm(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_ADC_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_adc_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,"OPQRSTUVWXYZABCDEFG"
- };
- mavlink_adc_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.channel_0 = packet_in.channel_0;
- packet1.channel_1 = packet_in.channel_1;
- packet1.channel_2 = packet_in.channel_2;
- packet1.channel_3 = packet_in.channel_3;
- packet1.channel_4 = packet_in.channel_4;
- packet1.channel_5 = packet_in.channel_5;
- packet1.channel_6 = packet_in.channel_6;
- packet1.channel_7 = packet_in.channel_7;
-
- mav_array_memcpy(packet1.sensor_name, packet_in.sensor_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_ADC_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ADC_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adc_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_adc_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adc_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_name , packet1.channel_0 , packet1.channel_1 , packet1.channel_2 , packet1.channel_3 , packet1.channel_4 , packet1.channel_5 , packet1.channel_6 , packet1.channel_7 );
- mavlink_msg_adc_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adc_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_name , packet1.channel_0 , packet1.channel_1 , packet1.channel_2 , packet1.channel_3 , packet1.channel_4 , packet1.channel_5 , packet1.channel_6 , packet1.channel_7 );
- mavlink_msg_adc_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_adc_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adc_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_name , packet1.channel_0 , packet1.channel_1 , packet1.channel_2 , packet1.channel_3 , packet1.channel_4 , packet1.channel_5 , packet1.channel_6 , packet1.channel_7 );
- mavlink_msg_adc_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("ADC_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ADC_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_voltage_tm(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_VOLTAGE_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_voltage_tm_t packet_in = {
- 93372036854775807ULL,73.0,"MNOPQRSTUVWXYZABCDE"
- };
- mavlink_voltage_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.voltage = packet_in.voltage;
-
- mav_array_memcpy(packet1.sensor_name, packet_in.sensor_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_VOLTAGE_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_voltage_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_voltage_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_voltage_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_name , packet1.voltage );
- mavlink_msg_voltage_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_voltage_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_name , packet1.voltage );
- mavlink_msg_voltage_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_voltage_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_voltage_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_name , packet1.voltage );
- mavlink_msg_voltage_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("VOLTAGE_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_VOLTAGE_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_current_tm(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_CURRENT_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_current_tm_t packet_in = {
- 93372036854775807ULL,73.0,"MNOPQRSTUVWXYZABCDE"
- };
- mavlink_current_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.current = packet_in.current;
-
- mav_array_memcpy(packet1.sensor_name, packet_in.sensor_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_CURRENT_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_current_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_current_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_current_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_name , packet1.current );
- mavlink_msg_current_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_current_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_name , packet1.current );
- mavlink_msg_current_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_current_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_current_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_name , packet1.current );
- mavlink_msg_current_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("CURRENT_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_CURRENT_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_temp_tm(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_TEMP_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_temp_tm_t packet_in = {
- 93372036854775807ULL,73.0,"MNOPQRSTUVWXYZABCDE"
- };
- mavlink_temp_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.temperature = packet_in.temperature;
-
- mav_array_memcpy(packet1.sensor_name, packet_in.sensor_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_TEMP_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TEMP_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_temp_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_temp_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_temp_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_name , packet1.temperature );
- mavlink_msg_temp_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_temp_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_name , packet1.temperature );
- mavlink_msg_temp_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_temp_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_temp_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_name , packet1.temperature );
- mavlink_msg_temp_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("TEMP_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_TEMP_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_load_tm(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_LOAD_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_load_tm_t packet_in = {
- 93372036854775807ULL,73.0,"MNOPQRSTUVWXYZABCDE"
- };
- mavlink_load_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.load = packet_in.load;
-
- mav_array_memcpy(packet1.sensor_name, packet_in.sensor_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_LOAD_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOAD_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_load_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_load_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_load_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_name , packet1.load );
- mavlink_msg_load_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_load_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_name , packet1.load );
- mavlink_msg_load_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_load_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_load_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_name , packet1.load );
- mavlink_msg_load_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("LOAD_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_LOAD_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_attitude_tm(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_ATTITUDE_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_attitude_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,"KLMNOPQRSTUVWXYZABC"
- };
- mavlink_attitude_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.roll = packet_in.roll;
- packet1.pitch = packet_in.pitch;
- packet1.yaw = packet_in.yaw;
- packet1.quat_x = packet_in.quat_x;
- packet1.quat_y = packet_in.quat_y;
- packet1.quat_z = packet_in.quat_z;
- packet1.quat_w = packet_in.quat_w;
-
- mav_array_memcpy(packet1.sensor_name, packet_in.sensor_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_ATTITUDE_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_attitude_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_attitude_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_attitude_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_name , packet1.roll , packet1.pitch , packet1.yaw , packet1.quat_x , packet1.quat_y , packet1.quat_z , packet1.quat_w );
- mavlink_msg_attitude_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_attitude_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_name , packet1.roll , packet1.pitch , packet1.yaw , packet1.quat_x , packet1.quat_y , packet1.quat_z , packet1.quat_w );
- mavlink_msg_attitude_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_attitude_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_attitude_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_name , packet1.roll , packet1.pitch , packet1.yaw , packet1.quat_x , packet1.quat_y , packet1.quat_z , packet1.quat_w );
- mavlink_msg_attitude_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("ATTITUDE_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ATTITUDE_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_sensor_state_tm(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_SENSOR_STATE_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_sensor_state_tm_t packet_in = {
- "ABCDEFGHIJKLMNOPQRS",65
- };
- mavlink_sensor_state_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.state = packet_in.state;
-
- mav_array_memcpy(packet1.sensor_name, packet_in.sensor_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_SENSOR_STATE_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_state_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_sensor_state_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_state_tm_pack(system_id, component_id, &msg , packet1.sensor_name , packet1.state );
- mavlink_msg_sensor_state_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_state_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.sensor_name , packet1.state );
- mavlink_msg_sensor_state_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_sensor_state_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_state_tm_send(MAVLINK_COMM_1 , packet1.sensor_name , packet1.state );
- mavlink_msg_sensor_state_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SENSOR_STATE_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SENSOR_STATE_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_servo_tm(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_SERVO_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_servo_tm_t packet_in = {
- 17.0,17
- };
- mavlink_servo_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.servo_position = packet_in.servo_position;
- packet1.servo_id = packet_in.servo_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SERVO_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SERVO_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_servo_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_pack(system_id, component_id, &msg , packet1.servo_id , packet1.servo_position );
- mavlink_msg_servo_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id , packet1.servo_position );
- mavlink_msg_servo_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_servo_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_send(MAVLINK_COMM_1 , packet1.servo_id , packet1.servo_position );
- mavlink_msg_servo_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SERVO_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SERVO_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_pin_tm(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_PIN_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_pin_tm_t packet_in = {
- 93372036854775807ULL,93372036854776311ULL,53,120,187
- };
- mavlink_pin_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.last_change_timestamp = packet_in.last_change_timestamp;
- packet1.pin_id = packet_in.pin_id;
- packet1.changes_counter = packet_in.changes_counter;
- packet1.current_state = packet_in.current_state;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_PIN_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PIN_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pin_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_pin_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pin_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.pin_id , packet1.last_change_timestamp , packet1.changes_counter , packet1.current_state );
- mavlink_msg_pin_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pin_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.pin_id , packet1.last_change_timestamp , packet1.changes_counter , packet1.current_state );
- mavlink_msg_pin_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_pin_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pin_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.pin_id , packet1.last_change_timestamp , packet1.changes_counter , packet1.current_state );
- mavlink_msg_pin_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("PIN_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_PIN_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_receiver_tm(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_RECEIVER_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_receiver_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,18691,18795,18899,19003,19107,19211,19315,19419,19523,19627,149,216,27,94
- };
- mavlink_receiver_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.main_rx_rssi = packet_in.main_rx_rssi;
- packet1.main_rx_fei = packet_in.main_rx_fei;
- packet1.payload_rx_rssi = packet_in.payload_rx_rssi;
- packet1.payload_rx_fei = packet_in.payload_rx_fei;
- packet1.battery_voltage = packet_in.battery_voltage;
- packet1.main_packet_tx_error_count = packet_in.main_packet_tx_error_count;
- packet1.main_tx_bitrate = packet_in.main_tx_bitrate;
- packet1.main_packet_rx_success_count = packet_in.main_packet_rx_success_count;
- packet1.main_packet_rx_drop_count = packet_in.main_packet_rx_drop_count;
- packet1.main_rx_bitrate = packet_in.main_rx_bitrate;
- packet1.payload_packet_tx_error_count = packet_in.payload_packet_tx_error_count;
- packet1.payload_tx_bitrate = packet_in.payload_tx_bitrate;
- packet1.payload_packet_rx_success_count = packet_in.payload_packet_rx_success_count;
- packet1.payload_packet_rx_drop_count = packet_in.payload_packet_rx_drop_count;
- packet1.payload_rx_bitrate = packet_in.payload_rx_bitrate;
- packet1.main_radio_present = packet_in.main_radio_present;
- packet1.payload_radio_present = packet_in.payload_radio_present;
- packet1.ethernet_present = packet_in.ethernet_present;
- packet1.ethernet_status = packet_in.ethernet_status;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_receiver_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_receiver_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_receiver_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.main_rx_fei , packet1.payload_radio_present , packet1.payload_packet_tx_error_count , packet1.payload_tx_bitrate , packet1.payload_packet_rx_success_count , packet1.payload_packet_rx_drop_count , packet1.payload_rx_bitrate , packet1.payload_rx_rssi , packet1.payload_rx_fei , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
- mavlink_msg_receiver_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_receiver_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.main_rx_fei , packet1.payload_radio_present , packet1.payload_packet_tx_error_count , packet1.payload_tx_bitrate , packet1.payload_packet_rx_success_count , packet1.payload_packet_rx_drop_count , packet1.payload_rx_bitrate , packet1.payload_rx_rssi , packet1.payload_rx_fei , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
- mavlink_msg_receiver_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_receiver_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_receiver_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.main_rx_fei , packet1.payload_radio_present , packet1.payload_packet_tx_error_count , packet1.payload_tx_bitrate , packet1.payload_packet_rx_success_count , packet1.payload_packet_rx_drop_count , packet1.payload_rx_bitrate , packet1.payload_rx_rssi , packet1.payload_rx_fei , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
- mavlink_msg_receiver_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("RECEIVER_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_RECEIVER_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_arp_tm(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_ARP_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_arp_tm_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,437.0,465.0,493.0,20979,21083,21187,21291,21395,123,190,1,68
- };
- mavlink_arp_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.yaw = packet_in.yaw;
- packet1.pitch = packet_in.pitch;
- packet1.roll = packet_in.roll;
- packet1.target_yaw = packet_in.target_yaw;
- packet1.target_pitch = packet_in.target_pitch;
- packet1.stepperX_pos = packet_in.stepperX_pos;
- packet1.stepperX_delta = packet_in.stepperX_delta;
- packet1.stepperX_speed = packet_in.stepperX_speed;
- packet1.stepperY_pos = packet_in.stepperY_pos;
- packet1.stepperY_delta = packet_in.stepperY_delta;
- packet1.stepperY_speed = packet_in.stepperY_speed;
- packet1.gps_latitude = packet_in.gps_latitude;
- packet1.gps_longitude = packet_in.gps_longitude;
- packet1.gps_height = packet_in.gps_height;
- packet1.main_rx_rssi = packet_in.main_rx_rssi;
- packet1.battery_voltage = packet_in.battery_voltage;
- packet1.main_packet_tx_error_count = packet_in.main_packet_tx_error_count;
- packet1.main_tx_bitrate = packet_in.main_tx_bitrate;
- packet1.main_packet_rx_success_count = packet_in.main_packet_rx_success_count;
- packet1.main_packet_rx_drop_count = packet_in.main_packet_rx_drop_count;
- packet1.main_rx_bitrate = packet_in.main_rx_bitrate;
- packet1.gps_fix = packet_in.gps_fix;
- packet1.main_radio_present = packet_in.main_radio_present;
- packet1.ethernet_present = packet_in.ethernet_present;
- packet1.ethernet_status = packet_in.ethernet_status;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_ARP_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ARP_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_arp_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_arp_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_arp_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
- mavlink_msg_arp_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_arp_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
- mavlink_msg_arp_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_arp_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_arp_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.yaw , packet1.pitch , packet1.roll , packet1.target_yaw , packet1.target_pitch , packet1.stepperX_pos , packet1.stepperX_delta , packet1.stepperX_speed , packet1.stepperY_pos , packet1.stepperY_delta , packet1.stepperY_speed , packet1.gps_latitude , packet1.gps_longitude , packet1.gps_height , packet1.gps_fix , packet1.main_radio_present , packet1.main_packet_tx_error_count , packet1.main_tx_bitrate , packet1.main_packet_rx_success_count , packet1.main_packet_rx_drop_count , packet1.main_rx_bitrate , packet1.main_rx_rssi , packet1.ethernet_present , packet1.ethernet_status , packet1.battery_voltage );
- mavlink_msg_arp_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("ARP_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ARP_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_set_antenna_coordinates_arp_tc(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_SET_ANTENNA_COORDINATES_ARP_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_antenna_coordinates_arp_tc_t packet_in = {
- 17.0,45.0
- };
- mavlink_set_antenna_coordinates_arp_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.latitude = packet_in.latitude;
- packet1.longitude = packet_in.longitude;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_antenna_coordinates_arp_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_antenna_coordinates_arp_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_antenna_coordinates_arp_tc_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude );
- mavlink_msg_set_antenna_coordinates_arp_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_antenna_coordinates_arp_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude );
- mavlink_msg_set_antenna_coordinates_arp_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_antenna_coordinates_arp_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_antenna_coordinates_arp_tc_send(MAVLINK_COMM_1 , packet1.latitude , packet1.longitude );
- mavlink_msg_set_antenna_coordinates_arp_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_ANTENNA_COORDINATES_ARP_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_ANTENNA_COORDINATES_ARP_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_rocket_coordinates_arp_tc(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_SET_ROCKET_COORDINATES_ARP_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_rocket_coordinates_arp_tc_t packet_in = {
- 17.0,45.0
- };
- mavlink_set_rocket_coordinates_arp_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.latitude = packet_in.latitude;
- packet1.longitude = packet_in.longitude;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_rocket_coordinates_arp_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_rocket_coordinates_arp_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_rocket_coordinates_arp_tc_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude );
- mavlink_msg_set_rocket_coordinates_arp_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_rocket_coordinates_arp_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude );
- mavlink_msg_set_rocket_coordinates_arp_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_rocket_coordinates_arp_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_rocket_coordinates_arp_tc_send(MAVLINK_COMM_1 , packet1.latitude , packet1.longitude );
- mavlink_msg_set_rocket_coordinates_arp_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_ROCKET_COORDINATES_ARP_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_ROCKET_COORDINATES_ARP_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_sys_tm(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_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_sys_tm_t packet_in = {
- 93372036854775807ULL,29,96,163,230,41,108
- };
- mavlink_sys_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.logger = packet_in.logger;
- packet1.event_broker = packet_in.event_broker;
- packet1.radio = packet_in.radio;
- packet1.pin_observer = packet_in.pin_observer;
- packet1.sensors = packet_in.sensors;
- packet1.board_scheduler = packet_in.board_scheduler;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SYS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SYS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sys_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_sys_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sys_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.logger , packet1.event_broker , packet1.radio , packet1.pin_observer , packet1.sensors , packet1.board_scheduler );
- mavlink_msg_sys_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sys_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.logger , packet1.event_broker , packet1.radio , packet1.pin_observer , packet1.sensors , packet1.board_scheduler );
- mavlink_msg_sys_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_sys_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sys_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.logger , packet1.event_broker , packet1.radio , packet1.pin_observer , packet1.sensors , packet1.board_scheduler );
- mavlink_msg_sys_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SYS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SYS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_fsm_tm(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_FSM_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_fsm_tm_t packet_in = {
- 93372036854775807ULL,29,96,163,230,41,108
- };
- mavlink_fsm_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.ada_state = packet_in.ada_state;
- packet1.abk_state = packet_in.abk_state;
- packet1.dpl_state = packet_in.dpl_state;
- packet1.fmm_state = packet_in.fmm_state;
- packet1.nas_state = packet_in.nas_state;
- packet1.wes_state = packet_in.wes_state;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_FSM_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FSM_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_fsm_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_fsm_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_fsm_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.ada_state , packet1.abk_state , packet1.dpl_state , packet1.fmm_state , packet1.nas_state , packet1.wes_state );
- mavlink_msg_fsm_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_fsm_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.ada_state , packet1.abk_state , packet1.dpl_state , packet1.fmm_state , packet1.nas_state , packet1.wes_state );
- mavlink_msg_fsm_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_fsm_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_fsm_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.ada_state , packet1.abk_state , packet1.dpl_state , packet1.fmm_state , packet1.nas_state , packet1.wes_state );
- mavlink_msg_fsm_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("FSM_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_FSM_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_logger_tm(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_LOGGER_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_logger_tm_t packet_in = {
- 93372036854775807ULL,963497880,963498088,963498296,963498504,963498712,963498920,963499128,963499336,963499544,19523
- };
- mavlink_logger_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.too_large_samples = packet_in.too_large_samples;
- packet1.dropped_samples = packet_in.dropped_samples;
- packet1.queued_samples = packet_in.queued_samples;
- packet1.buffers_filled = packet_in.buffers_filled;
- packet1.buffers_written = packet_in.buffers_written;
- packet1.writes_failed = packet_in.writes_failed;
- packet1.last_write_error = packet_in.last_write_error;
- packet1.average_write_time = packet_in.average_write_time;
- packet1.max_write_time = packet_in.max_write_time;
- packet1.log_number = packet_in.log_number;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_logger_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_logger_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_logger_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.log_number , packet1.too_large_samples , packet1.dropped_samples , packet1.queued_samples , packet1.buffers_filled , packet1.buffers_written , packet1.writes_failed , packet1.last_write_error , packet1.average_write_time , packet1.max_write_time );
- mavlink_msg_logger_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_logger_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.log_number , packet1.too_large_samples , packet1.dropped_samples , packet1.queued_samples , packet1.buffers_filled , packet1.buffers_written , packet1.writes_failed , packet1.last_write_error , packet1.average_write_time , packet1.max_write_time );
- mavlink_msg_logger_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_logger_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_logger_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.log_number , packet1.too_large_samples , packet1.dropped_samples , packet1.queued_samples , packet1.buffers_filled , packet1.buffers_written , packet1.writes_failed , packet1.last_write_error , packet1.average_write_time , packet1.max_write_time );
- mavlink_msg_logger_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("LOGGER_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_LOGGER_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_mavlink_stats_tm(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_MAVLINK_STATS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_mavlink_stats_tm_t packet_in = {
- 93372036854775807ULL,963497880,17859,17963,18067,18171,18275,199,10,77,144,211,22
- };
- mavlink_mavlink_stats_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.parse_state = packet_in.parse_state;
- packet1.n_send_queue = packet_in.n_send_queue;
- packet1.max_send_queue = packet_in.max_send_queue;
- packet1.n_send_errors = packet_in.n_send_errors;
- packet1.packet_rx_success_count = packet_in.packet_rx_success_count;
- packet1.packet_rx_drop_count = packet_in.packet_rx_drop_count;
- packet1.msg_received = packet_in.msg_received;
- packet1.buffer_overrun = packet_in.buffer_overrun;
- packet1.parse_error = packet_in.parse_error;
- packet1.packet_idx = packet_in.packet_idx;
- packet1.current_rx_seq = packet_in.current_rx_seq;
- packet1.current_tx_seq = packet_in.current_tx_seq;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mavlink_stats_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_mavlink_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mavlink_stats_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.n_send_queue , packet1.max_send_queue , packet1.n_send_errors , packet1.msg_received , packet1.buffer_overrun , packet1.parse_error , packet1.parse_state , packet1.packet_idx , packet1.current_rx_seq , packet1.current_tx_seq , packet1.packet_rx_success_count , packet1.packet_rx_drop_count );
- mavlink_msg_mavlink_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mavlink_stats_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.n_send_queue , packet1.max_send_queue , packet1.n_send_errors , packet1.msg_received , packet1.buffer_overrun , packet1.parse_error , packet1.parse_state , packet1.packet_idx , packet1.current_rx_seq , packet1.current_tx_seq , packet1.packet_rx_success_count , packet1.packet_rx_drop_count );
- mavlink_msg_mavlink_stats_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_mavlink_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mavlink_stats_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.n_send_queue , packet1.max_send_queue , packet1.n_send_errors , packet1.msg_received , packet1.buffer_overrun , packet1.parse_error , packet1.parse_state , packet1.packet_idx , packet1.current_rx_seq , packet1.current_tx_seq , packet1.packet_rx_success_count , packet1.packet_rx_drop_count );
- mavlink_msg_mavlink_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("MAVLINK_STATS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_MAVLINK_STATS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_task_stats_tm(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_TASK_STATS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_task_stats_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,18483,211
- };
- mavlink_task_stats_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.task_min = packet_in.task_min;
- packet1.task_max = packet_in.task_max;
- packet1.task_mean = packet_in.task_mean;
- packet1.task_stddev = packet_in.task_stddev;
- packet1.task_period = packet_in.task_period;
- packet1.task_id = packet_in.task_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_task_stats_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_task_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_task_stats_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.task_id , packet1.task_period , packet1.task_min , packet1.task_max , packet1.task_mean , packet1.task_stddev );
- mavlink_msg_task_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_task_stats_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.task_id , packet1.task_period , packet1.task_min , packet1.task_max , packet1.task_mean , packet1.task_stddev );
- mavlink_msg_task_stats_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_task_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_task_stats_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.task_id , packet1.task_period , packet1.task_min , packet1.task_max , packet1.task_mean , packet1.task_stddev );
- mavlink_msg_task_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("TASK_STATS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_TASK_STATS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_ada_tm(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_ADA_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ada_tm_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,161
- };
- mavlink_ada_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.kalman_x0 = packet_in.kalman_x0;
- packet1.kalman_x1 = packet_in.kalman_x1;
- packet1.kalman_x2 = packet_in.kalman_x2;
- packet1.vertical_speed = packet_in.vertical_speed;
- packet1.msl_altitude = packet_in.msl_altitude;
- packet1.ref_pressure = packet_in.ref_pressure;
- packet1.ref_altitude = packet_in.ref_altitude;
- packet1.ref_temperature = packet_in.ref_temperature;
- packet1.msl_pressure = packet_in.msl_pressure;
- packet1.msl_temperature = packet_in.msl_temperature;
- packet1.dpl_altitude = packet_in.dpl_altitude;
- 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_ADA_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ADA_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ada_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ada_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ada_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.vertical_speed , packet1.msl_altitude , packet1.ref_pressure , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_pressure , packet1.msl_temperature , packet1.dpl_altitude );
- mavlink_msg_ada_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ada_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.vertical_speed , packet1.msl_altitude , packet1.ref_pressure , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_pressure , packet1.msl_temperature , packet1.dpl_altitude );
- mavlink_msg_ada_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ada_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ada_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.vertical_speed , packet1.msl_altitude , packet1.ref_pressure , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_pressure , packet1.msl_temperature , packet1.dpl_altitude );
- mavlink_msg_ada_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("ADA_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ADA_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_nas_tm(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_NAS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_nas_tm_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,437.0,465.0,493.0,521.0,233
- };
- mavlink_nas_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.nas_n = packet_in.nas_n;
- packet1.nas_e = packet_in.nas_e;
- packet1.nas_d = packet_in.nas_d;
- packet1.nas_vn = packet_in.nas_vn;
- packet1.nas_ve = packet_in.nas_ve;
- packet1.nas_vd = packet_in.nas_vd;
- packet1.nas_qx = packet_in.nas_qx;
- packet1.nas_qy = packet_in.nas_qy;
- packet1.nas_qz = packet_in.nas_qz;
- packet1.nas_qw = packet_in.nas_qw;
- packet1.nas_bias_x = packet_in.nas_bias_x;
- packet1.nas_bias_y = packet_in.nas_bias_y;
- packet1.nas_bias_z = packet_in.nas_bias_z;
- packet1.ref_pressure = packet_in.ref_pressure;
- packet1.ref_temperature = packet_in.ref_temperature;
- packet1.ref_latitude = packet_in.ref_latitude;
- packet1.ref_longitude = packet_in.ref_longitude;
- 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_NAS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NAS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nas_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_nas_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nas_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.ref_pressure , packet1.ref_temperature , packet1.ref_latitude , packet1.ref_longitude );
- mavlink_msg_nas_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nas_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.ref_pressure , packet1.ref_temperature , packet1.ref_latitude , packet1.ref_longitude );
- mavlink_msg_nas_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_nas_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nas_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.ref_pressure , packet1.ref_temperature , packet1.ref_latitude , packet1.ref_longitude );
- mavlink_msg_nas_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("NAS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_NAS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_mea_tm(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_MEA_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_mea_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,89
- };
- mavlink_mea_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.kalman_x0 = packet_in.kalman_x0;
- packet1.kalman_x1 = packet_in.kalman_x1;
- packet1.kalman_x2 = packet_in.kalman_x2;
- packet1.mass = packet_in.mass;
- packet1.corrected_pressure = packet_in.corrected_pressure;
- 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_MEA_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MEA_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mea_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_mea_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mea_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.mass , packet1.corrected_pressure );
- mavlink_msg_mea_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mea_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.mass , packet1.corrected_pressure );
- mavlink_msg_mea_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_mea_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mea_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.mass , packet1.corrected_pressure );
- mavlink_msg_mea_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("MEA_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_MEA_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_rocket_flight_tm(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_ROCKET_FLIGHT_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_rocket_flight_tm_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,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,1081.0,1109.0,1137.0,241,52,119,186,253,64,131,198,9,76,143,210
- };
- mavlink_rocket_flight_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.pressure_ada = packet_in.pressure_ada;
- packet1.pressure_digi = packet_in.pressure_digi;
- packet1.pressure_static = packet_in.pressure_static;
- packet1.pressure_dpl = packet_in.pressure_dpl;
- packet1.airspeed_pitot = packet_in.airspeed_pitot;
- packet1.altitude_agl = packet_in.altitude_agl;
- packet1.ada_vert_speed = packet_in.ada_vert_speed;
- packet1.mea_mass = packet_in.mea_mass;
- packet1.acc_x = packet_in.acc_x;
- packet1.acc_y = packet_in.acc_y;
- packet1.acc_z = packet_in.acc_z;
- packet1.gyro_x = packet_in.gyro_x;
- packet1.gyro_y = packet_in.gyro_y;
- packet1.gyro_z = packet_in.gyro_z;
- packet1.mag_x = packet_in.mag_x;
- packet1.mag_y = packet_in.mag_y;
- packet1.mag_z = packet_in.mag_z;
- packet1.gps_lat = packet_in.gps_lat;
- packet1.gps_lon = packet_in.gps_lon;
- packet1.gps_alt = packet_in.gps_alt;
- packet1.abk_angle = packet_in.abk_angle;
- packet1.nas_n = packet_in.nas_n;
- packet1.nas_e = packet_in.nas_e;
- packet1.nas_d = packet_in.nas_d;
- packet1.nas_vn = packet_in.nas_vn;
- packet1.nas_ve = packet_in.nas_ve;
- packet1.nas_vd = packet_in.nas_vd;
- packet1.nas_qx = packet_in.nas_qx;
- packet1.nas_qy = packet_in.nas_qy;
- packet1.nas_qz = packet_in.nas_qz;
- packet1.nas_qw = packet_in.nas_qw;
- packet1.nas_bias_x = packet_in.nas_bias_x;
- packet1.nas_bias_y = packet_in.nas_bias_y;
- packet1.nas_bias_z = packet_in.nas_bias_z;
- packet1.pin_quick_connector = packet_in.pin_quick_connector;
- packet1.battery_voltage = packet_in.battery_voltage;
- packet1.cam_battery_voltage = packet_in.cam_battery_voltage;
- packet1.current_consumption = packet_in.current_consumption;
- packet1.temperature = packet_in.temperature;
- packet1.ada_state = packet_in.ada_state;
- packet1.fmm_state = packet_in.fmm_state;
- packet1.dpl_state = packet_in.dpl_state;
- packet1.abk_state = packet_in.abk_state;
- packet1.nas_state = packet_in.nas_state;
- packet1.mea_state = packet_in.mea_state;
- packet1.gps_fix = packet_in.gps_fix;
- packet1.pin_launch = packet_in.pin_launch;
- packet1.pin_nosecone = packet_in.pin_nosecone;
- packet1.pin_expulsion = packet_in.pin_expulsion;
- packet1.cutter_presence = packet_in.cutter_presence;
- packet1.logger_error = packet_in.logger_error;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_flight_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_rocket_flight_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_quick_connector , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.temperature , packet1.logger_error );
- mavlink_msg_rocket_flight_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_quick_connector , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.temperature , packet1.logger_error );
- mavlink_msg_rocket_flight_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_rocket_flight_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.mea_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.mea_mass , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_quick_connector , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.temperature , packet1.logger_error );
- mavlink_msg_rocket_flight_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("ROCKET_FLIGHT_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ROCKET_FLIGHT_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_payload_flight_tm(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_PAYLOAD_FLIGHT_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_payload_flight_tm_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,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,1081.0,217,28,95,162,229,40,107
- };
- mavlink_payload_flight_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.pressure_digi = packet_in.pressure_digi;
- packet1.pressure_static = packet_in.pressure_static;
- packet1.airspeed_pitot = packet_in.airspeed_pitot;
- packet1.altitude_agl = packet_in.altitude_agl;
- packet1.acc_x = packet_in.acc_x;
- packet1.acc_y = packet_in.acc_y;
- packet1.acc_z = packet_in.acc_z;
- packet1.gyro_x = packet_in.gyro_x;
- packet1.gyro_y = packet_in.gyro_y;
- packet1.gyro_z = packet_in.gyro_z;
- packet1.mag_x = packet_in.mag_x;
- packet1.mag_y = packet_in.mag_y;
- packet1.mag_z = packet_in.mag_z;
- packet1.gps_lat = packet_in.gps_lat;
- packet1.gps_lon = packet_in.gps_lon;
- packet1.gps_alt = packet_in.gps_alt;
- packet1.left_servo_angle = packet_in.left_servo_angle;
- packet1.right_servo_angle = packet_in.right_servo_angle;
- packet1.nas_n = packet_in.nas_n;
- packet1.nas_e = packet_in.nas_e;
- packet1.nas_d = packet_in.nas_d;
- packet1.nas_vn = packet_in.nas_vn;
- packet1.nas_ve = packet_in.nas_ve;
- packet1.nas_vd = packet_in.nas_vd;
- packet1.nas_qx = packet_in.nas_qx;
- packet1.nas_qy = packet_in.nas_qy;
- packet1.nas_qz = packet_in.nas_qz;
- packet1.nas_qw = packet_in.nas_qw;
- packet1.nas_bias_x = packet_in.nas_bias_x;
- packet1.nas_bias_y = packet_in.nas_bias_y;
- packet1.nas_bias_z = packet_in.nas_bias_z;
- packet1.wes_n = packet_in.wes_n;
- packet1.wes_e = packet_in.wes_e;
- packet1.battery_voltage = packet_in.battery_voltage;
- packet1.cam_battery_voltage = packet_in.cam_battery_voltage;
- packet1.current_consumption = packet_in.current_consumption;
- packet1.temperature = packet_in.temperature;
- packet1.fmm_state = packet_in.fmm_state;
- packet1.nas_state = packet_in.nas_state;
- packet1.wes_state = packet_in.wes_state;
- packet1.gps_fix = packet_in.gps_fix;
- packet1.pin_nosecone = packet_in.pin_nosecone;
- packet1.cutter_presence = packet_in.cutter_presence;
- packet1.logger_error = packet_in.logger_error;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_flight_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_payload_flight_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.cutter_presence , packet1.temperature , packet1.logger_error );
- mavlink_msg_payload_flight_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.cutter_presence , packet1.temperature , packet1.logger_error );
- mavlink_msg_payload_flight_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_payload_flight_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.fmm_state , packet1.nas_state , packet1.wes_state , packet1.pressure_digi , packet1.pressure_static , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.wes_n , packet1.wes_e , packet1.pin_nosecone , packet1.battery_voltage , packet1.cam_battery_voltage , packet1.current_consumption , packet1.cutter_presence , packet1.temperature , packet1.logger_error );
- mavlink_msg_payload_flight_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("PAYLOAD_FLIGHT_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_rocket_stats_tm(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_ROCKET_STATS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_rocket_stats_tm_t packet_in = {
- 93372036854775807ULL,93372036854776311ULL,93372036854776815ULL,93372036854777319ULL,93372036854777823ULL,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,605.0,963502040
- };
- mavlink_rocket_stats_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.liftoff_ts = packet_in.liftoff_ts;
- packet1.liftoff_max_acc_ts = packet_in.liftoff_max_acc_ts;
- packet1.dpl_ts = packet_in.dpl_ts;
- packet1.max_z_speed_ts = packet_in.max_z_speed_ts;
- packet1.apogee_ts = packet_in.apogee_ts;
- packet1.liftoff_max_acc = packet_in.liftoff_max_acc;
- packet1.dpl_max_acc = packet_in.dpl_max_acc;
- packet1.max_z_speed = packet_in.max_z_speed;
- packet1.max_airspeed_pitot = packet_in.max_airspeed_pitot;
- packet1.max_speed_altitude = packet_in.max_speed_altitude;
- packet1.apogee_lat = packet_in.apogee_lat;
- packet1.apogee_lon = packet_in.apogee_lon;
- packet1.apogee_alt = packet_in.apogee_alt;
- packet1.min_pressure = packet_in.min_pressure;
- packet1.ada_min_pressure = packet_in.ada_min_pressure;
- packet1.dpl_vane_max_pressure = packet_in.dpl_vane_max_pressure;
- packet1.cpu_load = packet_in.cpu_load;
- packet1.free_heap = packet_in.free_heap;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_stats_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_rocket_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_stats_tm_pack(system_id, component_id, &msg , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.ada_min_pressure , packet1.dpl_vane_max_pressure , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_rocket_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_stats_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.ada_min_pressure , packet1.dpl_vane_max_pressure , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_rocket_stats_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_rocket_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_stats_tm_send(MAVLINK_COMM_1 , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.ada_min_pressure , packet1.dpl_vane_max_pressure , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_rocket_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("ROCKET_STATS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ROCKET_STATS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_payload_stats_tm(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_PAYLOAD_STATS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_payload_stats_tm_t packet_in = {
- 93372036854775807ULL,93372036854776311ULL,93372036854776815ULL,93372036854777319ULL,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,963501208
- };
- mavlink_payload_stats_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.liftoff_max_acc_ts = packet_in.liftoff_max_acc_ts;
- packet1.dpl_ts = packet_in.dpl_ts;
- packet1.max_z_speed_ts = packet_in.max_z_speed_ts;
- packet1.apogee_ts = packet_in.apogee_ts;
- packet1.liftoff_max_acc = packet_in.liftoff_max_acc;
- packet1.dpl_max_acc = packet_in.dpl_max_acc;
- packet1.max_z_speed = packet_in.max_z_speed;
- packet1.max_airspeed_pitot = packet_in.max_airspeed_pitot;
- packet1.max_speed_altitude = packet_in.max_speed_altitude;
- packet1.apogee_lat = packet_in.apogee_lat;
- packet1.apogee_lon = packet_in.apogee_lon;
- packet1.apogee_alt = packet_in.apogee_alt;
- packet1.min_pressure = packet_in.min_pressure;
- packet1.cpu_load = packet_in.cpu_load;
- packet1.free_heap = packet_in.free_heap;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_stats_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_payload_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_stats_tm_pack(system_id, component_id, &msg , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_payload_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_stats_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_payload_stats_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_payload_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_stats_tm_send(MAVLINK_COMM_1 , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_payload_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("PAYLOAD_STATS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_PAYLOAD_STATS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_gse_tm(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_GSE_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_gse_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,101,168,235,46,113,180,247,58,125,192
- };
- mavlink_gse_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.loadcell_rocket = packet_in.loadcell_rocket;
- packet1.loadcell_vessel = packet_in.loadcell_vessel;
- packet1.filling_pressure = packet_in.filling_pressure;
- packet1.vessel_pressure = packet_in.vessel_pressure;
- packet1.battery_voltage = packet_in.battery_voltage;
- packet1.current_consumption = packet_in.current_consumption;
- packet1.arming_state = packet_in.arming_state;
- packet1.filling_valve_state = packet_in.filling_valve_state;
- packet1.venting_valve_state = packet_in.venting_valve_state;
- packet1.release_valve_state = packet_in.release_valve_state;
- packet1.main_valve_state = packet_in.main_valve_state;
- packet1.ignition_state = packet_in.ignition_state;
- packet1.tars_state = packet_in.tars_state;
- packet1.main_board_status = packet_in.main_board_status;
- packet1.payload_board_status = packet_in.payload_board_status;
- packet1.motor_board_status = packet_in.motor_board_status;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_GSE_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GSE_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gse_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_gse_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gse_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.loadcell_rocket , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.ignition_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption , packet1.main_board_status , packet1.payload_board_status , packet1.motor_board_status );
- mavlink_msg_gse_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gse_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.loadcell_rocket , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.ignition_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption , packet1.main_board_status , packet1.payload_board_status , packet1.motor_board_status );
- mavlink_msg_gse_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_gse_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gse_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.loadcell_rocket , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.ignition_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption , packet1.main_board_status , packet1.payload_board_status , packet1.motor_board_status );
- mavlink_msg_gse_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("GSE_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_GSE_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_motor_tm(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_MOTOR_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_motor_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,101,168,235
- };
- mavlink_motor_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.top_tank_pressure = packet_in.top_tank_pressure;
- packet1.bottom_tank_pressure = packet_in.bottom_tank_pressure;
- packet1.combustion_chamber_pressure = packet_in.combustion_chamber_pressure;
- packet1.tank_temperature = packet_in.tank_temperature;
- packet1.battery_voltage = packet_in.battery_voltage;
- packet1.current_consumption = packet_in.current_consumption;
- packet1.floating_level = packet_in.floating_level;
- packet1.main_valve_state = packet_in.main_valve_state;
- packet1.venting_valve_state = packet_in.venting_valve_state;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MOTOR_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_motor_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_motor_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_motor_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.floating_level , packet1.tank_temperature , packet1.main_valve_state , packet1.venting_valve_state , packet1.battery_voltage , packet1.current_consumption );
- mavlink_msg_motor_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_motor_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.floating_level , packet1.tank_temperature , packet1.main_valve_state , packet1.venting_valve_state , packet1.battery_voltage , packet1.current_consumption );
- mavlink_msg_motor_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_motor_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_motor_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.top_tank_pressure , packet1.bottom_tank_pressure , packet1.combustion_chamber_pressure , packet1.floating_level , packet1.tank_temperature , packet1.main_valve_state , packet1.venting_valve_state , packet1.battery_voltage , packet1.current_consumption );
- mavlink_msg_motor_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("MOTOR_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_MOTOR_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_lyra(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
-{
- mavlink_test_ping_tc(system_id, component_id, last_msg);
- mavlink_test_command_tc(system_id, component_id, last_msg);
- mavlink_test_system_tm_request_tc(system_id, component_id, last_msg);
- mavlink_test_sensor_tm_request_tc(system_id, component_id, last_msg);
- mavlink_test_servo_tm_request_tc(system_id, component_id, last_msg);
- mavlink_test_set_servo_angle_tc(system_id, component_id, last_msg);
- mavlink_test_wiggle_servo_tc(system_id, component_id, last_msg);
- mavlink_test_reset_servo_tc(system_id, component_id, last_msg);
- mavlink_test_set_reference_altitude_tc(system_id, component_id, last_msg);
- mavlink_test_set_reference_temperature_tc(system_id, component_id, last_msg);
- mavlink_test_set_orientation_tc(system_id, component_id, last_msg);
- mavlink_test_set_coordinates_tc(system_id, component_id, last_msg);
- mavlink_test_raw_event_tc(system_id, component_id, last_msg);
- mavlink_test_set_deployment_altitude_tc(system_id, component_id, last_msg);
- mavlink_test_set_target_coordinates_tc(system_id, component_id, last_msg);
- mavlink_test_set_algorithm_tc(system_id, component_id, last_msg);
- mavlink_test_set_atomic_valve_timing_tc(system_id, component_id, last_msg);
- mavlink_test_set_valve_maximum_aperture_tc(system_id, component_id, last_msg);
- mavlink_test_conrig_state_tc(system_id, component_id, last_msg);
- mavlink_test_set_ignition_time_tc(system_id, component_id, last_msg);
- mavlink_test_set_stepper_angle_tc(system_id, component_id, last_msg);
- mavlink_test_set_stepper_steps_tc(system_id, component_id, last_msg);
- mavlink_test_ack_tm(system_id, component_id, last_msg);
- mavlink_test_nack_tm(system_id, component_id, last_msg);
- mavlink_test_gps_tm(system_id, component_id, last_msg);
- mavlink_test_imu_tm(system_id, component_id, last_msg);
- mavlink_test_pressure_tm(system_id, component_id, last_msg);
- mavlink_test_adc_tm(system_id, component_id, last_msg);
- mavlink_test_voltage_tm(system_id, component_id, last_msg);
- mavlink_test_current_tm(system_id, component_id, last_msg);
- mavlink_test_temp_tm(system_id, component_id, last_msg);
- mavlink_test_load_tm(system_id, component_id, last_msg);
- mavlink_test_attitude_tm(system_id, component_id, last_msg);
- mavlink_test_sensor_state_tm(system_id, component_id, last_msg);
- mavlink_test_servo_tm(system_id, component_id, last_msg);
- mavlink_test_pin_tm(system_id, component_id, last_msg);
- mavlink_test_receiver_tm(system_id, component_id, last_msg);
- mavlink_test_arp_tm(system_id, component_id, last_msg);
- mavlink_test_set_antenna_coordinates_arp_tc(system_id, component_id, last_msg);
- mavlink_test_set_rocket_coordinates_arp_tc(system_id, component_id, last_msg);
- mavlink_test_sys_tm(system_id, component_id, last_msg);
- mavlink_test_fsm_tm(system_id, component_id, last_msg);
- mavlink_test_logger_tm(system_id, component_id, last_msg);
- mavlink_test_mavlink_stats_tm(system_id, component_id, last_msg);
- mavlink_test_task_stats_tm(system_id, component_id, last_msg);
- mavlink_test_ada_tm(system_id, component_id, last_msg);
- mavlink_test_nas_tm(system_id, component_id, last_msg);
- mavlink_test_mea_tm(system_id, component_id, last_msg);
- mavlink_test_rocket_flight_tm(system_id, component_id, last_msg);
- mavlink_test_payload_flight_tm(system_id, component_id, last_msg);
- mavlink_test_rocket_stats_tm(system_id, component_id, last_msg);
- mavlink_test_payload_stats_tm(system_id, component_id, last_msg);
- mavlink_test_gse_tm(system_id, component_id, last_msg);
- mavlink_test_motor_tm(system_id, component_id, last_msg);
-}
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // LYRA_TESTSUITE_H
diff --git a/mavlink_lib/lyra/version.h b/mavlink_lib/lyra/version.h
deleted file mode 100644
index 3eba20e8566c37c8f5823d77a2ed5b11049235d7..0000000000000000000000000000000000000000
--- a/mavlink_lib/lyra/version.h
+++ /dev/null
@@ -1,14 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol built from lyra.xml
- * @see http://mavlink.org
- */
-#pragma once
-
-#ifndef MAVLINK_VERSION_H
-#define MAVLINK_VERSION_H
-
-#define MAVLINK_BUILD_DATE "Sun Dec 10 2023"
-#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
-#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 176
-
-#endif // MAVLINK_VERSION_H
diff --git a/mavlink_lib/mavlink_conversions.h b/mavlink_lib/mavlink_conversions.h
deleted file mode 100644
index d45e6bab399e13c48fb64cd1ed3e57d5ce9241c2..0000000000000000000000000000000000000000
--- a/mavlink_lib/mavlink_conversions.h
+++ /dev/null
@@ -1,216 +0,0 @@
-#ifndef _MAVLINK_CONVERSIONS_H_
-#define _MAVLINK_CONVERSIONS_H_
-
-#ifndef MAVLINK_NO_CONVERSION_HELPERS
-
-/* enable math defines on Windows */
-#ifdef _MSC_VER
-#ifndef _USE_MATH_DEFINES
-#define _USE_MATH_DEFINES
-#endif
-#endif
-#include <math.h>
-
-#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 <thomasgubler@gmail.com>
- */
-
-
-/**
- * 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 = quaternion[0];
- double b = quaternion[1];
- double c = quaternion[2];
- double d = 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 = asin(-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
-
-#endif // _MAVLINK_CONVERSIONS_H_
-
diff --git a/mavlink_lib/mavlink_helpers.h b/mavlink_lib/mavlink_helpers.h
deleted file mode 100644
index 22e5d406c794010a8809ed2d9fb0765d9a7e06e5..0000000000000000000000000000000000000000
--- a/mavlink_lib/mavlink_helpers.h
+++ /dev/null
@@ -1,659 +0,0 @@
-#ifndef _MAVLINK_HELPERS_H_
-#define _MAVLINK_HELPERS_H_
-
-#include "string.h"
-#include "checksum.h"
-#include "mavlink_types.h"
-#include "mavlink_conversions.h"
-
-#ifndef MAVLINK_HELPER
-#define MAVLINK_HELPER
-#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
-
-/**
- * @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;
-}
-
-/**
- * @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
- */
-#if MAVLINK_CRC_EXTRA
-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)
-#else
-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 length)
-#endif
-{
- // This is only used for the v2 protocol and we silence it here
- (void)min_length;
- // This code part is the same for all messages;
- msg->magic = MAVLINK_STX;
- msg->len = length;
- msg->sysid = system_id;
- msg->compid = component_id;
- // One sequence number per channel
- msg->seq = mavlink_get_channel_status(chan)->current_tx_seq;
- mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1;
- msg->checksum = crc_calculate(((const uint8_t*)(msg)) + 3, MAVLINK_CORE_HEADER_LEN);
- crc_accumulate_buffer(&msg->checksum, _MAV_PAYLOAD(msg), msg->len);
-#if MAVLINK_CRC_EXTRA
- crc_accumulate(crc_extra, &msg->checksum);
-#endif
- mavlink_ck_a(msg) = (uint8_t)(msg->checksum & 0xFF);
- mavlink_ck_b(msg) = (uint8_t)(msg->checksum >> 8);
-
- return length + MAVLINK_NUM_NON_PAYLOAD_BYTES;
-}
-
-
-/**
- * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel
- */
-#if MAVLINK_CRC_EXTRA
-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);
-}
-#else
-MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t length)
-{
- return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length);
-}
-#endif
-
-#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
- */
-#if MAVLINK_CRC_EXTRA
-MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
- uint8_t min_length, uint8_t length, uint8_t crc_extra)
-#else
-MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length)
-#endif
-{
- uint16_t checksum;
- uint8_t buf[MAVLINK_NUM_HEADER_BYTES];
- uint8_t ck[2];
- mavlink_status_t *status = mavlink_get_channel_status(chan);
- buf[0] = MAVLINK_STX;
- buf[1] = length;
- buf[2] = status->current_tx_seq;
- buf[3] = mavlink_system.sysid;
- buf[4] = mavlink_system.compid;
- buf[5] = msgid;
- status->current_tx_seq++;
- checksum = crc_calculate((const uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN);
- crc_accumulate_buffer(&checksum, packet, length);
-#if MAVLINK_CRC_EXTRA
- crc_accumulate(crc_extra, &checksum);
-#endif
- ck[0] = (uint8_t)(checksum & 0xFF);
- ck[1] = (uint8_t)(checksum >> 8);
-
- MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length);
- _mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES);
- _mavlink_send_uart(chan, packet, length);
- _mavlink_send_uart(chan, (const char *)ck, 2);
- MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length);
-}
-
-/**
- * @brief re-send a message over a uart channel
- * this is more stack efficient than re-marshalling the message
- */
-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
-
- MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len);
- _mavlink_send_uart(chan, (const char *)&msg->magic, MAVLINK_NUM_HEADER_BYTES);
- _mavlink_send_uart(chan, _MAV_PAYLOAD(msg), msg->len);
- _mavlink_send_uart(chan, (const char *)ck, 2);
- MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->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 *buffer, const mavlink_message_t *msg)
-{
- memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len);
-
- uint8_t *ck = buffer + (MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len);
-
- ck[0] = (uint8_t)(msg->checksum & 0xFF);
- ck[1] = (uint8_t)(msg->checksum >> 8);
-
- return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->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)
-{
- crc_init(&msg->checksum);
-}
-
-MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
-{
- crc_accumulate(c, &msg->checksum);
-}
-
-/**
- * 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)
-{
- /*
- default message crc function. You can override this per-system to
- put this data in a different memory segment
- */
-#if MAVLINK_CRC_EXTRA
-#ifndef MAVLINK_MESSAGE_CRC
- static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS;
-#define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid]
-#endif
-#endif
-
- /* 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.
- */
-#ifdef MAVLINK_CHECK_MESSAGE_LENGTH
-#ifndef MAVLINK_MESSAGE_LENGTH
- static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS;
-#define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid]
-#endif
-#endif
-
- int bufferIndex = 0;
-
- 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;
- 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++;
- status->parse_error++;
- 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);
- status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH;
- }
- break;
-
- case MAVLINK_PARSE_STATE_GOT_LENGTH:
- 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:
-#ifdef MAVLINK_CHECK_MESSAGE_LENGTH
- if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(c))
- {
- status->parse_error++;
- status->parse_state = MAVLINK_PARSE_STATE_IDLE;
- break;
- }
-#endif
- rxmsg->msgid = c;
- mavlink_update_checksum(rxmsg, c);
- if (rxmsg->len == 0)
- {
- status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
- }
- else
- {
- status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID;
- }
- break;
-
- case MAVLINK_PARSE_STATE_GOT_MSGID:
- _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:
-#if MAVLINK_CRC_EXTRA
- mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid));
-#endif
- if (c != (rxmsg->checksum & 0xFF)) {
- status->parse_state = MAVLINK_PARSE_STATE_GOT_BAD_CRC1;
- } else {
- status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1;
- }
- _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c;
- 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;
- }
- status->parse_state = MAVLINK_PARSE_STATE_IDLE;
- _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c;
- memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
- break;
- }
-
- bufferIndex++;
- // 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++;
- }
-
- r_message->len = rxmsg->len; // Provide visibility on how far we are into current msg
- 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;
- 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
- */
- r_message->checksum = _MAV_PAYLOAD(rxmsg)[status->packet_idx] | (_MAV_PAYLOAD(rxmsg)[status->packet_idx+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, the message data else
- * @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.h>
- *
- * 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);
-}
-
-
-/**
- * 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.h>
- *
- * 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) {
- // 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);
- status->parse_error++;
- 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
-
-#endif /* _MAVLINK_HELPERS_H_ */
diff --git a/mavlink_lib/mavlink_types.h b/mavlink_lib/mavlink_types.h
deleted file mode 100644
index 5b577a33a6cf7a52855f527f5ebffae947d5e5b7..0000000000000000000000000000000000000000
--- a/mavlink_lib/mavlink_types.h
+++ /dev/null
@@ -1,230 +0,0 @@
-#ifndef MAVLINK_TYPES_H_
-#define MAVLINK_TYPES_H_
-
-// 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 <stdint.h>
-
-// 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 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte)
-#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum
-#define MAVLINK_NUM_CHECKSUM_BYTES 2
-#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES)
-
-#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length
-
-#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255
-#define MAVLINK_EXTENDED_HEADER_LEN 14
-
-#if (defined _MSC_VER) || ((defined __APPLE__) && (defined __MACH__)) || (defined __linux__)
- /* full fledged 32bit++ OS */
- #define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507
-#else
- /* small microcontrollers */
- #define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048
-#endif
-
-#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)
-
-
-/**
- * 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 seq; ///< Sequence of packet
- uint8_t sysid; ///< ID of message sender system/aircraft
- uint8_t compid; ///< ID of the message sender component
- uint8_t msgid; ///< ID of message in payload
- uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
-}) mavlink_message_t;
-
-MAVPACKED(
-typedef struct __mavlink_extended_message {
- mavlink_message_t base_msg;
- int32_t extended_payload_len; ///< Length of extended payload if any
- uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];
-}) mavlink_extended_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 {
- 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_SEQ,
- MAVLINK_PARSE_STATE_GOT_LENGTH,
- MAVLINK_PARSE_STATE_GOT_SYSID,
- MAVLINK_PARSE_STATE_GOT_COMPID,
- MAVLINK_PARSE_STATE_GOT_MSGID,
- MAVLINK_PARSE_STATE_GOT_PAYLOAD,
- MAVLINK_PARSE_STATE_GOT_CRC1,
- MAVLINK_PARSE_STATE_GOT_BAD_CRC1
-} 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_t;
-
-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
-} mavlink_status_t;
-
-#define MAVLINK_BIG_ENDIAN 0
-#define MAVLINK_LITTLE_ENDIAN 1
-
-#endif /* MAVLINK_TYPES_H_ */
diff --git a/mavlink_lib/protocol.h b/mavlink_lib/protocol.h
deleted file mode 100644
index 34749d9ba7106edf5de0486145fdde0e31aeec55..0000000000000000000000000000000000000000
--- a/mavlink_lib/protocol.h
+++ /dev/null
@@ -1,339 +0,0 @@
-#ifndef _MAVLINK_PROTOCOL_H_
-#define _MAVLINK_PROTOCOL_H_
-
-#include "string.h"
-#include "mavlink_types.h"
-
-/*
- If you want MAVLink on a system that is native big-endian,
- you need to define NATIVE_BIG_ENDIAN
-*/
-#ifdef NATIVE_BIG_ENDIAN
-# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN)
-#else
-# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN)
-#endif
-
-#ifndef MAVLINK_STACK_BUFFER
-#define MAVLINK_STACK_BUFFER 0
-#endif
-
-#ifndef MAVLINK_AVOID_GCC_STACK_BUG
-# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__)
-#endif
-
-#ifndef MAVLINK_ASSERT
-#define MAVLINK_ASSERT(x)
-#endif
-
-#ifndef MAVLINK_START_UART_SEND
-#define MAVLINK_START_UART_SEND(chan, length)
-#endif
-
-#ifndef MAVLINK_END_UART_SEND
-#define MAVLINK_END_UART_SEND(chan, length)
-#endif
-
-/* option to provide alternative implementation of mavlink_helpers.h */
-#ifdef MAVLINK_SEPARATE_HELPERS
-
- #define MAVLINK_HELPER
-
- /* decls in sync with those in mavlink_helpers.h */
- #ifndef MAVLINK_GET_CHANNEL_STATUS
- MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan);
- #endif
- MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan);
- #if MAVLINK_CRC_EXTRA
- 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_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);
- #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
- MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
- uint8_t min_length, uint8_t length, uint8_t crc_extra);
- #endif
- #else
- 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 length);
- MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t length);
- #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
- MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length);
- #endif
- #endif // MAVLINK_CRC_EXTRA
- MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg);
- MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg);
- MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c);
- 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);
- MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
- MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
- 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);
- #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
- MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
- MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg);
- #endif
-
-#else
-
- #define MAVLINK_HELPER static inline
- #include "mavlink_helpers.h"
-
-#endif // MAVLINK_SEPARATE_HELPERS
-
-/**
- * @brief Get the required buffer size for this message
- */
-static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg)
-{
- return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES;
-}
-
-#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<array_length; i++) { \
- _mav_put_## TYPE (buf, wire_offset+(i*sizeof(TYPE)), b[i]); \
- } \
- } \
-}
-#else
-#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) \
-{ \
- mav_array_memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \
-}
-#endif
-
-_MAV_PUT_ARRAY(uint16_t, u16)
-_MAV_PUT_ARRAY(uint32_t, u32)
-_MAV_PUT_ARRAY(uint64_t, u64)
-_MAV_PUT_ARRAY(int16_t, i16)
-_MAV_PUT_ARRAY(int32_t, i32)
-_MAV_PUT_ARRAY(int64_t, i64)
-_MAV_PUT_ARRAY(float, f)
-_MAV_PUT_ARRAY(double, d)
-
-#define _MAV_RETURN_char(msg, wire_offset) (char)_MAV_PAYLOAD(msg)[wire_offset]
-#define _MAV_RETURN_int8_t(msg, wire_offset) (int8_t)_MAV_PAYLOAD(msg)[wire_offset]
-#define _MAV_RETURN_uint8_t(msg, wire_offset) (uint8_t)_MAV_PAYLOAD(msg)[wire_offset]
-
-#if MAVLINK_NEED_BYTE_SWAP
-#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
-static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
-{ TYPE r; byte_swap_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
-
-_MAV_MSG_RETURN_TYPE(uint16_t, 2)
-_MAV_MSG_RETURN_TYPE(int16_t, 2)
-_MAV_MSG_RETURN_TYPE(uint32_t, 4)
-_MAV_MSG_RETURN_TYPE(int32_t, 4)
-_MAV_MSG_RETURN_TYPE(uint64_t, 8)
-_MAV_MSG_RETURN_TYPE(int64_t, 8)
-_MAV_MSG_RETURN_TYPE(float, 4)
-_MAV_MSG_RETURN_TYPE(double, 8)
-
-#elif !MAVLINK_ALIGNED_FIELDS
-#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
-static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
-{ TYPE r; byte_copy_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
-
-_MAV_MSG_RETURN_TYPE(uint16_t, 2)
-_MAV_MSG_RETURN_TYPE(int16_t, 2)
-_MAV_MSG_RETURN_TYPE(uint32_t, 4)
-_MAV_MSG_RETURN_TYPE(int32_t, 4)
-_MAV_MSG_RETURN_TYPE(uint64_t, 8)
-_MAV_MSG_RETURN_TYPE(int64_t, 8)
-_MAV_MSG_RETURN_TYPE(float, 4)
-_MAV_MSG_RETURN_TYPE(double, 8)
-#else // nicely aligned, no swap
-#define _MAV_MSG_RETURN_TYPE(TYPE) \
-static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
-{ return *(const TYPE *)(&_MAV_PAYLOAD(msg)[ofs]);}
-
-_MAV_MSG_RETURN_TYPE(uint16_t)
-_MAV_MSG_RETURN_TYPE(int16_t)
-_MAV_MSG_RETURN_TYPE(uint32_t)
-_MAV_MSG_RETURN_TYPE(int32_t)
-_MAV_MSG_RETURN_TYPE(uint64_t)
-_MAV_MSG_RETURN_TYPE(int64_t)
-_MAV_MSG_RETURN_TYPE(float)
-_MAV_MSG_RETURN_TYPE(double)
-#endif // MAVLINK_NEED_BYTE_SWAP
-
-static inline uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value,
- uint8_t array_length, uint8_t wire_offset)
-{
- memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
- return array_length;
-}
-
-static inline uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value,
- uint8_t array_length, uint8_t wire_offset)
-{
- memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
- return array_length;
-}
-
-static inline uint16_t _MAV_RETURN_int8_t_array(const mavlink_message_t *msg, int8_t *value,
- uint8_t array_length, uint8_t wire_offset)
-{
- memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
- return array_length;
-}
-
-#if MAVLINK_NEED_BYTE_SWAP
-#define _MAV_RETURN_ARRAY(TYPE, V) \
-static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
- uint8_t array_length, uint8_t wire_offset) \
-{ \
- uint16_t i; \
- for (i=0; i<array_length; i++) { \
- value[i] = _MAV_RETURN_## TYPE (msg, wire_offset+(i*sizeof(value[0]))); \
- } \
- return array_length*sizeof(value[0]); \
-}
-#else
-#define _MAV_RETURN_ARRAY(TYPE, V) \
-static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
- uint8_t array_length, uint8_t wire_offset) \
-{ \
- memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length*sizeof(TYPE)); \
- return array_length*sizeof(TYPE); \
-}
-#endif
-
-_MAV_RETURN_ARRAY(uint16_t, u16)
-_MAV_RETURN_ARRAY(uint32_t, u32)
-_MAV_RETURN_ARRAY(uint64_t, u64)
-_MAV_RETURN_ARRAY(int16_t, i16)
-_MAV_RETURN_ARRAY(int32_t, i32)
-_MAV_RETURN_ARRAY(int64_t, i64)
-_MAV_RETURN_ARRAY(float, f)
-_MAV_RETURN_ARRAY(double, d)
-
-#endif // _MAVLINK_PROTOCOL_H_
diff --git a/mavlink_lib/pyxis/mavlink.h b/mavlink_lib/pyxis/mavlink.h
deleted file mode 100644
index 1e83df9fcdbfc2bf9cd32ea0ad695bb4503cd3cb..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink.h
+++ /dev/null
@@ -1,34 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol built from pyxis.xml
- * @see http://mavlink.org
- */
-#pragma once
-#ifndef MAVLINK_H
-#define MAVLINK_H
-
-#define MAVLINK_PRIMARY_XML_HASH 7764457067459173741
-
-#ifndef MAVLINK_STX
-#define MAVLINK_STX 254
-#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 0
-#endif
-
-#include "version.h"
-#include "pyxis.h"
-
-#endif // MAVLINK_H
diff --git a/mavlink_lib/pyxis/mavlink_msg_ack_tm.h b/mavlink_lib/pyxis/mavlink_msg_ack_tm.h
deleted file mode 100644
index 8abc2a50773e576580ab8179be7c6a2348071c59..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_ack_tm.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE ACK_TM PACKING
-
-#define MAVLINK_MSG_ID_ACK_TM 100
-
-
-typedef struct __mavlink_ack_tm_t {
- uint8_t recv_msgid; /*< Message id of the received message*/
- uint8_t seq_ack; /*< Sequence number of the received message*/
-} mavlink_ack_tm_t;
-
-#define MAVLINK_MSG_ID_ACK_TM_LEN 2
-#define MAVLINK_MSG_ID_ACK_TM_MIN_LEN 2
-#define MAVLINK_MSG_ID_100_LEN 2
-#define MAVLINK_MSG_ID_100_MIN_LEN 2
-
-#define MAVLINK_MSG_ID_ACK_TM_CRC 50
-#define MAVLINK_MSG_ID_100_CRC 50
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ACK_TM { \
- 100, \
- "ACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_ack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_ack_tm_t, seq_ack) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ACK_TM { \
- "ACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_ack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_ack_tm_t, seq_ack) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ack_tm 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 recv_msgid Message id of the received message
- * @param seq_ack Sequence number of the received message
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ack_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACK_TM_LEN);
-#else
- mavlink_ack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ACK_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-}
-
-/**
- * @brief Pack a ack_tm 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 recv_msgid Message id of the received message
- * @param seq_ack Sequence number of the received message
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ack_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t recv_msgid,uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACK_TM_LEN);
-#else
- mavlink_ack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ACK_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-}
-
-/**
- * @brief Encode a ack_tm 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 ack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ack_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ack_tm_t* ack_tm)
-{
- return mavlink_msg_ack_tm_pack(system_id, component_id, msg, ack_tm->recv_msgid, ack_tm->seq_ack);
-}
-
-/**
- * @brief Encode a ack_tm 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 ack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ack_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ack_tm_t* ack_tm)
-{
- return mavlink_msg_ack_tm_pack_chan(system_id, component_id, chan, msg, ack_tm->recv_msgid, ack_tm->seq_ack);
-}
-
-/**
- * @brief Send a ack_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param recv_msgid Message id of the received message
- * @param seq_ack Sequence number of the received message
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ack_tm_send(mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, buf, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#else
- mavlink_ack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, (const char *)&packet, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a ack_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ack_tm_send_struct(mavlink_channel_t chan, const mavlink_ack_tm_t* ack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ack_tm_send(chan, ack_tm->recv_msgid, ack_tm->seq_ack);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, (const char *)ack_tm, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ACK_TM_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_ack_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, buf, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#else
- mavlink_ack_tm_t *packet = (mavlink_ack_tm_t *)msgbuf;
- packet->recv_msgid = recv_msgid;
- packet->seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, (const char *)packet, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ACK_TM UNPACKING
-
-
-/**
- * @brief Get field recv_msgid from ack_tm message
- *
- * @return Message id of the received message
- */
-static inline uint8_t mavlink_msg_ack_tm_get_recv_msgid(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field seq_ack from ack_tm message
- *
- * @return Sequence number of the received message
- */
-static inline uint8_t mavlink_msg_ack_tm_get_seq_ack(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Decode a ack_tm message into a struct
- *
- * @param msg The message to decode
- * @param ack_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ack_tm_decode(const mavlink_message_t* msg, mavlink_ack_tm_t* ack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ack_tm->recv_msgid = mavlink_msg_ack_tm_get_recv_msgid(msg);
- ack_tm->seq_ack = mavlink_msg_ack_tm_get_seq_ack(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ACK_TM_LEN? msg->len : MAVLINK_MSG_ID_ACK_TM_LEN;
- memset(ack_tm, 0, MAVLINK_MSG_ID_ACK_TM_LEN);
- memcpy(ack_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_ada_tm.h b/mavlink_lib/pyxis/mavlink_msg_ada_tm.h
deleted file mode 100644
index f96a75c0db6fcd54bea1d9bb6658860e7e998179..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_ada_tm.h
+++ /dev/null
@@ -1,513 +0,0 @@
-#pragma once
-// MESSAGE ADA_TM PACKING
-
-#define MAVLINK_MSG_ID_ADA_TM 205
-
-
-typedef struct __mavlink_ada_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float kalman_x0; /*< Kalman state variable 0 (pressure)*/
- float kalman_x1; /*< Kalman state variable 1 (pressure velocity)*/
- float kalman_x2; /*< Kalman state variable 2 (pressure acceleration)*/
- float vertical_speed; /*< [m/s] Vertical speed computed by the ADA*/
- float msl_altitude; /*< [m] Altitude w.r.t. mean sea level*/
- float ref_pressure; /*< [Pa] Calibration pressure*/
- float ref_altitude; /*< [m] Calibration altitude*/
- float ref_temperature; /*< [degC] Calibration temperature*/
- float msl_pressure; /*< [Pa] Expected pressure at mean sea level*/
- float msl_temperature; /*< [degC] Expected temperature at mean sea level*/
- float dpl_altitude; /*< [m] Main parachute deployment altituyde*/
- uint8_t state; /*< ADA current state*/
-} mavlink_ada_tm_t;
-
-#define MAVLINK_MSG_ID_ADA_TM_LEN 53
-#define MAVLINK_MSG_ID_ADA_TM_MIN_LEN 53
-#define MAVLINK_MSG_ID_205_LEN 53
-#define MAVLINK_MSG_ID_205_MIN_LEN 53
-
-#define MAVLINK_MSG_ID_ADA_TM_CRC 234
-#define MAVLINK_MSG_ID_205_CRC 234
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ADA_TM { \
- 205, \
- "ADA_TM", \
- 13, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ada_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_ada_tm_t, state) }, \
- { "kalman_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ada_tm_t, kalman_x0) }, \
- { "kalman_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ada_tm_t, kalman_x1) }, \
- { "kalman_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ada_tm_t, kalman_x2) }, \
- { "vertical_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ada_tm_t, vertical_speed) }, \
- { "msl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ada_tm_t, msl_altitude) }, \
- { "ref_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_ada_tm_t, ref_pressure) }, \
- { "ref_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_ada_tm_t, ref_altitude) }, \
- { "ref_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_ada_tm_t, ref_temperature) }, \
- { "msl_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_ada_tm_t, msl_pressure) }, \
- { "msl_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_ada_tm_t, msl_temperature) }, \
- { "dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_ada_tm_t, dpl_altitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ADA_TM { \
- "ADA_TM", \
- 13, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ada_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_ada_tm_t, state) }, \
- { "kalman_x0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ada_tm_t, kalman_x0) }, \
- { "kalman_x1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ada_tm_t, kalman_x1) }, \
- { "kalman_x2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ada_tm_t, kalman_x2) }, \
- { "vertical_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ada_tm_t, vertical_speed) }, \
- { "msl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ada_tm_t, msl_altitude) }, \
- { "ref_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_ada_tm_t, ref_pressure) }, \
- { "ref_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_ada_tm_t, ref_altitude) }, \
- { "ref_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_ada_tm_t, ref_temperature) }, \
- { "msl_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_ada_tm_t, msl_pressure) }, \
- { "msl_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_ada_tm_t, msl_temperature) }, \
- { "dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_ada_tm_t, dpl_altitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ada_tm 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] When was this logged
- * @param state ADA current state
- * @param kalman_x0 Kalman state variable 0 (pressure)
- * @param kalman_x1 Kalman state variable 1 (pressure velocity)
- * @param kalman_x2 Kalman state variable 2 (pressure acceleration)
- * @param vertical_speed [m/s] Vertical speed computed by the ADA
- * @param msl_altitude [m] Altitude w.r.t. mean sea level
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_altitude [m] Calibration altitude
- * @param ref_temperature [degC] Calibration temperature
- * @param msl_pressure [Pa] Expected pressure at mean sea level
- * @param msl_temperature [degC] Expected temperature at mean sea level
- * @param dpl_altitude [m] Main parachute deployment altituyde
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ada_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float vertical_speed, float msl_altitude, float ref_pressure, float ref_altitude, float ref_temperature, float msl_pressure, float msl_temperature, float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, kalman_x0);
- _mav_put_float(buf, 12, kalman_x1);
- _mav_put_float(buf, 16, kalman_x2);
- _mav_put_float(buf, 20, vertical_speed);
- _mav_put_float(buf, 24, msl_altitude);
- _mav_put_float(buf, 28, ref_pressure);
- _mav_put_float(buf, 32, ref_altitude);
- _mav_put_float(buf, 36, ref_temperature);
- _mav_put_float(buf, 40, msl_pressure);
- _mav_put_float(buf, 44, msl_temperature);
- _mav_put_float(buf, 48, dpl_altitude);
- _mav_put_uint8_t(buf, 52, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADA_TM_LEN);
-#else
- mavlink_ada_tm_t packet;
- packet.timestamp = timestamp;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.vertical_speed = vertical_speed;
- packet.msl_altitude = msl_altitude;
- packet.ref_pressure = ref_pressure;
- packet.ref_altitude = ref_altitude;
- packet.ref_temperature = ref_temperature;
- packet.msl_pressure = msl_pressure;
- packet.msl_temperature = msl_temperature;
- packet.dpl_altitude = dpl_altitude;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADA_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADA_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-}
-
-/**
- * @brief Pack a ada_tm 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] When was this logged
- * @param state ADA current state
- * @param kalman_x0 Kalman state variable 0 (pressure)
- * @param kalman_x1 Kalman state variable 1 (pressure velocity)
- * @param kalman_x2 Kalman state variable 2 (pressure acceleration)
- * @param vertical_speed [m/s] Vertical speed computed by the ADA
- * @param msl_altitude [m] Altitude w.r.t. mean sea level
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_altitude [m] Calibration altitude
- * @param ref_temperature [degC] Calibration temperature
- * @param msl_pressure [Pa] Expected pressure at mean sea level
- * @param msl_temperature [degC] Expected temperature at mean sea level
- * @param dpl_altitude [m] Main parachute deployment altituyde
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ada_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t state,float kalman_x0,float kalman_x1,float kalman_x2,float vertical_speed,float msl_altitude,float ref_pressure,float ref_altitude,float ref_temperature,float msl_pressure,float msl_temperature,float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, kalman_x0);
- _mav_put_float(buf, 12, kalman_x1);
- _mav_put_float(buf, 16, kalman_x2);
- _mav_put_float(buf, 20, vertical_speed);
- _mav_put_float(buf, 24, msl_altitude);
- _mav_put_float(buf, 28, ref_pressure);
- _mav_put_float(buf, 32, ref_altitude);
- _mav_put_float(buf, 36, ref_temperature);
- _mav_put_float(buf, 40, msl_pressure);
- _mav_put_float(buf, 44, msl_temperature);
- _mav_put_float(buf, 48, dpl_altitude);
- _mav_put_uint8_t(buf, 52, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADA_TM_LEN);
-#else
- mavlink_ada_tm_t packet;
- packet.timestamp = timestamp;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.vertical_speed = vertical_speed;
- packet.msl_altitude = msl_altitude;
- packet.ref_pressure = ref_pressure;
- packet.ref_altitude = ref_altitude;
- packet.ref_temperature = ref_temperature;
- packet.msl_pressure = msl_pressure;
- packet.msl_temperature = msl_temperature;
- packet.dpl_altitude = dpl_altitude;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADA_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADA_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-}
-
-/**
- * @brief Encode a ada_tm 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 ada_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ada_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ada_tm_t* ada_tm)
-{
- return mavlink_msg_ada_tm_pack(system_id, component_id, msg, ada_tm->timestamp, ada_tm->state, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->vertical_speed, ada_tm->msl_altitude, ada_tm->ref_pressure, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_pressure, ada_tm->msl_temperature, ada_tm->dpl_altitude);
-}
-
-/**
- * @brief Encode a ada_tm 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 ada_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ada_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ada_tm_t* ada_tm)
-{
- return mavlink_msg_ada_tm_pack_chan(system_id, component_id, chan, msg, ada_tm->timestamp, ada_tm->state, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->vertical_speed, ada_tm->msl_altitude, ada_tm->ref_pressure, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_pressure, ada_tm->msl_temperature, ada_tm->dpl_altitude);
-}
-
-/**
- * @brief Send a ada_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param state ADA current state
- * @param kalman_x0 Kalman state variable 0 (pressure)
- * @param kalman_x1 Kalman state variable 1 (pressure velocity)
- * @param kalman_x2 Kalman state variable 2 (pressure acceleration)
- * @param vertical_speed [m/s] Vertical speed computed by the ADA
- * @param msl_altitude [m] Altitude w.r.t. mean sea level
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_altitude [m] Calibration altitude
- * @param ref_temperature [degC] Calibration temperature
- * @param msl_pressure [Pa] Expected pressure at mean sea level
- * @param msl_temperature [degC] Expected temperature at mean sea level
- * @param dpl_altitude [m] Main parachute deployment altituyde
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ada_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float vertical_speed, float msl_altitude, float ref_pressure, float ref_altitude, float ref_temperature, float msl_pressure, float msl_temperature, float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADA_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, kalman_x0);
- _mav_put_float(buf, 12, kalman_x1);
- _mav_put_float(buf, 16, kalman_x2);
- _mav_put_float(buf, 20, vertical_speed);
- _mav_put_float(buf, 24, msl_altitude);
- _mav_put_float(buf, 28, ref_pressure);
- _mav_put_float(buf, 32, ref_altitude);
- _mav_put_float(buf, 36, ref_temperature);
- _mav_put_float(buf, 40, msl_pressure);
- _mav_put_float(buf, 44, msl_temperature);
- _mav_put_float(buf, 48, dpl_altitude);
- _mav_put_uint8_t(buf, 52, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, buf, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#else
- mavlink_ada_tm_t packet;
- packet.timestamp = timestamp;
- packet.kalman_x0 = kalman_x0;
- packet.kalman_x1 = kalman_x1;
- packet.kalman_x2 = kalman_x2;
- packet.vertical_speed = vertical_speed;
- packet.msl_altitude = msl_altitude;
- packet.ref_pressure = ref_pressure;
- packet.ref_altitude = ref_altitude;
- packet.ref_temperature = ref_temperature;
- packet.msl_pressure = msl_pressure;
- packet.msl_temperature = msl_temperature;
- packet.dpl_altitude = dpl_altitude;
- packet.state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, (const char *)&packet, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a ada_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ada_tm_send_struct(mavlink_channel_t chan, const mavlink_ada_tm_t* ada_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ada_tm_send(chan, ada_tm->timestamp, ada_tm->state, ada_tm->kalman_x0, ada_tm->kalman_x1, ada_tm->kalman_x2, ada_tm->vertical_speed, ada_tm->msl_altitude, ada_tm->ref_pressure, ada_tm->ref_altitude, ada_tm->ref_temperature, ada_tm->msl_pressure, ada_tm->msl_temperature, ada_tm->dpl_altitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, (const char *)ada_tm, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ADA_TM_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_ada_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float kalman_x0, float kalman_x1, float kalman_x2, float vertical_speed, float msl_altitude, float ref_pressure, float ref_altitude, float ref_temperature, float msl_pressure, float msl_temperature, float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, kalman_x0);
- _mav_put_float(buf, 12, kalman_x1);
- _mav_put_float(buf, 16, kalman_x2);
- _mav_put_float(buf, 20, vertical_speed);
- _mav_put_float(buf, 24, msl_altitude);
- _mav_put_float(buf, 28, ref_pressure);
- _mav_put_float(buf, 32, ref_altitude);
- _mav_put_float(buf, 36, ref_temperature);
- _mav_put_float(buf, 40, msl_pressure);
- _mav_put_float(buf, 44, msl_temperature);
- _mav_put_float(buf, 48, dpl_altitude);
- _mav_put_uint8_t(buf, 52, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, buf, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#else
- mavlink_ada_tm_t *packet = (mavlink_ada_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->kalman_x0 = kalman_x0;
- packet->kalman_x1 = kalman_x1;
- packet->kalman_x2 = kalman_x2;
- packet->vertical_speed = vertical_speed;
- packet->msl_altitude = msl_altitude;
- packet->ref_pressure = ref_pressure;
- packet->ref_altitude = ref_altitude;
- packet->ref_temperature = ref_temperature;
- packet->msl_pressure = msl_pressure;
- packet->msl_temperature = msl_temperature;
- packet->dpl_altitude = dpl_altitude;
- packet->state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADA_TM, (const char *)packet, MAVLINK_MSG_ID_ADA_TM_MIN_LEN, MAVLINK_MSG_ID_ADA_TM_LEN, MAVLINK_MSG_ID_ADA_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ADA_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from ada_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_ada_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field state from ada_tm message
- *
- * @return ADA current state
- */
-static inline uint8_t mavlink_msg_ada_tm_get_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 52);
-}
-
-/**
- * @brief Get field kalman_x0 from ada_tm message
- *
- * @return Kalman state variable 0 (pressure)
- */
-static inline float mavlink_msg_ada_tm_get_kalman_x0(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field kalman_x1 from ada_tm message
- *
- * @return Kalman state variable 1 (pressure velocity)
- */
-static inline float mavlink_msg_ada_tm_get_kalman_x1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field kalman_x2 from ada_tm message
- *
- * @return Kalman state variable 2 (pressure acceleration)
- */
-static inline float mavlink_msg_ada_tm_get_kalman_x2(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field vertical_speed from ada_tm message
- *
- * @return [m/s] Vertical speed computed by the ADA
- */
-static inline float mavlink_msg_ada_tm_get_vertical_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field msl_altitude from ada_tm message
- *
- * @return [m] Altitude w.r.t. mean sea level
- */
-static inline float mavlink_msg_ada_tm_get_msl_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field ref_pressure from ada_tm message
- *
- * @return [Pa] Calibration pressure
- */
-static inline float mavlink_msg_ada_tm_get_ref_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field ref_altitude from ada_tm message
- *
- * @return [m] Calibration altitude
- */
-static inline float mavlink_msg_ada_tm_get_ref_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field ref_temperature from ada_tm message
- *
- * @return [degC] Calibration temperature
- */
-static inline float mavlink_msg_ada_tm_get_ref_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field msl_pressure from ada_tm message
- *
- * @return [Pa] Expected pressure at mean sea level
- */
-static inline float mavlink_msg_ada_tm_get_msl_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field msl_temperature from ada_tm message
- *
- * @return [degC] Expected temperature at mean sea level
- */
-static inline float mavlink_msg_ada_tm_get_msl_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field dpl_altitude from ada_tm message
- *
- * @return [m] Main parachute deployment altituyde
- */
-static inline float mavlink_msg_ada_tm_get_dpl_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Decode a ada_tm message into a struct
- *
- * @param msg The message to decode
- * @param ada_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ada_tm_decode(const mavlink_message_t* msg, mavlink_ada_tm_t* ada_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ada_tm->timestamp = mavlink_msg_ada_tm_get_timestamp(msg);
- ada_tm->kalman_x0 = mavlink_msg_ada_tm_get_kalman_x0(msg);
- ada_tm->kalman_x1 = mavlink_msg_ada_tm_get_kalman_x1(msg);
- ada_tm->kalman_x2 = mavlink_msg_ada_tm_get_kalman_x2(msg);
- ada_tm->vertical_speed = mavlink_msg_ada_tm_get_vertical_speed(msg);
- ada_tm->msl_altitude = mavlink_msg_ada_tm_get_msl_altitude(msg);
- ada_tm->ref_pressure = mavlink_msg_ada_tm_get_ref_pressure(msg);
- ada_tm->ref_altitude = mavlink_msg_ada_tm_get_ref_altitude(msg);
- ada_tm->ref_temperature = mavlink_msg_ada_tm_get_ref_temperature(msg);
- ada_tm->msl_pressure = mavlink_msg_ada_tm_get_msl_pressure(msg);
- ada_tm->msl_temperature = mavlink_msg_ada_tm_get_msl_temperature(msg);
- ada_tm->dpl_altitude = mavlink_msg_ada_tm_get_dpl_altitude(msg);
- ada_tm->state = mavlink_msg_ada_tm_get_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ADA_TM_LEN? msg->len : MAVLINK_MSG_ID_ADA_TM_LEN;
- memset(ada_tm, 0, MAVLINK_MSG_ID_ADA_TM_LEN);
- memcpy(ada_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_adc_tm.h b/mavlink_lib/pyxis/mavlink_msg_adc_tm.h
deleted file mode 100644
index 3624e4f8fe82f06f80d123dd05d2616c14709cc1..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_adc_tm.h
+++ /dev/null
@@ -1,330 +0,0 @@
-#pragma once
-// MESSAGE ADC_TM PACKING
-
-#define MAVLINK_MSG_ID_ADC_TM 105
-
-
-typedef struct __mavlink_adc_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float channel_0; /*< [V] ADC voltage measured on channel 0*/
- float channel_1; /*< [V] ADC voltage measured on channel 1*/
- float channel_2; /*< [V] ADC voltage measured on channel 2*/
- float channel_3; /*< [V] ADC voltage measured on channel 3*/
- char sensor_id[20]; /*< Sensor name*/
-} mavlink_adc_tm_t;
-
-#define MAVLINK_MSG_ID_ADC_TM_LEN 44
-#define MAVLINK_MSG_ID_ADC_TM_MIN_LEN 44
-#define MAVLINK_MSG_ID_105_LEN 44
-#define MAVLINK_MSG_ID_105_MIN_LEN 44
-
-#define MAVLINK_MSG_ID_ADC_TM_CRC 104
-#define MAVLINK_MSG_ID_105_CRC 104
-
-#define MAVLINK_MSG_ADC_TM_FIELD_SENSOR_ID_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ADC_TM { \
- 105, \
- "ADC_TM", \
- 6, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_adc_tm_t, timestamp) }, \
- { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 24, offsetof(mavlink_adc_tm_t, sensor_id) }, \
- { "channel_0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_adc_tm_t, channel_0) }, \
- { "channel_1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_adc_tm_t, channel_1) }, \
- { "channel_2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_adc_tm_t, channel_2) }, \
- { "channel_3", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_adc_tm_t, channel_3) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ADC_TM { \
- "ADC_TM", \
- 6, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_adc_tm_t, timestamp) }, \
- { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 24, offsetof(mavlink_adc_tm_t, sensor_id) }, \
- { "channel_0", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_adc_tm_t, channel_0) }, \
- { "channel_1", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_adc_tm_t, channel_1) }, \
- { "channel_2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_adc_tm_t, channel_2) }, \
- { "channel_3", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_adc_tm_t, channel_3) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a adc_tm 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] When was this logged
- * @param sensor_id Sensor name
- * @param channel_0 [V] ADC voltage measured on channel 0
- * @param channel_1 [V] ADC voltage measured on channel 1
- * @param channel_2 [V] ADC voltage measured on channel 2
- * @param channel_3 [V] ADC voltage measured on channel 3
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_adc_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_id, float channel_0, float channel_1, float channel_2, float channel_3)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, channel_0);
- _mav_put_float(buf, 12, channel_1);
- _mav_put_float(buf, 16, channel_2);
- _mav_put_float(buf, 20, channel_3);
- _mav_put_char_array(buf, 24, sensor_id, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADC_TM_LEN);
-#else
- mavlink_adc_tm_t packet;
- packet.timestamp = timestamp;
- packet.channel_0 = channel_0;
- packet.channel_1 = channel_1;
- packet.channel_2 = channel_2;
- packet.channel_3 = channel_3;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADC_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADC_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-}
-
-/**
- * @brief Pack a adc_tm 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] When was this logged
- * @param sensor_id Sensor name
- * @param channel_0 [V] ADC voltage measured on channel 0
- * @param channel_1 [V] ADC voltage measured on channel 1
- * @param channel_2 [V] ADC voltage measured on channel 2
- * @param channel_3 [V] ADC voltage measured on channel 3
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_adc_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_id,float channel_0,float channel_1,float channel_2,float channel_3)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, channel_0);
- _mav_put_float(buf, 12, channel_1);
- _mav_put_float(buf, 16, channel_2);
- _mav_put_float(buf, 20, channel_3);
- _mav_put_char_array(buf, 24, sensor_id, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADC_TM_LEN);
-#else
- mavlink_adc_tm_t packet;
- packet.timestamp = timestamp;
- packet.channel_0 = channel_0;
- packet.channel_1 = channel_1;
- packet.channel_2 = channel_2;
- packet.channel_3 = channel_3;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADC_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ADC_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-}
-
-/**
- * @brief Encode a adc_tm 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 adc_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_adc_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_adc_tm_t* adc_tm)
-{
- return mavlink_msg_adc_tm_pack(system_id, component_id, msg, adc_tm->timestamp, adc_tm->sensor_id, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3);
-}
-
-/**
- * @brief Encode a adc_tm 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 adc_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_adc_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_adc_tm_t* adc_tm)
-{
- return mavlink_msg_adc_tm_pack_chan(system_id, component_id, chan, msg, adc_tm->timestamp, adc_tm->sensor_id, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3);
-}
-
-/**
- * @brief Send a adc_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_id Sensor name
- * @param channel_0 [V] ADC voltage measured on channel 0
- * @param channel_1 [V] ADC voltage measured on channel 1
- * @param channel_2 [V] ADC voltage measured on channel 2
- * @param channel_3 [V] ADC voltage measured on channel 3
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_adc_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_id, float channel_0, float channel_1, float channel_2, float channel_3)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ADC_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, channel_0);
- _mav_put_float(buf, 12, channel_1);
- _mav_put_float(buf, 16, channel_2);
- _mav_put_float(buf, 20, channel_3);
- _mav_put_char_array(buf, 24, sensor_id, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, buf, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#else
- mavlink_adc_tm_t packet;
- packet.timestamp = timestamp;
- packet.channel_0 = channel_0;
- packet.channel_1 = channel_1;
- packet.channel_2 = channel_2;
- packet.channel_3 = channel_3;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)&packet, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a adc_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_adc_tm_send_struct(mavlink_channel_t chan, const mavlink_adc_tm_t* adc_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_adc_tm_send(chan, adc_tm->timestamp, adc_tm->sensor_id, adc_tm->channel_0, adc_tm->channel_1, adc_tm->channel_2, adc_tm->channel_3);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)adc_tm, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ADC_TM_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_adc_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_id, float channel_0, float channel_1, float channel_2, float channel_3)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, channel_0);
- _mav_put_float(buf, 12, channel_1);
- _mav_put_float(buf, 16, channel_2);
- _mav_put_float(buf, 20, channel_3);
- _mav_put_char_array(buf, 24, sensor_id, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, buf, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#else
- mavlink_adc_tm_t *packet = (mavlink_adc_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->channel_0 = channel_0;
- packet->channel_1 = channel_1;
- packet->channel_2 = channel_2;
- packet->channel_3 = channel_3;
- mav_array_memcpy(packet->sensor_id, sensor_id, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADC_TM, (const char *)packet, MAVLINK_MSG_ID_ADC_TM_MIN_LEN, MAVLINK_MSG_ID_ADC_TM_LEN, MAVLINK_MSG_ID_ADC_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ADC_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from adc_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_adc_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_id from adc_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_adc_tm_get_sensor_id(const mavlink_message_t* msg, char *sensor_id)
-{
- return _MAV_RETURN_char_array(msg, sensor_id, 20, 24);
-}
-
-/**
- * @brief Get field channel_0 from adc_tm message
- *
- * @return [V] ADC voltage measured on channel 0
- */
-static inline float mavlink_msg_adc_tm_get_channel_0(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field channel_1 from adc_tm message
- *
- * @return [V] ADC voltage measured on channel 1
- */
-static inline float mavlink_msg_adc_tm_get_channel_1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field channel_2 from adc_tm message
- *
- * @return [V] ADC voltage measured on channel 2
- */
-static inline float mavlink_msg_adc_tm_get_channel_2(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field channel_3 from adc_tm message
- *
- * @return [V] ADC voltage measured on channel 3
- */
-static inline float mavlink_msg_adc_tm_get_channel_3(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Decode a adc_tm message into a struct
- *
- * @param msg The message to decode
- * @param adc_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_adc_tm_decode(const mavlink_message_t* msg, mavlink_adc_tm_t* adc_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- adc_tm->timestamp = mavlink_msg_adc_tm_get_timestamp(msg);
- adc_tm->channel_0 = mavlink_msg_adc_tm_get_channel_0(msg);
- adc_tm->channel_1 = mavlink_msg_adc_tm_get_channel_1(msg);
- adc_tm->channel_2 = mavlink_msg_adc_tm_get_channel_2(msg);
- adc_tm->channel_3 = mavlink_msg_adc_tm_get_channel_3(msg);
- mavlink_msg_adc_tm_get_sensor_id(msg, adc_tm->sensor_id);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ADC_TM_LEN? msg->len : MAVLINK_MSG_ID_ADC_TM_LEN;
- memset(adc_tm, 0, MAVLINK_MSG_ID_ADC_TM_LEN);
- memcpy(adc_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_attitude_tm.h b/mavlink_lib/pyxis/mavlink_msg_attitude_tm.h
deleted file mode 100644
index 7e503eccdbd088a0aa49bfb2aece565deb0344d1..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_attitude_tm.h
+++ /dev/null
@@ -1,405 +0,0 @@
-#pragma once
-// MESSAGE ATTITUDE_TM PACKING
-
-#define MAVLINK_MSG_ID_ATTITUDE_TM 110
-
-
-typedef struct __mavlink_attitude_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float roll; /*< [deg] Roll angle*/
- float pitch; /*< [deg] Pitch angle*/
- float yaw; /*< [deg] Yaw angle*/
- float quat_x; /*< Quaternion x component*/
- float quat_y; /*< Quaternion y component*/
- float quat_z; /*< Quaternion z component*/
- float quat_w; /*< Quaternion w component*/
- char sensor_id[20]; /*< Sensor name*/
-} mavlink_attitude_tm_t;
-
-#define MAVLINK_MSG_ID_ATTITUDE_TM_LEN 56
-#define MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN 56
-#define MAVLINK_MSG_ID_110_LEN 56
-#define MAVLINK_MSG_ID_110_MIN_LEN 56
-
-#define MAVLINK_MSG_ID_ATTITUDE_TM_CRC 170
-#define MAVLINK_MSG_ID_110_CRC 170
-
-#define MAVLINK_MSG_ATTITUDE_TM_FIELD_SENSOR_ID_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ATTITUDE_TM { \
- 110, \
- "ATTITUDE_TM", \
- 9, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_attitude_tm_t, timestamp) }, \
- { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 36, offsetof(mavlink_attitude_tm_t, sensor_id) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_tm_t, roll) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_tm_t, pitch) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_tm_t, yaw) }, \
- { "quat_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_tm_t, quat_x) }, \
- { "quat_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_tm_t, quat_y) }, \
- { "quat_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_tm_t, quat_z) }, \
- { "quat_w", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_tm_t, quat_w) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ATTITUDE_TM { \
- "ATTITUDE_TM", \
- 9, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_attitude_tm_t, timestamp) }, \
- { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 36, offsetof(mavlink_attitude_tm_t, sensor_id) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_tm_t, roll) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_tm_t, pitch) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_tm_t, yaw) }, \
- { "quat_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_tm_t, quat_x) }, \
- { "quat_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_tm_t, quat_y) }, \
- { "quat_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_tm_t, quat_z) }, \
- { "quat_w", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_tm_t, quat_w) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a attitude_tm 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] When was this logged
- * @param sensor_id Sensor name
- * @param roll [deg] Roll angle
- * @param pitch [deg] Pitch angle
- * @param yaw [deg] Yaw angle
- * @param quat_x Quaternion x component
- * @param quat_y Quaternion y component
- * @param quat_z Quaternion z component
- * @param quat_w Quaternion w component
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_attitude_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_id, float roll, float pitch, float yaw, float quat_x, float quat_y, float quat_z, float quat_w)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ATTITUDE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, roll);
- _mav_put_float(buf, 12, pitch);
- _mav_put_float(buf, 16, yaw);
- _mav_put_float(buf, 20, quat_x);
- _mav_put_float(buf, 24, quat_y);
- _mav_put_float(buf, 28, quat_z);
- _mav_put_float(buf, 32, quat_w);
- _mav_put_char_array(buf, 36, sensor_id, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TM_LEN);
-#else
- mavlink_attitude_tm_t packet;
- packet.timestamp = timestamp;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.quat_x = quat_x;
- packet.quat_y = quat_y;
- packet.quat_z = quat_z;
- packet.quat_w = quat_w;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-}
-
-/**
- * @brief Pack a attitude_tm 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] When was this logged
- * @param sensor_id Sensor name
- * @param roll [deg] Roll angle
- * @param pitch [deg] Pitch angle
- * @param yaw [deg] Yaw angle
- * @param quat_x Quaternion x component
- * @param quat_y Quaternion y component
- * @param quat_z Quaternion z component
- * @param quat_w Quaternion w component
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_attitude_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_id,float roll,float pitch,float yaw,float quat_x,float quat_y,float quat_z,float quat_w)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ATTITUDE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, roll);
- _mav_put_float(buf, 12, pitch);
- _mav_put_float(buf, 16, yaw);
- _mav_put_float(buf, 20, quat_x);
- _mav_put_float(buf, 24, quat_y);
- _mav_put_float(buf, 28, quat_z);
- _mav_put_float(buf, 32, quat_w);
- _mav_put_char_array(buf, 36, sensor_id, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TM_LEN);
-#else
- mavlink_attitude_tm_t packet;
- packet.timestamp = timestamp;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.quat_x = quat_x;
- packet.quat_y = quat_y;
- packet.quat_z = quat_z;
- packet.quat_w = quat_w;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-}
-
-/**
- * @brief Encode a attitude_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_attitude_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_tm_t* attitude_tm)
-{
- return mavlink_msg_attitude_tm_pack(system_id, component_id, msg, attitude_tm->timestamp, attitude_tm->sensor_id, attitude_tm->roll, attitude_tm->pitch, attitude_tm->yaw, attitude_tm->quat_x, attitude_tm->quat_y, attitude_tm->quat_z, attitude_tm->quat_w);
-}
-
-/**
- * @brief Encode a attitude_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_attitude_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_tm_t* attitude_tm)
-{
- return mavlink_msg_attitude_tm_pack_chan(system_id, component_id, chan, msg, attitude_tm->timestamp, attitude_tm->sensor_id, attitude_tm->roll, attitude_tm->pitch, attitude_tm->yaw, attitude_tm->quat_x, attitude_tm->quat_y, attitude_tm->quat_z, attitude_tm->quat_w);
-}
-
-/**
- * @brief Send a attitude_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_id Sensor name
- * @param roll [deg] Roll angle
- * @param pitch [deg] Pitch angle
- * @param yaw [deg] Yaw angle
- * @param quat_x Quaternion x component
- * @param quat_y Quaternion y component
- * @param quat_z Quaternion z component
- * @param quat_w Quaternion w component
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_attitude_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_id, float roll, float pitch, float yaw, float quat_x, float quat_y, float quat_z, float quat_w)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ATTITUDE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, roll);
- _mav_put_float(buf, 12, pitch);
- _mav_put_float(buf, 16, yaw);
- _mav_put_float(buf, 20, quat_x);
- _mav_put_float(buf, 24, quat_y);
- _mav_put_float(buf, 28, quat_z);
- _mav_put_float(buf, 32, quat_w);
- _mav_put_char_array(buf, 36, sensor_id, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TM, buf, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-#else
- mavlink_attitude_tm_t packet;
- packet.timestamp = timestamp;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.quat_x = quat_x;
- packet.quat_y = quat_y;
- packet.quat_z = quat_z;
- packet.quat_w = quat_w;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TM, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a attitude_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_attitude_tm_send_struct(mavlink_channel_t chan, const mavlink_attitude_tm_t* attitude_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_attitude_tm_send(chan, attitude_tm->timestamp, attitude_tm->sensor_id, attitude_tm->roll, attitude_tm->pitch, attitude_tm->yaw, attitude_tm->quat_x, attitude_tm->quat_y, attitude_tm->quat_z, attitude_tm->quat_w);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TM, (const char *)attitude_tm, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ATTITUDE_TM_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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_id, float roll, float pitch, float yaw, float quat_x, float quat_y, float quat_z, float quat_w)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, roll);
- _mav_put_float(buf, 12, pitch);
- _mav_put_float(buf, 16, yaw);
- _mav_put_float(buf, 20, quat_x);
- _mav_put_float(buf, 24, quat_y);
- _mav_put_float(buf, 28, quat_z);
- _mav_put_float(buf, 32, quat_w);
- _mav_put_char_array(buf, 36, sensor_id, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TM, buf, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-#else
- mavlink_attitude_tm_t *packet = (mavlink_attitude_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->roll = roll;
- packet->pitch = pitch;
- packet->yaw = yaw;
- packet->quat_x = quat_x;
- packet->quat_y = quat_y;
- packet->quat_z = quat_z;
- packet->quat_w = quat_w;
- mav_array_memcpy(packet->sensor_id, sensor_id, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TM, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_LEN, MAVLINK_MSG_ID_ATTITUDE_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ATTITUDE_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from attitude_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_attitude_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_id from attitude_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_attitude_tm_get_sensor_id(const mavlink_message_t* msg, char *sensor_id)
-{
- return _MAV_RETURN_char_array(msg, sensor_id, 20, 36);
-}
-
-/**
- * @brief Get field roll from attitude_tm message
- *
- * @return [deg] Roll angle
- */
-static inline float mavlink_msg_attitude_tm_get_roll(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field pitch from attitude_tm message
- *
- * @return [deg] Pitch angle
- */
-static inline float mavlink_msg_attitude_tm_get_pitch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field yaw from attitude_tm message
- *
- * @return [deg] Yaw angle
- */
-static inline float mavlink_msg_attitude_tm_get_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field quat_x from attitude_tm message
- *
- * @return Quaternion x component
- */
-static inline float mavlink_msg_attitude_tm_get_quat_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field quat_y from attitude_tm message
- *
- * @return Quaternion y component
- */
-static inline float mavlink_msg_attitude_tm_get_quat_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field quat_z from attitude_tm message
- *
- * @return Quaternion z component
- */
-static inline float mavlink_msg_attitude_tm_get_quat_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field quat_w from attitude_tm message
- *
- * @return Quaternion w component
- */
-static inline float mavlink_msg_attitude_tm_get_quat_w(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Decode a attitude_tm message into a struct
- *
- * @param msg The message to decode
- * @param attitude_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_attitude_tm_decode(const mavlink_message_t* msg, mavlink_attitude_tm_t* attitude_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- attitude_tm->timestamp = mavlink_msg_attitude_tm_get_timestamp(msg);
- attitude_tm->roll = mavlink_msg_attitude_tm_get_roll(msg);
- attitude_tm->pitch = mavlink_msg_attitude_tm_get_pitch(msg);
- attitude_tm->yaw = mavlink_msg_attitude_tm_get_yaw(msg);
- attitude_tm->quat_x = mavlink_msg_attitude_tm_get_quat_x(msg);
- attitude_tm->quat_y = mavlink_msg_attitude_tm_get_quat_y(msg);
- attitude_tm->quat_z = mavlink_msg_attitude_tm_get_quat_z(msg);
- attitude_tm->quat_w = mavlink_msg_attitude_tm_get_quat_w(msg);
- mavlink_msg_attitude_tm_get_sensor_id(msg, attitude_tm->sensor_id);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_TM_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_TM_LEN;
- memset(attitude_tm, 0, MAVLINK_MSG_ID_ATTITUDE_TM_LEN);
- memcpy(attitude_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_can_tm.h b/mavlink_lib/pyxis/mavlink_msg_can_tm.h
deleted file mode 100644
index 150c4748532b39bb9327f6553f1c6aed93151a43..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_can_tm.h
+++ /dev/null
@@ -1,363 +0,0 @@
-#pragma once
-// MESSAGE CAN_TM PACKING
-
-#define MAVLINK_MSG_ID_CAN_TM 207
-
-
-typedef struct __mavlink_can_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- uint64_t last_sent_ts; /*< Timestamp of the last sent message*/
- uint64_t last_rcv_ts; /*< Timestamp of the last received message*/
- uint16_t n_sent; /*< Number of sent messages*/
- uint16_t n_rcv; /*< Number of received messages*/
- uint8_t last_sent; /*< Id of the last sent message*/
- uint8_t last_rcv; /*< Id of the last received message*/
-} mavlink_can_tm_t;
-
-#define MAVLINK_MSG_ID_CAN_TM_LEN 30
-#define MAVLINK_MSG_ID_CAN_TM_MIN_LEN 30
-#define MAVLINK_MSG_ID_207_LEN 30
-#define MAVLINK_MSG_ID_207_MIN_LEN 30
-
-#define MAVLINK_MSG_ID_CAN_TM_CRC 169
-#define MAVLINK_MSG_ID_207_CRC 169
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_CAN_TM { \
- 207, \
- "CAN_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_can_tm_t, timestamp) }, \
- { "n_sent", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_can_tm_t, n_sent) }, \
- { "n_rcv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_can_tm_t, n_rcv) }, \
- { "last_sent", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_can_tm_t, last_sent) }, \
- { "last_rcv", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_can_tm_t, last_rcv) }, \
- { "last_sent_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_can_tm_t, last_sent_ts) }, \
- { "last_rcv_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_can_tm_t, last_rcv_ts) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_CAN_TM { \
- "CAN_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_can_tm_t, timestamp) }, \
- { "n_sent", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_can_tm_t, n_sent) }, \
- { "n_rcv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_can_tm_t, n_rcv) }, \
- { "last_sent", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_can_tm_t, last_sent) }, \
- { "last_rcv", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_can_tm_t, last_rcv) }, \
- { "last_sent_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_can_tm_t, last_sent_ts) }, \
- { "last_rcv_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_can_tm_t, last_rcv_ts) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a can_tm 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] When was this logged
- * @param n_sent Number of sent messages
- * @param n_rcv Number of received messages
- * @param last_sent Id of the last sent message
- * @param last_rcv Id of the last received message
- * @param last_sent_ts Timestamp of the last sent message
- * @param last_rcv_ts Timestamp of the last received message
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_can_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint16_t n_sent, uint16_t n_rcv, uint8_t last_sent, uint8_t last_rcv, uint64_t last_sent_ts, uint64_t last_rcv_ts)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CAN_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, last_sent_ts);
- _mav_put_uint64_t(buf, 16, last_rcv_ts);
- _mav_put_uint16_t(buf, 24, n_sent);
- _mav_put_uint16_t(buf, 26, n_rcv);
- _mav_put_uint8_t(buf, 28, last_sent);
- _mav_put_uint8_t(buf, 29, last_rcv);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAN_TM_LEN);
-#else
- mavlink_can_tm_t packet;
- packet.timestamp = timestamp;
- packet.last_sent_ts = last_sent_ts;
- packet.last_rcv_ts = last_rcv_ts;
- packet.n_sent = n_sent;
- packet.n_rcv = n_rcv;
- packet.last_sent = last_sent;
- packet.last_rcv = last_rcv;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAN_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_CAN_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAN_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_TM_LEN, MAVLINK_MSG_ID_CAN_TM_CRC);
-}
-
-/**
- * @brief Pack a can_tm 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] When was this logged
- * @param n_sent Number of sent messages
- * @param n_rcv Number of received messages
- * @param last_sent Id of the last sent message
- * @param last_rcv Id of the last received message
- * @param last_sent_ts Timestamp of the last sent message
- * @param last_rcv_ts Timestamp of the last received message
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_can_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint16_t n_sent,uint16_t n_rcv,uint8_t last_sent,uint8_t last_rcv,uint64_t last_sent_ts,uint64_t last_rcv_ts)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CAN_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, last_sent_ts);
- _mav_put_uint64_t(buf, 16, last_rcv_ts);
- _mav_put_uint16_t(buf, 24, n_sent);
- _mav_put_uint16_t(buf, 26, n_rcv);
- _mav_put_uint8_t(buf, 28, last_sent);
- _mav_put_uint8_t(buf, 29, last_rcv);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAN_TM_LEN);
-#else
- mavlink_can_tm_t packet;
- packet.timestamp = timestamp;
- packet.last_sent_ts = last_sent_ts;
- packet.last_rcv_ts = last_rcv_ts;
- packet.n_sent = n_sent;
- packet.n_rcv = n_rcv;
- packet.last_sent = last_sent;
- packet.last_rcv = last_rcv;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAN_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_CAN_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAN_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_TM_LEN, MAVLINK_MSG_ID_CAN_TM_CRC);
-}
-
-/**
- * @brief Encode a can_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_can_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_can_tm_t* can_tm)
-{
- return mavlink_msg_can_tm_pack(system_id, component_id, msg, can_tm->timestamp, can_tm->n_sent, can_tm->n_rcv, can_tm->last_sent, can_tm->last_rcv, can_tm->last_sent_ts, can_tm->last_rcv_ts);
-}
-
-/**
- * @brief Encode a can_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_can_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_can_tm_t* can_tm)
-{
- return mavlink_msg_can_tm_pack_chan(system_id, component_id, chan, msg, can_tm->timestamp, can_tm->n_sent, can_tm->n_rcv, can_tm->last_sent, can_tm->last_rcv, can_tm->last_sent_ts, can_tm->last_rcv_ts);
-}
-
-/**
- * @brief Send a can_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param n_sent Number of sent messages
- * @param n_rcv Number of received messages
- * @param last_sent Id of the last sent message
- * @param last_rcv Id of the last received message
- * @param last_sent_ts Timestamp of the last sent message
- * @param last_rcv_ts Timestamp of the last received message
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_can_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint16_t n_sent, uint16_t n_rcv, uint8_t last_sent, uint8_t last_rcv, uint64_t last_sent_ts, uint64_t last_rcv_ts)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CAN_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, last_sent_ts);
- _mav_put_uint64_t(buf, 16, last_rcv_ts);
- _mav_put_uint16_t(buf, 24, n_sent);
- _mav_put_uint16_t(buf, 26, n_rcv);
- _mav_put_uint8_t(buf, 28, last_sent);
- _mav_put_uint8_t(buf, 29, last_rcv);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_TM, buf, MAVLINK_MSG_ID_CAN_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_TM_LEN, MAVLINK_MSG_ID_CAN_TM_CRC);
-#else
- mavlink_can_tm_t packet;
- packet.timestamp = timestamp;
- packet.last_sent_ts = last_sent_ts;
- packet.last_rcv_ts = last_rcv_ts;
- packet.n_sent = n_sent;
- packet.n_rcv = n_rcv;
- packet.last_sent = last_sent;
- packet.last_rcv = last_rcv;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_TM, (const char *)&packet, MAVLINK_MSG_ID_CAN_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_TM_LEN, MAVLINK_MSG_ID_CAN_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a can_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_can_tm_send_struct(mavlink_channel_t chan, const mavlink_can_tm_t* can_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_can_tm_send(chan, can_tm->timestamp, can_tm->n_sent, can_tm->n_rcv, can_tm->last_sent, can_tm->last_rcv, can_tm->last_sent_ts, can_tm->last_rcv_ts);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_TM, (const char *)can_tm, MAVLINK_MSG_ID_CAN_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_TM_LEN, MAVLINK_MSG_ID_CAN_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_CAN_TM_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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint16_t n_sent, uint16_t n_rcv, uint8_t last_sent, uint8_t last_rcv, uint64_t last_sent_ts, uint64_t last_rcv_ts)
-{
-#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_sent_ts);
- _mav_put_uint64_t(buf, 16, last_rcv_ts);
- _mav_put_uint16_t(buf, 24, n_sent);
- _mav_put_uint16_t(buf, 26, n_rcv);
- _mav_put_uint8_t(buf, 28, last_sent);
- _mav_put_uint8_t(buf, 29, last_rcv);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_TM, buf, MAVLINK_MSG_ID_CAN_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_TM_LEN, MAVLINK_MSG_ID_CAN_TM_CRC);
-#else
- mavlink_can_tm_t *packet = (mavlink_can_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->last_sent_ts = last_sent_ts;
- packet->last_rcv_ts = last_rcv_ts;
- packet->n_sent = n_sent;
- packet->n_rcv = n_rcv;
- packet->last_sent = last_sent;
- packet->last_rcv = last_rcv;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_TM, (const char *)packet, MAVLINK_MSG_ID_CAN_TM_MIN_LEN, MAVLINK_MSG_ID_CAN_TM_LEN, MAVLINK_MSG_ID_CAN_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE CAN_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from can_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_can_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field n_sent from can_tm message
- *
- * @return Number of sent messages
- */
-static inline uint16_t mavlink_msg_can_tm_get_n_sent(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 24);
-}
-
-/**
- * @brief Get field n_rcv from can_tm message
- *
- * @return Number of received messages
- */
-static inline uint16_t mavlink_msg_can_tm_get_n_rcv(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 26);
-}
-
-/**
- * @brief Get field last_sent from can_tm message
- *
- * @return Id of the last sent message
- */
-static inline uint8_t mavlink_msg_can_tm_get_last_sent(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 28);
-}
-
-/**
- * @brief Get field last_rcv from can_tm message
- *
- * @return Id of the last received message
- */
-static inline uint8_t mavlink_msg_can_tm_get_last_rcv(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 29);
-}
-
-/**
- * @brief Get field last_sent_ts from can_tm message
- *
- * @return Timestamp of the last sent message
- */
-static inline uint64_t mavlink_msg_can_tm_get_last_sent_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 8);
-}
-
-/**
- * @brief Get field last_rcv_ts from can_tm message
- *
- * @return Timestamp of the last received message
- */
-static inline uint64_t mavlink_msg_can_tm_get_last_rcv_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 16);
-}
-
-/**
- * @brief Decode a can_tm message into a struct
- *
- * @param msg The message to decode
- * @param can_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_can_tm_decode(const mavlink_message_t* msg, mavlink_can_tm_t* can_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- can_tm->timestamp = mavlink_msg_can_tm_get_timestamp(msg);
- can_tm->last_sent_ts = mavlink_msg_can_tm_get_last_sent_ts(msg);
- can_tm->last_rcv_ts = mavlink_msg_can_tm_get_last_rcv_ts(msg);
- can_tm->n_sent = mavlink_msg_can_tm_get_n_sent(msg);
- can_tm->n_rcv = mavlink_msg_can_tm_get_n_rcv(msg);
- can_tm->last_sent = mavlink_msg_can_tm_get_last_sent(msg);
- can_tm->last_rcv = mavlink_msg_can_tm_get_last_rcv(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_CAN_TM_LEN? msg->len : MAVLINK_MSG_ID_CAN_TM_LEN;
- memset(can_tm, 0, MAVLINK_MSG_ID_CAN_TM_LEN);
- memcpy(can_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_command_tc.h b/mavlink_lib/pyxis/mavlink_msg_command_tc.h
deleted file mode 100644
index a4d0886b3f67df648cfd4ed0b8debc059ecfa272..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_command_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE COMMAND_TC PACKING
-
-#define MAVLINK_MSG_ID_COMMAND_TC 2
-
-
-typedef struct __mavlink_command_tc_t {
- uint8_t command_id; /*< A member of the MavCommandList enum*/
-} mavlink_command_tc_t;
-
-#define MAVLINK_MSG_ID_COMMAND_TC_LEN 1
-#define MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_2_LEN 1
-#define MAVLINK_MSG_ID_2_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_COMMAND_TC_CRC 198
-#define MAVLINK_MSG_ID_2_CRC 198
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_COMMAND_TC { \
- 2, \
- "COMMAND_TC", \
- 1, \
- { { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_command_tc_t, command_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_COMMAND_TC { \
- "COMMAND_TC", \
- 1, \
- { { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_command_tc_t, command_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a command_tc 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_id A member of the MavCommandList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_command_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_COMMAND_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_TC_LEN);
-#else
- mavlink_command_tc_t packet;
- packet.command_id = command_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_COMMAND_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-}
-
-/**
- * @brief Pack a command_tc 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_id A member of the MavCommandList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_command_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_COMMAND_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_TC_LEN);
-#else
- mavlink_command_tc_t packet;
- packet.command_id = command_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_COMMAND_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-}
-
-/**
- * @brief Encode a command_tc 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_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_command_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_tc_t* command_tc)
-{
- return mavlink_msg_command_tc_pack(system_id, component_id, msg, command_tc->command_id);
-}
-
-/**
- * @brief Encode a command_tc 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_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_command_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_tc_t* command_tc)
-{
- return mavlink_msg_command_tc_pack_chan(system_id, component_id, chan, msg, command_tc->command_id);
-}
-
-/**
- * @brief Send a command_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param command_id A member of the MavCommandList enum
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_command_tc_send(mavlink_channel_t chan, uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_COMMAND_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_TC, buf, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-#else
- mavlink_command_tc_t packet;
- packet.command_id = command_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_TC, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a command_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_command_tc_send_struct(mavlink_channel_t chan, const mavlink_command_tc_t* command_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_command_tc_send(chan, command_tc->command_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_TC, (const char *)command_tc, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_COMMAND_TC_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_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, command_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_TC, buf, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-#else
- mavlink_command_tc_t *packet = (mavlink_command_tc_t *)msgbuf;
- packet->command_id = command_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_TC, (const char *)packet, MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_COMMAND_TC_LEN, MAVLINK_MSG_ID_COMMAND_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE COMMAND_TC UNPACKING
-
-
-/**
- * @brief Get field command_id from command_tc message
- *
- * @return A member of the MavCommandList enum
- */
-static inline uint8_t mavlink_msg_command_tc_get_command_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a command_tc message into a struct
- *
- * @param msg The message to decode
- * @param command_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_command_tc_decode(const mavlink_message_t* msg, mavlink_command_tc_t* command_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- command_tc->command_id = mavlink_msg_command_tc_get_command_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_TC_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_TC_LEN;
- memset(command_tc, 0, MAVLINK_MSG_ID_COMMAND_TC_LEN);
- memcpy(command_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_current_tm.h b/mavlink_lib/pyxis/mavlink_msg_current_tm.h
deleted file mode 100644
index 0c267176bd001cd9cec19b888881dbd6769c6cd9..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_current_tm.h
+++ /dev/null
@@ -1,255 +0,0 @@
-#pragma once
-// MESSAGE CURRENT_TM PACKING
-
-#define MAVLINK_MSG_ID_CURRENT_TM 107
-
-
-typedef struct __mavlink_current_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float current; /*< [A] Current*/
- char sensor_id[20]; /*< Sensor name*/
-} mavlink_current_tm_t;
-
-#define MAVLINK_MSG_ID_CURRENT_TM_LEN 32
-#define MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_107_LEN 32
-#define MAVLINK_MSG_ID_107_MIN_LEN 32
-
-#define MAVLINK_MSG_ID_CURRENT_TM_CRC 222
-#define MAVLINK_MSG_ID_107_CRC 222
-
-#define MAVLINK_MSG_CURRENT_TM_FIELD_SENSOR_ID_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_CURRENT_TM { \
- 107, \
- "CURRENT_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_current_tm_t, timestamp) }, \
- { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_current_tm_t, sensor_id) }, \
- { "current", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_current_tm_t, current) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_CURRENT_TM { \
- "CURRENT_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_current_tm_t, timestamp) }, \
- { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_current_tm_t, sensor_id) }, \
- { "current", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_current_tm_t, current) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a current_tm 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] When was this logged
- * @param sensor_id Sensor name
- * @param current [A] Current
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_current_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_id, float current)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CURRENT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, current);
- _mav_put_char_array(buf, 12, sensor_id, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CURRENT_TM_LEN);
-#else
- mavlink_current_tm_t packet;
- packet.timestamp = timestamp;
- packet.current = current;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CURRENT_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_CURRENT_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-}
-
-/**
- * @brief Pack a current_tm 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] When was this logged
- * @param sensor_id Sensor name
- * @param current [A] Current
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_current_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_id,float current)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CURRENT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, current);
- _mav_put_char_array(buf, 12, sensor_id, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CURRENT_TM_LEN);
-#else
- mavlink_current_tm_t packet;
- packet.timestamp = timestamp;
- packet.current = current;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CURRENT_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_CURRENT_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-}
-
-/**
- * @brief Encode a current_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_current_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_current_tm_t* current_tm)
-{
- return mavlink_msg_current_tm_pack(system_id, component_id, msg, current_tm->timestamp, current_tm->sensor_id, current_tm->current);
-}
-
-/**
- * @brief Encode a current_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_current_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_current_tm_t* current_tm)
-{
- return mavlink_msg_current_tm_pack_chan(system_id, component_id, chan, msg, current_tm->timestamp, current_tm->sensor_id, current_tm->current);
-}
-
-/**
- * @brief Send a current_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_id Sensor name
- * @param current [A] Current
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_current_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_id, float current)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_CURRENT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, current);
- _mav_put_char_array(buf, 12, sensor_id, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CURRENT_TM, buf, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-#else
- mavlink_current_tm_t packet;
- packet.timestamp = timestamp;
- packet.current = current;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CURRENT_TM, (const char *)&packet, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a current_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_current_tm_send_struct(mavlink_channel_t chan, const mavlink_current_tm_t* current_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_current_tm_send(chan, current_tm->timestamp, current_tm->sensor_id, current_tm->current);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CURRENT_TM, (const char *)current_tm, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_CURRENT_TM_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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_id, float current)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, current);
- _mav_put_char_array(buf, 12, sensor_id, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CURRENT_TM, buf, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-#else
- mavlink_current_tm_t *packet = (mavlink_current_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->current = current;
- mav_array_memcpy(packet->sensor_id, sensor_id, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CURRENT_TM, (const char *)packet, MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN, MAVLINK_MSG_ID_CURRENT_TM_LEN, MAVLINK_MSG_ID_CURRENT_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE CURRENT_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from current_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_current_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_id from current_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_current_tm_get_sensor_id(const mavlink_message_t* msg, char *sensor_id)
-{
- return _MAV_RETURN_char_array(msg, sensor_id, 20, 12);
-}
-
-/**
- * @brief Get field current from current_tm message
- *
- * @return [A] Current
- */
-static inline float mavlink_msg_current_tm_get_current(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Decode a current_tm message into a struct
- *
- * @param msg The message to decode
- * @param current_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_current_tm_decode(const mavlink_message_t* msg, mavlink_current_tm_t* current_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- current_tm->timestamp = mavlink_msg_current_tm_get_timestamp(msg);
- current_tm->current = mavlink_msg_current_tm_get_current(msg);
- mavlink_msg_current_tm_get_sensor_id(msg, current_tm->sensor_id);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_CURRENT_TM_LEN? msg->len : MAVLINK_MSG_ID_CURRENT_TM_LEN;
- memset(current_tm, 0, MAVLINK_MSG_ID_CURRENT_TM_LEN);
- memcpy(current_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_fsm_tm.h b/mavlink_lib/pyxis/mavlink_msg_fsm_tm.h
deleted file mode 100644
index 5fc60088816ba5f4dce6687d1faa8e1b7520015e..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_fsm_tm.h
+++ /dev/null
@@ -1,338 +0,0 @@
-#pragma once
-// MESSAGE FSM_TM PACKING
-
-#define MAVLINK_MSG_ID_FSM_TM 201
-
-
-typedef struct __mavlink_fsm_tm_t {
- uint64_t timestamp; /*< [us] Timestamp*/
- uint8_t ada_state; /*< Apogee Detection Algorithm state*/
- uint8_t abk_state; /*< Air Brakes state*/
- uint8_t dpl_state; /*< Deployment state*/
- uint8_t fmm_state; /*< Flight Mode Manager state*/
- uint8_t nas_state; /*< Navigation and Attitude State state*/
-} mavlink_fsm_tm_t;
-
-#define MAVLINK_MSG_ID_FSM_TM_LEN 13
-#define MAVLINK_MSG_ID_FSM_TM_MIN_LEN 13
-#define MAVLINK_MSG_ID_201_LEN 13
-#define MAVLINK_MSG_ID_201_MIN_LEN 13
-
-#define MAVLINK_MSG_ID_FSM_TM_CRC 253
-#define MAVLINK_MSG_ID_201_CRC 253
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_FSM_TM { \
- 201, \
- "FSM_TM", \
- 6, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_fsm_tm_t, timestamp) }, \
- { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fsm_tm_t, ada_state) }, \
- { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_fsm_tm_t, abk_state) }, \
- { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_fsm_tm_t, dpl_state) }, \
- { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_fsm_tm_t, fmm_state) }, \
- { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_fsm_tm_t, nas_state) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_FSM_TM { \
- "FSM_TM", \
- 6, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_fsm_tm_t, timestamp) }, \
- { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fsm_tm_t, ada_state) }, \
- { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_fsm_tm_t, abk_state) }, \
- { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_fsm_tm_t, dpl_state) }, \
- { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_fsm_tm_t, fmm_state) }, \
- { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_fsm_tm_t, nas_state) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a fsm_tm 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
- * @param ada_state Apogee Detection Algorithm state
- * @param abk_state Air Brakes state
- * @param dpl_state Deployment state
- * @param fmm_state Flight Mode Manager state
- * @param nas_state Navigation and Attitude State state
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_fsm_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t ada_state, uint8_t abk_state, uint8_t dpl_state, uint8_t fmm_state, uint8_t nas_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_FSM_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, ada_state);
- _mav_put_uint8_t(buf, 9, abk_state);
- _mav_put_uint8_t(buf, 10, dpl_state);
- _mav_put_uint8_t(buf, 11, fmm_state);
- _mav_put_uint8_t(buf, 12, nas_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FSM_TM_LEN);
-#else
- mavlink_fsm_tm_t packet;
- packet.timestamp = timestamp;
- packet.ada_state = ada_state;
- packet.abk_state = abk_state;
- packet.dpl_state = dpl_state;
- packet.fmm_state = fmm_state;
- packet.nas_state = nas_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FSM_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_FSM_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-}
-
-/**
- * @brief Pack a fsm_tm 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
- * @param ada_state Apogee Detection Algorithm state
- * @param abk_state Air Brakes state
- * @param dpl_state Deployment state
- * @param fmm_state Flight Mode Manager state
- * @param nas_state Navigation and Attitude State state
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_fsm_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t ada_state,uint8_t abk_state,uint8_t dpl_state,uint8_t fmm_state,uint8_t nas_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_FSM_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, ada_state);
- _mav_put_uint8_t(buf, 9, abk_state);
- _mav_put_uint8_t(buf, 10, dpl_state);
- _mav_put_uint8_t(buf, 11, fmm_state);
- _mav_put_uint8_t(buf, 12, nas_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FSM_TM_LEN);
-#else
- mavlink_fsm_tm_t packet;
- packet.timestamp = timestamp;
- packet.ada_state = ada_state;
- packet.abk_state = abk_state;
- packet.dpl_state = dpl_state;
- packet.fmm_state = fmm_state;
- packet.nas_state = nas_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FSM_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_FSM_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-}
-
-/**
- * @brief Encode a fsm_tm 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 fsm_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_fsm_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fsm_tm_t* fsm_tm)
-{
- return mavlink_msg_fsm_tm_pack(system_id, component_id, msg, fsm_tm->timestamp, fsm_tm->ada_state, fsm_tm->abk_state, fsm_tm->dpl_state, fsm_tm->fmm_state, fsm_tm->nas_state);
-}
-
-/**
- * @brief Encode a fsm_tm 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 fsm_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_fsm_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fsm_tm_t* fsm_tm)
-{
- return mavlink_msg_fsm_tm_pack_chan(system_id, component_id, chan, msg, fsm_tm->timestamp, fsm_tm->ada_state, fsm_tm->abk_state, fsm_tm->dpl_state, fsm_tm->fmm_state, fsm_tm->nas_state);
-}
-
-/**
- * @brief Send a fsm_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp
- * @param ada_state Apogee Detection Algorithm state
- * @param abk_state Air Brakes state
- * @param dpl_state Deployment state
- * @param fmm_state Flight Mode Manager state
- * @param nas_state Navigation and Attitude State state
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_fsm_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t abk_state, uint8_t dpl_state, uint8_t fmm_state, uint8_t nas_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_FSM_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, ada_state);
- _mav_put_uint8_t(buf, 9, abk_state);
- _mav_put_uint8_t(buf, 10, dpl_state);
- _mav_put_uint8_t(buf, 11, fmm_state);
- _mav_put_uint8_t(buf, 12, nas_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, buf, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-#else
- mavlink_fsm_tm_t packet;
- packet.timestamp = timestamp;
- packet.ada_state = ada_state;
- packet.abk_state = abk_state;
- packet.dpl_state = dpl_state;
- packet.fmm_state = fmm_state;
- packet.nas_state = nas_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, (const char *)&packet, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a fsm_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_fsm_tm_send_struct(mavlink_channel_t chan, const mavlink_fsm_tm_t* fsm_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_fsm_tm_send(chan, fsm_tm->timestamp, fsm_tm->ada_state, fsm_tm->abk_state, fsm_tm->dpl_state, fsm_tm->fmm_state, fsm_tm->nas_state);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, (const char *)fsm_tm, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_FSM_TM_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_fsm_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t abk_state, uint8_t dpl_state, uint8_t fmm_state, uint8_t nas_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, ada_state);
- _mav_put_uint8_t(buf, 9, abk_state);
- _mav_put_uint8_t(buf, 10, dpl_state);
- _mav_put_uint8_t(buf, 11, fmm_state);
- _mav_put_uint8_t(buf, 12, nas_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, buf, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-#else
- mavlink_fsm_tm_t *packet = (mavlink_fsm_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->ada_state = ada_state;
- packet->abk_state = abk_state;
- packet->dpl_state = dpl_state;
- packet->fmm_state = fmm_state;
- packet->nas_state = nas_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FSM_TM, (const char *)packet, MAVLINK_MSG_ID_FSM_TM_MIN_LEN, MAVLINK_MSG_ID_FSM_TM_LEN, MAVLINK_MSG_ID_FSM_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE FSM_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from fsm_tm message
- *
- * @return [us] Timestamp
- */
-static inline uint64_t mavlink_msg_fsm_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field ada_state from fsm_tm message
- *
- * @return Apogee Detection Algorithm state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_ada_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 8);
-}
-
-/**
- * @brief Get field abk_state from fsm_tm message
- *
- * @return Air Brakes state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_abk_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 9);
-}
-
-/**
- * @brief Get field dpl_state from fsm_tm message
- *
- * @return Deployment state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_dpl_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 10);
-}
-
-/**
- * @brief Get field fmm_state from fsm_tm message
- *
- * @return Flight Mode Manager state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_fmm_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 11);
-}
-
-/**
- * @brief Get field nas_state from fsm_tm message
- *
- * @return Navigation and Attitude State state
- */
-static inline uint8_t mavlink_msg_fsm_tm_get_nas_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 12);
-}
-
-/**
- * @brief Decode a fsm_tm message into a struct
- *
- * @param msg The message to decode
- * @param fsm_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_fsm_tm_decode(const mavlink_message_t* msg, mavlink_fsm_tm_t* fsm_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- fsm_tm->timestamp = mavlink_msg_fsm_tm_get_timestamp(msg);
- fsm_tm->ada_state = mavlink_msg_fsm_tm_get_ada_state(msg);
- fsm_tm->abk_state = mavlink_msg_fsm_tm_get_abk_state(msg);
- fsm_tm->dpl_state = mavlink_msg_fsm_tm_get_dpl_state(msg);
- fsm_tm->fmm_state = mavlink_msg_fsm_tm_get_fmm_state(msg);
- fsm_tm->nas_state = mavlink_msg_fsm_tm_get_nas_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_FSM_TM_LEN? msg->len : MAVLINK_MSG_ID_FSM_TM_LEN;
- memset(fsm_tm, 0, MAVLINK_MSG_ID_FSM_TM_LEN);
- memcpy(fsm_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_gps_tm.h b/mavlink_lib/pyxis/mavlink_msg_gps_tm.h
deleted file mode 100644
index 779f8b8033a9814d5f605b862663eff24cdc79c5..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_gps_tm.h
+++ /dev/null
@@ -1,480 +0,0 @@
-#pragma once
-// MESSAGE GPS_TM PACKING
-
-#define MAVLINK_MSG_ID_GPS_TM 102
-
-
-typedef struct __mavlink_gps_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- double latitude; /*< [deg] Latitude*/
- double longitude; /*< [deg] Longitude*/
- double height; /*< [m] Altitude*/
- float vel_north; /*< [m/s] Velocity in NED frame (north)*/
- float vel_east; /*< [m/s] Velocity in NED frame (east)*/
- float vel_down; /*< [m/s] Velocity in NED frame (down)*/
- float speed; /*< [m/s] Speed*/
- float track; /*< [deg] Track*/
- char sensor_id[20]; /*< Sensor name*/
- uint8_t fix; /*< Wether the GPS has a FIX*/
- uint8_t n_satellites; /*< Number of connected satellites*/
-} mavlink_gps_tm_t;
-
-#define MAVLINK_MSG_ID_GPS_TM_LEN 74
-#define MAVLINK_MSG_ID_GPS_TM_MIN_LEN 74
-#define MAVLINK_MSG_ID_102_LEN 74
-#define MAVLINK_MSG_ID_102_MIN_LEN 74
-
-#define MAVLINK_MSG_ID_GPS_TM_CRC 39
-#define MAVLINK_MSG_ID_102_CRC 39
-
-#define MAVLINK_MSG_GPS_TM_FIELD_SENSOR_ID_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_GPS_TM { \
- 102, \
- "GPS_TM", \
- 12, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_tm_t, timestamp) }, \
- { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 52, offsetof(mavlink_gps_tm_t, sensor_id) }, \
- { "fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 72, offsetof(mavlink_gps_tm_t, fix) }, \
- { "latitude", NULL, MAVLINK_TYPE_DOUBLE, 0, 8, offsetof(mavlink_gps_tm_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_DOUBLE, 0, 16, offsetof(mavlink_gps_tm_t, longitude) }, \
- { "height", NULL, MAVLINK_TYPE_DOUBLE, 0, 24, offsetof(mavlink_gps_tm_t, height) }, \
- { "vel_north", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_tm_t, vel_north) }, \
- { "vel_east", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gps_tm_t, vel_east) }, \
- { "vel_down", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gps_tm_t, vel_down) }, \
- { "speed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_tm_t, speed) }, \
- { "track", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_tm_t, track) }, \
- { "n_satellites", NULL, MAVLINK_TYPE_UINT8_T, 0, 73, offsetof(mavlink_gps_tm_t, n_satellites) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_GPS_TM { \
- "GPS_TM", \
- 12, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_tm_t, timestamp) }, \
- { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 52, offsetof(mavlink_gps_tm_t, sensor_id) }, \
- { "fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 72, offsetof(mavlink_gps_tm_t, fix) }, \
- { "latitude", NULL, MAVLINK_TYPE_DOUBLE, 0, 8, offsetof(mavlink_gps_tm_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_DOUBLE, 0, 16, offsetof(mavlink_gps_tm_t, longitude) }, \
- { "height", NULL, MAVLINK_TYPE_DOUBLE, 0, 24, offsetof(mavlink_gps_tm_t, height) }, \
- { "vel_north", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_tm_t, vel_north) }, \
- { "vel_east", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gps_tm_t, vel_east) }, \
- { "vel_down", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gps_tm_t, vel_down) }, \
- { "speed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_tm_t, speed) }, \
- { "track", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_tm_t, track) }, \
- { "n_satellites", NULL, MAVLINK_TYPE_UINT8_T, 0, 73, offsetof(mavlink_gps_tm_t, n_satellites) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a gps_tm 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] When was this logged
- * @param sensor_id Sensor name
- * @param fix Wether the GPS has a FIX
- * @param latitude [deg] Latitude
- * @param longitude [deg] Longitude
- * @param height [m] Altitude
- * @param vel_north [m/s] Velocity in NED frame (north)
- * @param vel_east [m/s] Velocity in NED frame (east)
- * @param vel_down [m/s] Velocity in NED frame (down)
- * @param speed [m/s] Speed
- * @param track [deg] Track
- * @param n_satellites Number of connected satellites
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_gps_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_id, uint8_t fix, double latitude, double longitude, double height, float vel_north, float vel_east, float vel_down, float speed, float track, uint8_t n_satellites)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GPS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, latitude);
- _mav_put_double(buf, 16, longitude);
- _mav_put_double(buf, 24, height);
- _mav_put_float(buf, 32, vel_north);
- _mav_put_float(buf, 36, vel_east);
- _mav_put_float(buf, 40, vel_down);
- _mav_put_float(buf, 44, speed);
- _mav_put_float(buf, 48, track);
- _mav_put_uint8_t(buf, 72, fix);
- _mav_put_uint8_t(buf, 73, n_satellites);
- _mav_put_char_array(buf, 52, sensor_id, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_TM_LEN);
-#else
- mavlink_gps_tm_t packet;
- packet.timestamp = timestamp;
- packet.latitude = latitude;
- packet.longitude = longitude;
- packet.height = height;
- packet.vel_north = vel_north;
- packet.vel_east = vel_east;
- packet.vel_down = vel_down;
- packet.speed = speed;
- packet.track = track;
- packet.fix = fix;
- packet.n_satellites = n_satellites;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_GPS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-}
-
-/**
- * @brief Pack a gps_tm 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] When was this logged
- * @param sensor_id Sensor name
- * @param fix Wether the GPS has a FIX
- * @param latitude [deg] Latitude
- * @param longitude [deg] Longitude
- * @param height [m] Altitude
- * @param vel_north [m/s] Velocity in NED frame (north)
- * @param vel_east [m/s] Velocity in NED frame (east)
- * @param vel_down [m/s] Velocity in NED frame (down)
- * @param speed [m/s] Speed
- * @param track [deg] Track
- * @param n_satellites Number of connected satellites
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_gps_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_id,uint8_t fix,double latitude,double longitude,double height,float vel_north,float vel_east,float vel_down,float speed,float track,uint8_t n_satellites)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GPS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, latitude);
- _mav_put_double(buf, 16, longitude);
- _mav_put_double(buf, 24, height);
- _mav_put_float(buf, 32, vel_north);
- _mav_put_float(buf, 36, vel_east);
- _mav_put_float(buf, 40, vel_down);
- _mav_put_float(buf, 44, speed);
- _mav_put_float(buf, 48, track);
- _mav_put_uint8_t(buf, 72, fix);
- _mav_put_uint8_t(buf, 73, n_satellites);
- _mav_put_char_array(buf, 52, sensor_id, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_TM_LEN);
-#else
- mavlink_gps_tm_t packet;
- packet.timestamp = timestamp;
- packet.latitude = latitude;
- packet.longitude = longitude;
- packet.height = height;
- packet.vel_north = vel_north;
- packet.vel_east = vel_east;
- packet.vel_down = vel_down;
- packet.speed = speed;
- packet.track = track;
- packet.fix = fix;
- packet.n_satellites = n_satellites;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_GPS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-}
-
-/**
- * @brief Encode a gps_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_gps_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_tm_t* gps_tm)
-{
- return mavlink_msg_gps_tm_pack(system_id, component_id, msg, gps_tm->timestamp, gps_tm->sensor_id, gps_tm->fix, gps_tm->latitude, gps_tm->longitude, gps_tm->height, gps_tm->vel_north, gps_tm->vel_east, gps_tm->vel_down, gps_tm->speed, gps_tm->track, gps_tm->n_satellites);
-}
-
-/**
- * @brief Encode a gps_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_gps_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_tm_t* gps_tm)
-{
- return mavlink_msg_gps_tm_pack_chan(system_id, component_id, chan, msg, gps_tm->timestamp, gps_tm->sensor_id, gps_tm->fix, gps_tm->latitude, gps_tm->longitude, gps_tm->height, gps_tm->vel_north, gps_tm->vel_east, gps_tm->vel_down, gps_tm->speed, gps_tm->track, gps_tm->n_satellites);
-}
-
-/**
- * @brief Send a gps_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_id Sensor name
- * @param fix Wether the GPS has a FIX
- * @param latitude [deg] Latitude
- * @param longitude [deg] Longitude
- * @param height [m] Altitude
- * @param vel_north [m/s] Velocity in NED frame (north)
- * @param vel_east [m/s] Velocity in NED frame (east)
- * @param vel_down [m/s] Velocity in NED frame (down)
- * @param speed [m/s] Speed
- * @param track [deg] Track
- * @param n_satellites Number of connected satellites
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_gps_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_id, uint8_t fix, double latitude, double longitude, double height, float vel_north, float vel_east, float vel_down, float speed, float track, uint8_t n_satellites)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_GPS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, latitude);
- _mav_put_double(buf, 16, longitude);
- _mav_put_double(buf, 24, height);
- _mav_put_float(buf, 32, vel_north);
- _mav_put_float(buf, 36, vel_east);
- _mav_put_float(buf, 40, vel_down);
- _mav_put_float(buf, 44, speed);
- _mav_put_float(buf, 48, track);
- _mav_put_uint8_t(buf, 72, fix);
- _mav_put_uint8_t(buf, 73, n_satellites);
- _mav_put_char_array(buf, 52, sensor_id, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, buf, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#else
- mavlink_gps_tm_t packet;
- packet.timestamp = timestamp;
- packet.latitude = latitude;
- packet.longitude = longitude;
- packet.height = height;
- packet.vel_north = vel_north;
- packet.vel_east = vel_east;
- packet.vel_down = vel_down;
- packet.speed = speed;
- packet.track = track;
- packet.fix = fix;
- packet.n_satellites = n_satellites;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, (const char *)&packet, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a gps_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_gps_tm_send_struct(mavlink_channel_t chan, const mavlink_gps_tm_t* gps_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_gps_tm_send(chan, gps_tm->timestamp, gps_tm->sensor_id, gps_tm->fix, gps_tm->latitude, gps_tm->longitude, gps_tm->height, gps_tm->vel_north, gps_tm->vel_east, gps_tm->vel_down, gps_tm->speed, gps_tm->track, gps_tm->n_satellites);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, (const char *)gps_tm, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_GPS_TM_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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_id, uint8_t fix, double latitude, double longitude, double height, float vel_north, float vel_east, float vel_down, float speed, float track, uint8_t n_satellites)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_double(buf, 8, latitude);
- _mav_put_double(buf, 16, longitude);
- _mav_put_double(buf, 24, height);
- _mav_put_float(buf, 32, vel_north);
- _mav_put_float(buf, 36, vel_east);
- _mav_put_float(buf, 40, vel_down);
- _mav_put_float(buf, 44, speed);
- _mav_put_float(buf, 48, track);
- _mav_put_uint8_t(buf, 72, fix);
- _mav_put_uint8_t(buf, 73, n_satellites);
- _mav_put_char_array(buf, 52, sensor_id, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, buf, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#else
- mavlink_gps_tm_t *packet = (mavlink_gps_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->latitude = latitude;
- packet->longitude = longitude;
- packet->height = height;
- packet->vel_north = vel_north;
- packet->vel_east = vel_east;
- packet->vel_down = vel_down;
- packet->speed = speed;
- packet->track = track;
- packet->fix = fix;
- packet->n_satellites = n_satellites;
- mav_array_memcpy(packet->sensor_id, sensor_id, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_TM, (const char *)packet, MAVLINK_MSG_ID_GPS_TM_MIN_LEN, MAVLINK_MSG_ID_GPS_TM_LEN, MAVLINK_MSG_ID_GPS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE GPS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from gps_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_gps_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_id from gps_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_gps_tm_get_sensor_id(const mavlink_message_t* msg, char *sensor_id)
-{
- return _MAV_RETURN_char_array(msg, sensor_id, 20, 52);
-}
-
-/**
- * @brief Get field fix from gps_tm message
- *
- * @return Wether the GPS has a FIX
- */
-static inline uint8_t mavlink_msg_gps_tm_get_fix(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 72);
-}
-
-/**
- * @brief Get field latitude from gps_tm message
- *
- * @return [deg] Latitude
- */
-static inline double mavlink_msg_gps_tm_get_latitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_double(msg, 8);
-}
-
-/**
- * @brief Get field longitude from gps_tm message
- *
- * @return [deg] Longitude
- */
-static inline double mavlink_msg_gps_tm_get_longitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_double(msg, 16);
-}
-
-/**
- * @brief Get field height from gps_tm message
- *
- * @return [m] Altitude
- */
-static inline double mavlink_msg_gps_tm_get_height(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_double(msg, 24);
-}
-
-/**
- * @brief Get field vel_north from gps_tm message
- *
- * @return [m/s] Velocity in NED frame (north)
- */
-static inline float mavlink_msg_gps_tm_get_vel_north(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field vel_east from gps_tm message
- *
- * @return [m/s] Velocity in NED frame (east)
- */
-static inline float mavlink_msg_gps_tm_get_vel_east(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field vel_down from gps_tm message
- *
- * @return [m/s] Velocity in NED frame (down)
- */
-static inline float mavlink_msg_gps_tm_get_vel_down(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field speed from gps_tm message
- *
- * @return [m/s] Speed
- */
-static inline float mavlink_msg_gps_tm_get_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field track from gps_tm message
- *
- * @return [deg] Track
- */
-static inline float mavlink_msg_gps_tm_get_track(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field n_satellites from gps_tm message
- *
- * @return Number of connected satellites
- */
-static inline uint8_t mavlink_msg_gps_tm_get_n_satellites(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 73);
-}
-
-/**
- * @brief Decode a gps_tm message into a struct
- *
- * @param msg The message to decode
- * @param gps_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_gps_tm_decode(const mavlink_message_t* msg, mavlink_gps_tm_t* gps_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- gps_tm->timestamp = mavlink_msg_gps_tm_get_timestamp(msg);
- gps_tm->latitude = mavlink_msg_gps_tm_get_latitude(msg);
- gps_tm->longitude = mavlink_msg_gps_tm_get_longitude(msg);
- gps_tm->height = mavlink_msg_gps_tm_get_height(msg);
- gps_tm->vel_north = mavlink_msg_gps_tm_get_vel_north(msg);
- gps_tm->vel_east = mavlink_msg_gps_tm_get_vel_east(msg);
- gps_tm->vel_down = mavlink_msg_gps_tm_get_vel_down(msg);
- gps_tm->speed = mavlink_msg_gps_tm_get_speed(msg);
- gps_tm->track = mavlink_msg_gps_tm_get_track(msg);
- mavlink_msg_gps_tm_get_sensor_id(msg, gps_tm->sensor_id);
- gps_tm->fix = mavlink_msg_gps_tm_get_fix(msg);
- gps_tm->n_satellites = mavlink_msg_gps_tm_get_n_satellites(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_TM_LEN? msg->len : MAVLINK_MSG_ID_GPS_TM_LEN;
- memset(gps_tm, 0, MAVLINK_MSG_ID_GPS_TM_LEN);
- memcpy(gps_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_imu_tm.h b/mavlink_lib/pyxis/mavlink_msg_imu_tm.h
deleted file mode 100644
index c522e3adb13d141fca4f4fe3b1aff4ad0a4328fd..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_imu_tm.h
+++ /dev/null
@@ -1,455 +0,0 @@
-#pragma once
-// MESSAGE IMU_TM PACKING
-
-#define MAVLINK_MSG_ID_IMU_TM 103
-
-
-typedef struct __mavlink_imu_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float acc_x; /*< [m/s2] X axis acceleration*/
- float acc_y; /*< [m/s2] Y axis acceleration*/
- float acc_z; /*< [m/s2] Z axis acceleration*/
- float gyro_x; /*< [rad/s] X axis gyro*/
- float gyro_y; /*< [rad/s] Y axis gyro*/
- float gyro_z; /*< [rad/s] Z axis gyro*/
- float mag_x; /*< [uT] X axis compass*/
- float mag_y; /*< [uT] Y axis compass*/
- float mag_z; /*< [uT] Z axis compass*/
- char sensor_id[20]; /*< Sensor name*/
-} mavlink_imu_tm_t;
-
-#define MAVLINK_MSG_ID_IMU_TM_LEN 64
-#define MAVLINK_MSG_ID_IMU_TM_MIN_LEN 64
-#define MAVLINK_MSG_ID_103_LEN 64
-#define MAVLINK_MSG_ID_103_MIN_LEN 64
-
-#define MAVLINK_MSG_ID_IMU_TM_CRC 178
-#define MAVLINK_MSG_ID_103_CRC 178
-
-#define MAVLINK_MSG_IMU_TM_FIELD_SENSOR_ID_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_IMU_TM { \
- 103, \
- "IMU_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_imu_tm_t, timestamp) }, \
- { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 44, offsetof(mavlink_imu_tm_t, sensor_id) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_imu_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_imu_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_imu_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_imu_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_imu_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_imu_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_imu_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_imu_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_imu_tm_t, mag_z) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_IMU_TM { \
- "IMU_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_imu_tm_t, timestamp) }, \
- { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 44, offsetof(mavlink_imu_tm_t, sensor_id) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_imu_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_imu_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_imu_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_imu_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_imu_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_imu_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_imu_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_imu_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_imu_tm_t, mag_z) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a imu_tm 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] When was this logged
- * @param sensor_id Sensor name
- * @param acc_x [m/s2] X axis acceleration
- * @param acc_y [m/s2] Y axis acceleration
- * @param acc_z [m/s2] Z axis acceleration
- * @param gyro_x [rad/s] X axis gyro
- * @param gyro_y [rad/s] Y axis gyro
- * @param gyro_z [rad/s] Z axis gyro
- * @param mag_x [uT] X axis compass
- * @param mag_y [uT] Y axis compass
- * @param mag_z [uT] Z axis compass
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_imu_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_id, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_IMU_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, mag_x);
- _mav_put_float(buf, 36, mag_y);
- _mav_put_float(buf, 40, mag_z);
- _mav_put_char_array(buf, 44, sensor_id, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IMU_TM_LEN);
-#else
- mavlink_imu_tm_t packet;
- packet.timestamp = timestamp;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IMU_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_IMU_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-}
-
-/**
- * @brief Pack a imu_tm 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] When was this logged
- * @param sensor_id Sensor name
- * @param acc_x [m/s2] X axis acceleration
- * @param acc_y [m/s2] Y axis acceleration
- * @param acc_z [m/s2] Z axis acceleration
- * @param gyro_x [rad/s] X axis gyro
- * @param gyro_y [rad/s] Y axis gyro
- * @param gyro_z [rad/s] Z axis gyro
- * @param mag_x [uT] X axis compass
- * @param mag_y [uT] Y axis compass
- * @param mag_z [uT] Z axis compass
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_imu_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_id,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_IMU_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, mag_x);
- _mav_put_float(buf, 36, mag_y);
- _mav_put_float(buf, 40, mag_z);
- _mav_put_char_array(buf, 44, sensor_id, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IMU_TM_LEN);
-#else
- mavlink_imu_tm_t packet;
- packet.timestamp = timestamp;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IMU_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_IMU_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-}
-
-/**
- * @brief Encode a imu_tm 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 imu_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_imu_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_imu_tm_t* imu_tm)
-{
- return mavlink_msg_imu_tm_pack(system_id, component_id, msg, imu_tm->timestamp, imu_tm->sensor_id, imu_tm->acc_x, imu_tm->acc_y, imu_tm->acc_z, imu_tm->gyro_x, imu_tm->gyro_y, imu_tm->gyro_z, imu_tm->mag_x, imu_tm->mag_y, imu_tm->mag_z);
-}
-
-/**
- * @brief Encode a imu_tm 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 imu_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_imu_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_imu_tm_t* imu_tm)
-{
- return mavlink_msg_imu_tm_pack_chan(system_id, component_id, chan, msg, imu_tm->timestamp, imu_tm->sensor_id, imu_tm->acc_x, imu_tm->acc_y, imu_tm->acc_z, imu_tm->gyro_x, imu_tm->gyro_y, imu_tm->gyro_z, imu_tm->mag_x, imu_tm->mag_y, imu_tm->mag_z);
-}
-
-/**
- * @brief Send a imu_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_id Sensor name
- * @param acc_x [m/s2] X axis acceleration
- * @param acc_y [m/s2] Y axis acceleration
- * @param acc_z [m/s2] Z axis acceleration
- * @param gyro_x [rad/s] X axis gyro
- * @param gyro_y [rad/s] Y axis gyro
- * @param gyro_z [rad/s] Z axis gyro
- * @param mag_x [uT] X axis compass
- * @param mag_y [uT] Y axis compass
- * @param mag_z [uT] Z axis compass
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_imu_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_id, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_IMU_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, mag_x);
- _mav_put_float(buf, 36, mag_y);
- _mav_put_float(buf, 40, mag_z);
- _mav_put_char_array(buf, 44, sensor_id, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMU_TM, buf, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-#else
- mavlink_imu_tm_t packet;
- packet.timestamp = timestamp;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMU_TM, (const char *)&packet, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a imu_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_imu_tm_send_struct(mavlink_channel_t chan, const mavlink_imu_tm_t* imu_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_imu_tm_send(chan, imu_tm->timestamp, imu_tm->sensor_id, imu_tm->acc_x, imu_tm->acc_y, imu_tm->acc_z, imu_tm->gyro_x, imu_tm->gyro_y, imu_tm->gyro_z, imu_tm->mag_x, imu_tm->mag_y, imu_tm->mag_z);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMU_TM, (const char *)imu_tm, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_IMU_TM_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_imu_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_id, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, acc_x);
- _mav_put_float(buf, 12, acc_y);
- _mav_put_float(buf, 16, acc_z);
- _mav_put_float(buf, 20, gyro_x);
- _mav_put_float(buf, 24, gyro_y);
- _mav_put_float(buf, 28, gyro_z);
- _mav_put_float(buf, 32, mag_x);
- _mav_put_float(buf, 36, mag_y);
- _mav_put_float(buf, 40, mag_z);
- _mav_put_char_array(buf, 44, sensor_id, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMU_TM, buf, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-#else
- mavlink_imu_tm_t *packet = (mavlink_imu_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->acc_x = acc_x;
- packet->acc_y = acc_y;
- packet->acc_z = acc_z;
- packet->gyro_x = gyro_x;
- packet->gyro_y = gyro_y;
- packet->gyro_z = gyro_z;
- packet->mag_x = mag_x;
- packet->mag_y = mag_y;
- packet->mag_z = mag_z;
- mav_array_memcpy(packet->sensor_id, sensor_id, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMU_TM, (const char *)packet, MAVLINK_MSG_ID_IMU_TM_MIN_LEN, MAVLINK_MSG_ID_IMU_TM_LEN, MAVLINK_MSG_ID_IMU_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE IMU_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from imu_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_imu_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_id from imu_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_imu_tm_get_sensor_id(const mavlink_message_t* msg, char *sensor_id)
-{
- return _MAV_RETURN_char_array(msg, sensor_id, 20, 44);
-}
-
-/**
- * @brief Get field acc_x from imu_tm message
- *
- * @return [m/s2] X axis acceleration
- */
-static inline float mavlink_msg_imu_tm_get_acc_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field acc_y from imu_tm message
- *
- * @return [m/s2] Y axis acceleration
- */
-static inline float mavlink_msg_imu_tm_get_acc_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field acc_z from imu_tm message
- *
- * @return [m/s2] Z axis acceleration
- */
-static inline float mavlink_msg_imu_tm_get_acc_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field gyro_x from imu_tm message
- *
- * @return [rad/s] X axis gyro
- */
-static inline float mavlink_msg_imu_tm_get_gyro_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field gyro_y from imu_tm message
- *
- * @return [rad/s] Y axis gyro
- */
-static inline float mavlink_msg_imu_tm_get_gyro_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field gyro_z from imu_tm message
- *
- * @return [rad/s] Z axis gyro
- */
-static inline float mavlink_msg_imu_tm_get_gyro_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field mag_x from imu_tm message
- *
- * @return [uT] X axis compass
- */
-static inline float mavlink_msg_imu_tm_get_mag_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field mag_y from imu_tm message
- *
- * @return [uT] Y axis compass
- */
-static inline float mavlink_msg_imu_tm_get_mag_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field mag_z from imu_tm message
- *
- * @return [uT] Z axis compass
- */
-static inline float mavlink_msg_imu_tm_get_mag_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Decode a imu_tm message into a struct
- *
- * @param msg The message to decode
- * @param imu_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_imu_tm_decode(const mavlink_message_t* msg, mavlink_imu_tm_t* imu_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- imu_tm->timestamp = mavlink_msg_imu_tm_get_timestamp(msg);
- imu_tm->acc_x = mavlink_msg_imu_tm_get_acc_x(msg);
- imu_tm->acc_y = mavlink_msg_imu_tm_get_acc_y(msg);
- imu_tm->acc_z = mavlink_msg_imu_tm_get_acc_z(msg);
- imu_tm->gyro_x = mavlink_msg_imu_tm_get_gyro_x(msg);
- imu_tm->gyro_y = mavlink_msg_imu_tm_get_gyro_y(msg);
- imu_tm->gyro_z = mavlink_msg_imu_tm_get_gyro_z(msg);
- imu_tm->mag_x = mavlink_msg_imu_tm_get_mag_x(msg);
- imu_tm->mag_y = mavlink_msg_imu_tm_get_mag_y(msg);
- imu_tm->mag_z = mavlink_msg_imu_tm_get_mag_z(msg);
- mavlink_msg_imu_tm_get_sensor_id(msg, imu_tm->sensor_id);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_IMU_TM_LEN? msg->len : MAVLINK_MSG_ID_IMU_TM_LEN;
- memset(imu_tm, 0, MAVLINK_MSG_ID_IMU_TM_LEN);
- memcpy(imu_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_load_tm.h b/mavlink_lib/pyxis/mavlink_msg_load_tm.h
deleted file mode 100644
index ce806b6fb8ec732673118daab24fea12d112c796..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_load_tm.h
+++ /dev/null
@@ -1,255 +0,0 @@
-#pragma once
-// MESSAGE LOAD_TM PACKING
-
-#define MAVLINK_MSG_ID_LOAD_TM 109
-
-
-typedef struct __mavlink_load_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float load; /*< [deg] Load force*/
- char sensor_id[20]; /*< Sensor name*/
-} mavlink_load_tm_t;
-
-#define MAVLINK_MSG_ID_LOAD_TM_LEN 32
-#define MAVLINK_MSG_ID_LOAD_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_109_LEN 32
-#define MAVLINK_MSG_ID_109_MIN_LEN 32
-
-#define MAVLINK_MSG_ID_LOAD_TM_CRC 233
-#define MAVLINK_MSG_ID_109_CRC 233
-
-#define MAVLINK_MSG_LOAD_TM_FIELD_SENSOR_ID_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_LOAD_TM { \
- 109, \
- "LOAD_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_load_tm_t, timestamp) }, \
- { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_load_tm_t, sensor_id) }, \
- { "load", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_load_tm_t, load) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_LOAD_TM { \
- "LOAD_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_load_tm_t, timestamp) }, \
- { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_load_tm_t, sensor_id) }, \
- { "load", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_load_tm_t, load) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a load_tm 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] When was this logged
- * @param sensor_id Sensor name
- * @param load [deg] Load force
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_load_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_id, float load)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOAD_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, load);
- _mav_put_char_array(buf, 12, sensor_id, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOAD_TM_LEN);
-#else
- mavlink_load_tm_t packet;
- packet.timestamp = timestamp;
- packet.load = load;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOAD_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LOAD_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-}
-
-/**
- * @brief Pack a load_tm 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] When was this logged
- * @param sensor_id Sensor name
- * @param load [deg] Load force
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_load_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_id,float load)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOAD_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, load);
- _mav_put_char_array(buf, 12, sensor_id, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOAD_TM_LEN);
-#else
- mavlink_load_tm_t packet;
- packet.timestamp = timestamp;
- packet.load = load;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOAD_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LOAD_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-}
-
-/**
- * @brief Encode a load_tm 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 load_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_load_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_load_tm_t* load_tm)
-{
- return mavlink_msg_load_tm_pack(system_id, component_id, msg, load_tm->timestamp, load_tm->sensor_id, load_tm->load);
-}
-
-/**
- * @brief Encode a load_tm 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 load_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_load_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_load_tm_t* load_tm)
-{
- return mavlink_msg_load_tm_pack_chan(system_id, component_id, chan, msg, load_tm->timestamp, load_tm->sensor_id, load_tm->load);
-}
-
-/**
- * @brief Send a load_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_id Sensor name
- * @param load [deg] Load force
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_load_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_id, float load)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOAD_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, load);
- _mav_put_char_array(buf, 12, sensor_id, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOAD_TM, buf, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-#else
- mavlink_load_tm_t packet;
- packet.timestamp = timestamp;
- packet.load = load;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOAD_TM, (const char *)&packet, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a load_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_load_tm_send_struct(mavlink_channel_t chan, const mavlink_load_tm_t* load_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_load_tm_send(chan, load_tm->timestamp, load_tm->sensor_id, load_tm->load);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOAD_TM, (const char *)load_tm, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_LOAD_TM_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_load_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_id, float load)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, load);
- _mav_put_char_array(buf, 12, sensor_id, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOAD_TM, buf, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-#else
- mavlink_load_tm_t *packet = (mavlink_load_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->load = load;
- mav_array_memcpy(packet->sensor_id, sensor_id, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOAD_TM, (const char *)packet, MAVLINK_MSG_ID_LOAD_TM_MIN_LEN, MAVLINK_MSG_ID_LOAD_TM_LEN, MAVLINK_MSG_ID_LOAD_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE LOAD_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from load_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_load_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_id from load_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_load_tm_get_sensor_id(const mavlink_message_t* msg, char *sensor_id)
-{
- return _MAV_RETURN_char_array(msg, sensor_id, 20, 12);
-}
-
-/**
- * @brief Get field load from load_tm message
- *
- * @return [deg] Load force
- */
-static inline float mavlink_msg_load_tm_get_load(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Decode a load_tm message into a struct
- *
- * @param msg The message to decode
- * @param load_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_load_tm_decode(const mavlink_message_t* msg, mavlink_load_tm_t* load_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- load_tm->timestamp = mavlink_msg_load_tm_get_timestamp(msg);
- load_tm->load = mavlink_msg_load_tm_get_load(msg);
- mavlink_msg_load_tm_get_sensor_id(msg, load_tm->sensor_id);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_LOAD_TM_LEN? msg->len : MAVLINK_MSG_ID_LOAD_TM_LEN;
- memset(load_tm, 0, MAVLINK_MSG_ID_LOAD_TM_LEN);
- memcpy(load_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_logger_tm.h b/mavlink_lib/pyxis/mavlink_msg_logger_tm.h
deleted file mode 100644
index ac52b5a9d5faa26bb0047de6f0c67293ff6fe4f5..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_logger_tm.h
+++ /dev/null
@@ -1,463 +0,0 @@
-#pragma once
-// MESSAGE LOGGER_TM PACKING
-
-#define MAVLINK_MSG_ID_LOGGER_TM 202
-
-
-typedef struct __mavlink_logger_tm_t {
- uint64_t timestamp; /*< [us] Timestamp*/
- int32_t too_large_samples; /*< Number of dropped samples because too large*/
- int32_t dropped_samples; /*< Number of dropped samples due to fifo full*/
- int32_t queued_samples; /*< Number of samples written to buffer*/
- int32_t buffers_filled; /*< Number of buffers filled*/
- int32_t buffers_written; /*< Number of buffers written to disk*/
- int32_t writes_failed; /*< Number of fwrite() that failed*/
- int32_t last_write_error; /*< Error of the last fwrite() that failed*/
- int32_t average_write_time; /*< Average time to perform an fwrite() of a buffer*/
- int32_t max_write_time; /*< Max time to perform an fwrite() of a buffer*/
- int16_t log_number; /*< Currently active log file, -1 if the logger is inactive*/
-} mavlink_logger_tm_t;
-
-#define MAVLINK_MSG_ID_LOGGER_TM_LEN 46
-#define MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN 46
-#define MAVLINK_MSG_ID_202_LEN 46
-#define MAVLINK_MSG_ID_202_MIN_LEN 46
-
-#define MAVLINK_MSG_ID_LOGGER_TM_CRC 142
-#define MAVLINK_MSG_ID_202_CRC 142
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_LOGGER_TM { \
- 202, \
- "LOGGER_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_logger_tm_t, timestamp) }, \
- { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_logger_tm_t, log_number) }, \
- { "too_large_samples", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_logger_tm_t, too_large_samples) }, \
- { "dropped_samples", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_logger_tm_t, dropped_samples) }, \
- { "queued_samples", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_logger_tm_t, queued_samples) }, \
- { "buffers_filled", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_logger_tm_t, buffers_filled) }, \
- { "buffers_written", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_logger_tm_t, buffers_written) }, \
- { "writes_failed", NULL, MAVLINK_TYPE_INT32_T, 0, 28, offsetof(mavlink_logger_tm_t, writes_failed) }, \
- { "last_write_error", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_logger_tm_t, last_write_error) }, \
- { "average_write_time", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_logger_tm_t, average_write_time) }, \
- { "max_write_time", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_logger_tm_t, max_write_time) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_LOGGER_TM { \
- "LOGGER_TM", \
- 11, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_logger_tm_t, timestamp) }, \
- { "log_number", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_logger_tm_t, log_number) }, \
- { "too_large_samples", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_logger_tm_t, too_large_samples) }, \
- { "dropped_samples", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_logger_tm_t, dropped_samples) }, \
- { "queued_samples", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_logger_tm_t, queued_samples) }, \
- { "buffers_filled", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_logger_tm_t, buffers_filled) }, \
- { "buffers_written", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_logger_tm_t, buffers_written) }, \
- { "writes_failed", NULL, MAVLINK_TYPE_INT32_T, 0, 28, offsetof(mavlink_logger_tm_t, writes_failed) }, \
- { "last_write_error", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_logger_tm_t, last_write_error) }, \
- { "average_write_time", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_logger_tm_t, average_write_time) }, \
- { "max_write_time", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_logger_tm_t, max_write_time) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a logger_tm 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
- * @param log_number Currently active log file, -1 if the logger is inactive
- * @param too_large_samples Number of dropped samples because too large
- * @param dropped_samples Number of dropped samples due to fifo full
- * @param queued_samples Number of samples written to buffer
- * @param buffers_filled Number of buffers filled
- * @param buffers_written Number of buffers written to disk
- * @param writes_failed Number of fwrite() that failed
- * @param last_write_error Error of the last fwrite() that failed
- * @param average_write_time Average time to perform an fwrite() of a buffer
- * @param max_write_time Max time to perform an fwrite() of a buffer
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_logger_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, int16_t log_number, int32_t too_large_samples, int32_t dropped_samples, int32_t queued_samples, int32_t buffers_filled, int32_t buffers_written, int32_t writes_failed, int32_t last_write_error, int32_t average_write_time, int32_t max_write_time)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOGGER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 8, too_large_samples);
- _mav_put_int32_t(buf, 12, dropped_samples);
- _mav_put_int32_t(buf, 16, queued_samples);
- _mav_put_int32_t(buf, 20, buffers_filled);
- _mav_put_int32_t(buf, 24, buffers_written);
- _mav_put_int32_t(buf, 28, writes_failed);
- _mav_put_int32_t(buf, 32, last_write_error);
- _mav_put_int32_t(buf, 36, average_write_time);
- _mav_put_int32_t(buf, 40, max_write_time);
- _mav_put_int16_t(buf, 44, log_number);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGER_TM_LEN);
-#else
- mavlink_logger_tm_t packet;
- packet.timestamp = timestamp;
- packet.too_large_samples = too_large_samples;
- packet.dropped_samples = dropped_samples;
- packet.queued_samples = queued_samples;
- packet.buffers_filled = buffers_filled;
- packet.buffers_written = buffers_written;
- packet.writes_failed = writes_failed;
- packet.last_write_error = last_write_error;
- packet.average_write_time = average_write_time;
- packet.max_write_time = max_write_time;
- packet.log_number = log_number;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGER_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LOGGER_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-}
-
-/**
- * @brief Pack a logger_tm 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
- * @param log_number Currently active log file, -1 if the logger is inactive
- * @param too_large_samples Number of dropped samples because too large
- * @param dropped_samples Number of dropped samples due to fifo full
- * @param queued_samples Number of samples written to buffer
- * @param buffers_filled Number of buffers filled
- * @param buffers_written Number of buffers written to disk
- * @param writes_failed Number of fwrite() that failed
- * @param last_write_error Error of the last fwrite() that failed
- * @param average_write_time Average time to perform an fwrite() of a buffer
- * @param max_write_time Max time to perform an fwrite() of a buffer
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_logger_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,int16_t log_number,int32_t too_large_samples,int32_t dropped_samples,int32_t queued_samples,int32_t buffers_filled,int32_t buffers_written,int32_t writes_failed,int32_t last_write_error,int32_t average_write_time,int32_t max_write_time)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOGGER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 8, too_large_samples);
- _mav_put_int32_t(buf, 12, dropped_samples);
- _mav_put_int32_t(buf, 16, queued_samples);
- _mav_put_int32_t(buf, 20, buffers_filled);
- _mav_put_int32_t(buf, 24, buffers_written);
- _mav_put_int32_t(buf, 28, writes_failed);
- _mav_put_int32_t(buf, 32, last_write_error);
- _mav_put_int32_t(buf, 36, average_write_time);
- _mav_put_int32_t(buf, 40, max_write_time);
- _mav_put_int16_t(buf, 44, log_number);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGER_TM_LEN);
-#else
- mavlink_logger_tm_t packet;
- packet.timestamp = timestamp;
- packet.too_large_samples = too_large_samples;
- packet.dropped_samples = dropped_samples;
- packet.queued_samples = queued_samples;
- packet.buffers_filled = buffers_filled;
- packet.buffers_written = buffers_written;
- packet.writes_failed = writes_failed;
- packet.last_write_error = last_write_error;
- packet.average_write_time = average_write_time;
- packet.max_write_time = max_write_time;
- packet.log_number = log_number;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGER_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LOGGER_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-}
-
-/**
- * @brief Encode a logger_tm 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 logger_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_logger_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_logger_tm_t* logger_tm)
-{
- return mavlink_msg_logger_tm_pack(system_id, component_id, msg, logger_tm->timestamp, logger_tm->log_number, logger_tm->too_large_samples, logger_tm->dropped_samples, logger_tm->queued_samples, logger_tm->buffers_filled, logger_tm->buffers_written, logger_tm->writes_failed, logger_tm->last_write_error, logger_tm->average_write_time, logger_tm->max_write_time);
-}
-
-/**
- * @brief Encode a logger_tm 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 logger_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_logger_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_logger_tm_t* logger_tm)
-{
- return mavlink_msg_logger_tm_pack_chan(system_id, component_id, chan, msg, logger_tm->timestamp, logger_tm->log_number, logger_tm->too_large_samples, logger_tm->dropped_samples, logger_tm->queued_samples, logger_tm->buffers_filled, logger_tm->buffers_written, logger_tm->writes_failed, logger_tm->last_write_error, logger_tm->average_write_time, logger_tm->max_write_time);
-}
-
-/**
- * @brief Send a logger_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp
- * @param log_number Currently active log file, -1 if the logger is inactive
- * @param too_large_samples Number of dropped samples because too large
- * @param dropped_samples Number of dropped samples due to fifo full
- * @param queued_samples Number of samples written to buffer
- * @param buffers_filled Number of buffers filled
- * @param buffers_written Number of buffers written to disk
- * @param writes_failed Number of fwrite() that failed
- * @param last_write_error Error of the last fwrite() that failed
- * @param average_write_time Average time to perform an fwrite() of a buffer
- * @param max_write_time Max time to perform an fwrite() of a buffer
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_logger_tm_send(mavlink_channel_t chan, uint64_t timestamp, int16_t log_number, int32_t too_large_samples, int32_t dropped_samples, int32_t queued_samples, int32_t buffers_filled, int32_t buffers_written, int32_t writes_failed, int32_t last_write_error, int32_t average_write_time, int32_t max_write_time)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LOGGER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 8, too_large_samples);
- _mav_put_int32_t(buf, 12, dropped_samples);
- _mav_put_int32_t(buf, 16, queued_samples);
- _mav_put_int32_t(buf, 20, buffers_filled);
- _mav_put_int32_t(buf, 24, buffers_written);
- _mav_put_int32_t(buf, 28, writes_failed);
- _mav_put_int32_t(buf, 32, last_write_error);
- _mav_put_int32_t(buf, 36, average_write_time);
- _mav_put_int32_t(buf, 40, max_write_time);
- _mav_put_int16_t(buf, 44, log_number);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, buf, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#else
- mavlink_logger_tm_t packet;
- packet.timestamp = timestamp;
- packet.too_large_samples = too_large_samples;
- packet.dropped_samples = dropped_samples;
- packet.queued_samples = queued_samples;
- packet.buffers_filled = buffers_filled;
- packet.buffers_written = buffers_written;
- packet.writes_failed = writes_failed;
- packet.last_write_error = last_write_error;
- packet.average_write_time = average_write_time;
- packet.max_write_time = max_write_time;
- packet.log_number = log_number;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, (const char *)&packet, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a logger_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_logger_tm_send_struct(mavlink_channel_t chan, const mavlink_logger_tm_t* logger_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_logger_tm_send(chan, logger_tm->timestamp, logger_tm->log_number, logger_tm->too_large_samples, logger_tm->dropped_samples, logger_tm->queued_samples, logger_tm->buffers_filled, logger_tm->buffers_written, logger_tm->writes_failed, logger_tm->last_write_error, logger_tm->average_write_time, logger_tm->max_write_time);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, (const char *)logger_tm, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_LOGGER_TM_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_logger_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, int16_t log_number, int32_t too_large_samples, int32_t dropped_samples, int32_t queued_samples, int32_t buffers_filled, int32_t buffers_written, int32_t writes_failed, int32_t last_write_error, int32_t average_write_time, int32_t max_write_time)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_int32_t(buf, 8, too_large_samples);
- _mav_put_int32_t(buf, 12, dropped_samples);
- _mav_put_int32_t(buf, 16, queued_samples);
- _mav_put_int32_t(buf, 20, buffers_filled);
- _mav_put_int32_t(buf, 24, buffers_written);
- _mav_put_int32_t(buf, 28, writes_failed);
- _mav_put_int32_t(buf, 32, last_write_error);
- _mav_put_int32_t(buf, 36, average_write_time);
- _mav_put_int32_t(buf, 40, max_write_time);
- _mav_put_int16_t(buf, 44, log_number);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, buf, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#else
- mavlink_logger_tm_t *packet = (mavlink_logger_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->too_large_samples = too_large_samples;
- packet->dropped_samples = dropped_samples;
- packet->queued_samples = queued_samples;
- packet->buffers_filled = buffers_filled;
- packet->buffers_written = buffers_written;
- packet->writes_failed = writes_failed;
- packet->last_write_error = last_write_error;
- packet->average_write_time = average_write_time;
- packet->max_write_time = max_write_time;
- packet->log_number = log_number;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGER_TM, (const char *)packet, MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN, MAVLINK_MSG_ID_LOGGER_TM_LEN, MAVLINK_MSG_ID_LOGGER_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE LOGGER_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from logger_tm message
- *
- * @return [us] Timestamp
- */
-static inline uint64_t mavlink_msg_logger_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field log_number from logger_tm message
- *
- * @return Currently active log file, -1 if the logger is inactive
- */
-static inline int16_t mavlink_msg_logger_tm_get_log_number(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int16_t(msg, 44);
-}
-
-/**
- * @brief Get field too_large_samples from logger_tm message
- *
- * @return Number of dropped samples because too large
- */
-static inline int32_t mavlink_msg_logger_tm_get_too_large_samples(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 8);
-}
-
-/**
- * @brief Get field dropped_samples from logger_tm message
- *
- * @return Number of dropped samples due to fifo full
- */
-static inline int32_t mavlink_msg_logger_tm_get_dropped_samples(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 12);
-}
-
-/**
- * @brief Get field queued_samples from logger_tm message
- *
- * @return Number of samples written to buffer
- */
-static inline int32_t mavlink_msg_logger_tm_get_queued_samples(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 16);
-}
-
-/**
- * @brief Get field buffers_filled from logger_tm message
- *
- * @return Number of buffers filled
- */
-static inline int32_t mavlink_msg_logger_tm_get_buffers_filled(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 20);
-}
-
-/**
- * @brief Get field buffers_written from logger_tm message
- *
- * @return Number of buffers written to disk
- */
-static inline int32_t mavlink_msg_logger_tm_get_buffers_written(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 24);
-}
-
-/**
- * @brief Get field writes_failed from logger_tm message
- *
- * @return Number of fwrite() that failed
- */
-static inline int32_t mavlink_msg_logger_tm_get_writes_failed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 28);
-}
-
-/**
- * @brief Get field last_write_error from logger_tm message
- *
- * @return Error of the last fwrite() that failed
- */
-static inline int32_t mavlink_msg_logger_tm_get_last_write_error(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 32);
-}
-
-/**
- * @brief Get field average_write_time from logger_tm message
- *
- * @return Average time to perform an fwrite() of a buffer
- */
-static inline int32_t mavlink_msg_logger_tm_get_average_write_time(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 36);
-}
-
-/**
- * @brief Get field max_write_time from logger_tm message
- *
- * @return Max time to perform an fwrite() of a buffer
- */
-static inline int32_t mavlink_msg_logger_tm_get_max_write_time(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 40);
-}
-
-/**
- * @brief Decode a logger_tm message into a struct
- *
- * @param msg The message to decode
- * @param logger_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_logger_tm_decode(const mavlink_message_t* msg, mavlink_logger_tm_t* logger_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- logger_tm->timestamp = mavlink_msg_logger_tm_get_timestamp(msg);
- logger_tm->too_large_samples = mavlink_msg_logger_tm_get_too_large_samples(msg);
- logger_tm->dropped_samples = mavlink_msg_logger_tm_get_dropped_samples(msg);
- logger_tm->queued_samples = mavlink_msg_logger_tm_get_queued_samples(msg);
- logger_tm->buffers_filled = mavlink_msg_logger_tm_get_buffers_filled(msg);
- logger_tm->buffers_written = mavlink_msg_logger_tm_get_buffers_written(msg);
- logger_tm->writes_failed = mavlink_msg_logger_tm_get_writes_failed(msg);
- logger_tm->last_write_error = mavlink_msg_logger_tm_get_last_write_error(msg);
- logger_tm->average_write_time = mavlink_msg_logger_tm_get_average_write_time(msg);
- logger_tm->max_write_time = mavlink_msg_logger_tm_get_max_write_time(msg);
- logger_tm->log_number = mavlink_msg_logger_tm_get_log_number(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_LOGGER_TM_LEN? msg->len : MAVLINK_MSG_ID_LOGGER_TM_LEN;
- memset(logger_tm, 0, MAVLINK_MSG_ID_LOGGER_TM_LEN);
- memcpy(logger_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_mavlink_stats_tm.h b/mavlink_lib/pyxis/mavlink_msg_mavlink_stats_tm.h
deleted file mode 100644
index ba89b5f0761bcadff4201e229880cd30f7b90358..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_mavlink_stats_tm.h
+++ /dev/null
@@ -1,513 +0,0 @@
-#pragma once
-// MESSAGE MAVLINK_STATS_TM PACKING
-
-#define MAVLINK_MSG_ID_MAVLINK_STATS_TM 203
-
-
-typedef struct __mavlink_mavlink_stats_tm_t {
- uint64_t timestamp; /*< [us] When was this logged */
- uint32_t parse_state; /*< Parsing state machine*/
- uint16_t n_send_queue; /*< Current len of the occupied portion of the queue*/
- uint16_t max_send_queue; /*< Max occupied len of the queue */
- uint16_t n_send_errors; /*< Number of packet not sent correctly by the TMTC*/
- uint16_t packet_rx_success_count; /*< Received packets*/
- uint16_t packet_rx_drop_count; /*< Number of packet drops */
- uint8_t msg_received; /*< Number of received messages*/
- uint8_t buffer_overrun; /*< Number of buffer overruns*/
- uint8_t parse_error; /*< Number of parse errors*/
- 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 */
-} mavlink_mavlink_stats_tm_t;
-
-#define MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN 28
-#define MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN 28
-#define MAVLINK_MSG_ID_203_LEN 28
-#define MAVLINK_MSG_ID_203_MIN_LEN 28
-
-#define MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC 108
-#define MAVLINK_MSG_ID_203_CRC 108
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM { \
- 203, \
- "MAVLINK_STATS_TM", \
- 13, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_mavlink_stats_tm_t, timestamp) }, \
- { "n_send_queue", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_mavlink_stats_tm_t, n_send_queue) }, \
- { "max_send_queue", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_mavlink_stats_tm_t, max_send_queue) }, \
- { "n_send_errors", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_mavlink_stats_tm_t, n_send_errors) }, \
- { "msg_received", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_mavlink_stats_tm_t, msg_received) }, \
- { "buffer_overrun", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_mavlink_stats_tm_t, buffer_overrun) }, \
- { "parse_error", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_mavlink_stats_tm_t, parse_error) }, \
- { "parse_state", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_mavlink_stats_tm_t, parse_state) }, \
- { "packet_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_mavlink_stats_tm_t, packet_idx) }, \
- { "current_rx_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_mavlink_stats_tm_t, current_rx_seq) }, \
- { "current_tx_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_mavlink_stats_tm_t, current_tx_seq) }, \
- { "packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_mavlink_stats_tm_t, packet_rx_success_count) }, \
- { "packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_mavlink_stats_tm_t, packet_rx_drop_count) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM { \
- "MAVLINK_STATS_TM", \
- 13, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_mavlink_stats_tm_t, timestamp) }, \
- { "n_send_queue", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_mavlink_stats_tm_t, n_send_queue) }, \
- { "max_send_queue", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_mavlink_stats_tm_t, max_send_queue) }, \
- { "n_send_errors", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_mavlink_stats_tm_t, n_send_errors) }, \
- { "msg_received", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_mavlink_stats_tm_t, msg_received) }, \
- { "buffer_overrun", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_mavlink_stats_tm_t, buffer_overrun) }, \
- { "parse_error", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_mavlink_stats_tm_t, parse_error) }, \
- { "parse_state", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_mavlink_stats_tm_t, parse_state) }, \
- { "packet_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_mavlink_stats_tm_t, packet_idx) }, \
- { "current_rx_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_mavlink_stats_tm_t, current_rx_seq) }, \
- { "current_tx_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_mavlink_stats_tm_t, current_tx_seq) }, \
- { "packet_rx_success_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_mavlink_stats_tm_t, packet_rx_success_count) }, \
- { "packet_rx_drop_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_mavlink_stats_tm_t, packet_rx_drop_count) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a mavlink_stats_tm 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] When was this logged
- * @param n_send_queue Current len of the occupied portion of the queue
- * @param max_send_queue Max occupied len of the queue
- * @param n_send_errors Number of packet not sent correctly by the TMTC
- * @param msg_received Number of received messages
- * @param buffer_overrun Number of buffer overruns
- * @param parse_error Number of parse errors
- * @param parse_state Parsing state machine
- * @param packet_idx Index in current packet
- * @param current_rx_seq Sequence number of last packet received
- * @param current_tx_seq Sequence number of last packet sent
- * @param packet_rx_success_count Received packets
- * @param packet_rx_drop_count Number of packet drops
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint16_t n_send_queue, uint16_t max_send_queue, uint16_t n_send_errors, uint8_t msg_received, uint8_t buffer_overrun, uint8_t parse_error, uint32_t parse_state, uint8_t packet_idx, uint8_t current_rx_seq, uint8_t current_tx_seq, uint16_t packet_rx_success_count, uint16_t packet_rx_drop_count)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint32_t(buf, 8, parse_state);
- _mav_put_uint16_t(buf, 12, n_send_queue);
- _mav_put_uint16_t(buf, 14, max_send_queue);
- _mav_put_uint16_t(buf, 16, n_send_errors);
- _mav_put_uint16_t(buf, 18, packet_rx_success_count);
- _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
- _mav_put_uint8_t(buf, 22, msg_received);
- _mav_put_uint8_t(buf, 23, buffer_overrun);
- _mav_put_uint8_t(buf, 24, parse_error);
- _mav_put_uint8_t(buf, 25, packet_idx);
- _mav_put_uint8_t(buf, 26, current_rx_seq);
- _mav_put_uint8_t(buf, 27, current_tx_seq);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN);
-#else
- mavlink_mavlink_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.parse_state = parse_state;
- packet.n_send_queue = n_send_queue;
- packet.max_send_queue = max_send_queue;
- packet.n_send_errors = n_send_errors;
- packet.packet_rx_success_count = packet_rx_success_count;
- packet.packet_rx_drop_count = packet_rx_drop_count;
- packet.msg_received = msg_received;
- packet.buffer_overrun = buffer_overrun;
- packet.parse_error = parse_error;
- packet.packet_idx = packet_idx;
- packet.current_rx_seq = current_rx_seq;
- packet.current_tx_seq = current_tx_seq;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_MAVLINK_STATS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-}
-
-/**
- * @brief Pack a mavlink_stats_tm 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] When was this logged
- * @param n_send_queue Current len of the occupied portion of the queue
- * @param max_send_queue Max occupied len of the queue
- * @param n_send_errors Number of packet not sent correctly by the TMTC
- * @param msg_received Number of received messages
- * @param buffer_overrun Number of buffer overruns
- * @param parse_error Number of parse errors
- * @param parse_state Parsing state machine
- * @param packet_idx Index in current packet
- * @param current_rx_seq Sequence number of last packet received
- * @param current_tx_seq Sequence number of last packet sent
- * @param packet_rx_success_count Received packets
- * @param packet_rx_drop_count Number of packet drops
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint16_t n_send_queue,uint16_t max_send_queue,uint16_t n_send_errors,uint8_t msg_received,uint8_t buffer_overrun,uint8_t parse_error,uint32_t parse_state,uint8_t packet_idx,uint8_t current_rx_seq,uint8_t current_tx_seq,uint16_t packet_rx_success_count,uint16_t packet_rx_drop_count)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint32_t(buf, 8, parse_state);
- _mav_put_uint16_t(buf, 12, n_send_queue);
- _mav_put_uint16_t(buf, 14, max_send_queue);
- _mav_put_uint16_t(buf, 16, n_send_errors);
- _mav_put_uint16_t(buf, 18, packet_rx_success_count);
- _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
- _mav_put_uint8_t(buf, 22, msg_received);
- _mav_put_uint8_t(buf, 23, buffer_overrun);
- _mav_put_uint8_t(buf, 24, parse_error);
- _mav_put_uint8_t(buf, 25, packet_idx);
- _mav_put_uint8_t(buf, 26, current_rx_seq);
- _mav_put_uint8_t(buf, 27, current_tx_seq);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN);
-#else
- mavlink_mavlink_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.parse_state = parse_state;
- packet.n_send_queue = n_send_queue;
- packet.max_send_queue = max_send_queue;
- packet.n_send_errors = n_send_errors;
- packet.packet_rx_success_count = packet_rx_success_count;
- packet.packet_rx_drop_count = packet_rx_drop_count;
- packet.msg_received = msg_received;
- packet.buffer_overrun = buffer_overrun;
- packet.parse_error = parse_error;
- packet.packet_idx = packet_idx;
- packet.current_rx_seq = current_rx_seq;
- packet.current_tx_seq = current_tx_seq;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_MAVLINK_STATS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-}
-
-/**
- * @brief Encode a mavlink_stats_tm 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 mavlink_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mavlink_stats_tm_t* mavlink_stats_tm)
-{
- return mavlink_msg_mavlink_stats_tm_pack(system_id, component_id, msg, mavlink_stats_tm->timestamp, mavlink_stats_tm->n_send_queue, mavlink_stats_tm->max_send_queue, mavlink_stats_tm->n_send_errors, mavlink_stats_tm->msg_received, mavlink_stats_tm->buffer_overrun, mavlink_stats_tm->parse_error, mavlink_stats_tm->parse_state, mavlink_stats_tm->packet_idx, mavlink_stats_tm->current_rx_seq, mavlink_stats_tm->current_tx_seq, mavlink_stats_tm->packet_rx_success_count, mavlink_stats_tm->packet_rx_drop_count);
-}
-
-/**
- * @brief Encode a mavlink_stats_tm 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 mavlink_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mavlink_stats_tm_t* mavlink_stats_tm)
-{
- return mavlink_msg_mavlink_stats_tm_pack_chan(system_id, component_id, chan, msg, mavlink_stats_tm->timestamp, mavlink_stats_tm->n_send_queue, mavlink_stats_tm->max_send_queue, mavlink_stats_tm->n_send_errors, mavlink_stats_tm->msg_received, mavlink_stats_tm->buffer_overrun, mavlink_stats_tm->parse_error, mavlink_stats_tm->parse_state, mavlink_stats_tm->packet_idx, mavlink_stats_tm->current_rx_seq, mavlink_stats_tm->current_tx_seq, mavlink_stats_tm->packet_rx_success_count, mavlink_stats_tm->packet_rx_drop_count);
-}
-
-/**
- * @brief Send a mavlink_stats_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param n_send_queue Current len of the occupied portion of the queue
- * @param max_send_queue Max occupied len of the queue
- * @param n_send_errors Number of packet not sent correctly by the TMTC
- * @param msg_received Number of received messages
- * @param buffer_overrun Number of buffer overruns
- * @param parse_error Number of parse errors
- * @param parse_state Parsing state machine
- * @param packet_idx Index in current packet
- * @param current_rx_seq Sequence number of last packet received
- * @param current_tx_seq Sequence number of last packet sent
- * @param packet_rx_success_count Received packets
- * @param packet_rx_drop_count Number of packet drops
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_mavlink_stats_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint16_t n_send_queue, uint16_t max_send_queue, uint16_t n_send_errors, uint8_t msg_received, uint8_t buffer_overrun, uint8_t parse_error, uint32_t parse_state, uint8_t packet_idx, uint8_t current_rx_seq, uint8_t current_tx_seq, uint16_t packet_rx_success_count, uint16_t packet_rx_drop_count)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint32_t(buf, 8, parse_state);
- _mav_put_uint16_t(buf, 12, n_send_queue);
- _mav_put_uint16_t(buf, 14, max_send_queue);
- _mav_put_uint16_t(buf, 16, n_send_errors);
- _mav_put_uint16_t(buf, 18, packet_rx_success_count);
- _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
- _mav_put_uint8_t(buf, 22, msg_received);
- _mav_put_uint8_t(buf, 23, buffer_overrun);
- _mav_put_uint8_t(buf, 24, parse_error);
- _mav_put_uint8_t(buf, 25, packet_idx);
- _mav_put_uint8_t(buf, 26, current_rx_seq);
- _mav_put_uint8_t(buf, 27, current_tx_seq);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAVLINK_STATS_TM, buf, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-#else
- mavlink_mavlink_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.parse_state = parse_state;
- packet.n_send_queue = n_send_queue;
- packet.max_send_queue = max_send_queue;
- packet.n_send_errors = n_send_errors;
- packet.packet_rx_success_count = packet_rx_success_count;
- packet.packet_rx_drop_count = packet_rx_drop_count;
- packet.msg_received = msg_received;
- packet.buffer_overrun = buffer_overrun;
- packet.parse_error = parse_error;
- packet.packet_idx = packet_idx;
- packet.current_rx_seq = current_rx_seq;
- packet.current_tx_seq = current_tx_seq;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAVLINK_STATS_TM, (const char *)&packet, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a mavlink_stats_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_mavlink_stats_tm_send_struct(mavlink_channel_t chan, const mavlink_mavlink_stats_tm_t* mavlink_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_mavlink_stats_tm_send(chan, mavlink_stats_tm->timestamp, mavlink_stats_tm->n_send_queue, mavlink_stats_tm->max_send_queue, mavlink_stats_tm->n_send_errors, mavlink_stats_tm->msg_received, mavlink_stats_tm->buffer_overrun, mavlink_stats_tm->parse_error, mavlink_stats_tm->parse_state, mavlink_stats_tm->packet_idx, mavlink_stats_tm->current_rx_seq, mavlink_stats_tm->current_tx_seq, mavlink_stats_tm->packet_rx_success_count, mavlink_stats_tm->packet_rx_drop_count);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAVLINK_STATS_TM, (const char *)mavlink_stats_tm, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_MAVLINK_STATS_TM_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_mavlink_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint16_t n_send_queue, uint16_t max_send_queue, uint16_t n_send_errors, uint8_t msg_received, uint8_t buffer_overrun, uint8_t parse_error, uint32_t parse_state, uint8_t packet_idx, uint8_t current_rx_seq, uint8_t current_tx_seq, uint16_t packet_rx_success_count, uint16_t packet_rx_drop_count)
-{
-#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, parse_state);
- _mav_put_uint16_t(buf, 12, n_send_queue);
- _mav_put_uint16_t(buf, 14, max_send_queue);
- _mav_put_uint16_t(buf, 16, n_send_errors);
- _mav_put_uint16_t(buf, 18, packet_rx_success_count);
- _mav_put_uint16_t(buf, 20, packet_rx_drop_count);
- _mav_put_uint8_t(buf, 22, msg_received);
- _mav_put_uint8_t(buf, 23, buffer_overrun);
- _mav_put_uint8_t(buf, 24, parse_error);
- _mav_put_uint8_t(buf, 25, packet_idx);
- _mav_put_uint8_t(buf, 26, current_rx_seq);
- _mav_put_uint8_t(buf, 27, current_tx_seq);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAVLINK_STATS_TM, buf, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-#else
- mavlink_mavlink_stats_tm_t *packet = (mavlink_mavlink_stats_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->parse_state = parse_state;
- packet->n_send_queue = n_send_queue;
- packet->max_send_queue = max_send_queue;
- packet->n_send_errors = n_send_errors;
- packet->packet_rx_success_count = packet_rx_success_count;
- packet->packet_rx_drop_count = packet_rx_drop_count;
- packet->msg_received = msg_received;
- packet->buffer_overrun = buffer_overrun;
- packet->parse_error = parse_error;
- packet->packet_idx = packet_idx;
- packet->current_rx_seq = current_rx_seq;
- packet->current_tx_seq = current_tx_seq;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAVLINK_STATS_TM, (const char *)packet, MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN, MAVLINK_MSG_ID_MAVLINK_STATS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE MAVLINK_STATS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from mavlink_stats_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_mavlink_stats_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field n_send_queue from mavlink_stats_tm message
- *
- * @return Current len of the occupied portion of the queue
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_get_n_send_queue(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 12);
-}
-
-/**
- * @brief Get field max_send_queue from mavlink_stats_tm message
- *
- * @return Max occupied len of the queue
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_get_max_send_queue(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 14);
-}
-
-/**
- * @brief Get field n_send_errors from mavlink_stats_tm message
- *
- * @return Number of packet not sent correctly by the TMTC
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_get_n_send_errors(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 16);
-}
-
-/**
- * @brief Get field msg_received from mavlink_stats_tm message
- *
- * @return Number of received messages
- */
-static inline uint8_t mavlink_msg_mavlink_stats_tm_get_msg_received(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 22);
-}
-
-/**
- * @brief Get field buffer_overrun from mavlink_stats_tm message
- *
- * @return Number of buffer overruns
- */
-static inline uint8_t mavlink_msg_mavlink_stats_tm_get_buffer_overrun(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 23);
-}
-
-/**
- * @brief Get field parse_error from mavlink_stats_tm message
- *
- * @return Number of parse errors
- */
-static inline uint8_t mavlink_msg_mavlink_stats_tm_get_parse_error(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 24);
-}
-
-/**
- * @brief Get field parse_state from mavlink_stats_tm message
- *
- * @return Parsing state machine
- */
-static inline uint32_t mavlink_msg_mavlink_stats_tm_get_parse_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 8);
-}
-
-/**
- * @brief Get field packet_idx from mavlink_stats_tm message
- *
- * @return Index in current packet
- */
-static inline uint8_t mavlink_msg_mavlink_stats_tm_get_packet_idx(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 25);
-}
-
-/**
- * @brief Get field current_rx_seq from mavlink_stats_tm message
- *
- * @return Sequence number of last packet received
- */
-static inline uint8_t mavlink_msg_mavlink_stats_tm_get_current_rx_seq(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 26);
-}
-
-/**
- * @brief Get field current_tx_seq from mavlink_stats_tm message
- *
- * @return Sequence number of last packet sent
- */
-static inline uint8_t mavlink_msg_mavlink_stats_tm_get_current_tx_seq(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 27);
-}
-
-/**
- * @brief Get field packet_rx_success_count from mavlink_stats_tm message
- *
- * @return Received packets
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_get_packet_rx_success_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 18);
-}
-
-/**
- * @brief Get field packet_rx_drop_count from mavlink_stats_tm message
- *
- * @return Number of packet drops
- */
-static inline uint16_t mavlink_msg_mavlink_stats_tm_get_packet_rx_drop_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 20);
-}
-
-/**
- * @brief Decode a mavlink_stats_tm message into a struct
- *
- * @param msg The message to decode
- * @param mavlink_stats_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_mavlink_stats_tm_decode(const mavlink_message_t* msg, mavlink_mavlink_stats_tm_t* mavlink_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_stats_tm->timestamp = mavlink_msg_mavlink_stats_tm_get_timestamp(msg);
- mavlink_stats_tm->parse_state = mavlink_msg_mavlink_stats_tm_get_parse_state(msg);
- mavlink_stats_tm->n_send_queue = mavlink_msg_mavlink_stats_tm_get_n_send_queue(msg);
- mavlink_stats_tm->max_send_queue = mavlink_msg_mavlink_stats_tm_get_max_send_queue(msg);
- mavlink_stats_tm->n_send_errors = mavlink_msg_mavlink_stats_tm_get_n_send_errors(msg);
- mavlink_stats_tm->packet_rx_success_count = mavlink_msg_mavlink_stats_tm_get_packet_rx_success_count(msg);
- mavlink_stats_tm->packet_rx_drop_count = mavlink_msg_mavlink_stats_tm_get_packet_rx_drop_count(msg);
- mavlink_stats_tm->msg_received = mavlink_msg_mavlink_stats_tm_get_msg_received(msg);
- mavlink_stats_tm->buffer_overrun = mavlink_msg_mavlink_stats_tm_get_buffer_overrun(msg);
- mavlink_stats_tm->parse_error = mavlink_msg_mavlink_stats_tm_get_parse_error(msg);
- mavlink_stats_tm->packet_idx = mavlink_msg_mavlink_stats_tm_get_packet_idx(msg);
- mavlink_stats_tm->current_rx_seq = mavlink_msg_mavlink_stats_tm_get_current_rx_seq(msg);
- mavlink_stats_tm->current_tx_seq = mavlink_msg_mavlink_stats_tm_get_current_tx_seq(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN? msg->len : MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN;
- memset(mavlink_stats_tm, 0, MAVLINK_MSG_ID_MAVLINK_STATS_TM_LEN);
- memcpy(mavlink_stats_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_nack_tm.h b/mavlink_lib/pyxis/mavlink_msg_nack_tm.h
deleted file mode 100644
index 85abd048c50911cd99ded380f566cf5c34b29322..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_nack_tm.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE NACK_TM PACKING
-
-#define MAVLINK_MSG_ID_NACK_TM 101
-
-
-typedef struct __mavlink_nack_tm_t {
- uint8_t recv_msgid; /*< Message id of the received message*/
- uint8_t seq_ack; /*< Sequence number of the received message*/
-} mavlink_nack_tm_t;
-
-#define MAVLINK_MSG_ID_NACK_TM_LEN 2
-#define MAVLINK_MSG_ID_NACK_TM_MIN_LEN 2
-#define MAVLINK_MSG_ID_101_LEN 2
-#define MAVLINK_MSG_ID_101_MIN_LEN 2
-
-#define MAVLINK_MSG_ID_NACK_TM_CRC 146
-#define MAVLINK_MSG_ID_101_CRC 146
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_NACK_TM { \
- 101, \
- "NACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_nack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_nack_tm_t, seq_ack) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_NACK_TM { \
- "NACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_nack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_nack_tm_t, seq_ack) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a nack_tm 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 recv_msgid Message id of the received message
- * @param seq_ack Sequence number of the received message
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_nack_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NACK_TM_LEN);
-#else
- mavlink_nack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NACK_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-}
-
-/**
- * @brief Pack a nack_tm 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 recv_msgid Message id of the received message
- * @param seq_ack Sequence number of the received message
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_nack_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t recv_msgid,uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NACK_TM_LEN);
-#else
- mavlink_nack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NACK_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-}
-
-/**
- * @brief Encode a nack_tm 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 nack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_nack_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nack_tm_t* nack_tm)
-{
- return mavlink_msg_nack_tm_pack(system_id, component_id, msg, nack_tm->recv_msgid, nack_tm->seq_ack);
-}
-
-/**
- * @brief Encode a nack_tm 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 nack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_nack_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nack_tm_t* nack_tm)
-{
- return mavlink_msg_nack_tm_pack_chan(system_id, component_id, chan, msg, nack_tm->recv_msgid, nack_tm->seq_ack);
-}
-
-/**
- * @brief Send a nack_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param recv_msgid Message id of the received message
- * @param seq_ack Sequence number of the received message
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_nack_tm_send(mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, buf, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#else
- mavlink_nack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, (const char *)&packet, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a nack_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_nack_tm_send_struct(mavlink_channel_t chan, const mavlink_nack_tm_t* nack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_nack_tm_send(chan, nack_tm->recv_msgid, nack_tm->seq_ack);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, (const char *)nack_tm, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_NACK_TM_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_nack_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, buf, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#else
- mavlink_nack_tm_t *packet = (mavlink_nack_tm_t *)msgbuf;
- packet->recv_msgid = recv_msgid;
- packet->seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NACK_TM, (const char *)packet, MAVLINK_MSG_ID_NACK_TM_MIN_LEN, MAVLINK_MSG_ID_NACK_TM_LEN, MAVLINK_MSG_ID_NACK_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE NACK_TM UNPACKING
-
-
-/**
- * @brief Get field recv_msgid from nack_tm message
- *
- * @return Message id of the received message
- */
-static inline uint8_t mavlink_msg_nack_tm_get_recv_msgid(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field seq_ack from nack_tm message
- *
- * @return Sequence number of the received message
- */
-static inline uint8_t mavlink_msg_nack_tm_get_seq_ack(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Decode a nack_tm message into a struct
- *
- * @param msg The message to decode
- * @param nack_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_nack_tm_decode(const mavlink_message_t* msg, mavlink_nack_tm_t* nack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- nack_tm->recv_msgid = mavlink_msg_nack_tm_get_recv_msgid(msg);
- nack_tm->seq_ack = mavlink_msg_nack_tm_get_seq_ack(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_NACK_TM_LEN? msg->len : MAVLINK_MSG_ID_NACK_TM_LEN;
- memset(nack_tm, 0, MAVLINK_MSG_ID_NACK_TM_LEN);
- memcpy(nack_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_nas_tm.h b/mavlink_lib/pyxis/mavlink_msg_nas_tm.h
deleted file mode 100644
index 47a786d940c76fc63b419a60703fc663e41087f3..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_nas_tm.h
+++ /dev/null
@@ -1,663 +0,0 @@
-#pragma once
-// MESSAGE NAS_TM PACKING
-
-#define MAVLINK_MSG_ID_NAS_TM 206
-
-
-typedef struct __mavlink_nas_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float nas_n; /*< [deg] Navigation system estimated noth position*/
- float nas_e; /*< [deg] Navigation system estimated east position*/
- float nas_d; /*< [m] Navigation system estimated down position*/
- float nas_vn; /*< [m/s] Navigation system estimated north velocity*/
- float nas_ve; /*< [m/s] Navigation system estimated east velocity*/
- float nas_vd; /*< [m/s] Navigation system estimated down velocity*/
- float nas_qx; /*< [deg] Navigation system estimated attitude (qx)*/
- float nas_qy; /*< [deg] Navigation system estimated attitude (qy)*/
- float nas_qz; /*< [deg] Navigation system estimated attitude (qz)*/
- float nas_qw; /*< [deg] Navigation system estimated attitude (qw)*/
- float nas_bias_x; /*< Navigation system gyroscope bias on x axis*/
- float nas_bias_y; /*< Navigation system gyroscope bias on x axis*/
- float nas_bias_z; /*< Navigation system gyroscope bias on x axis*/
- float ref_pressure; /*< [Pa] Calibration pressure*/
- float ref_temperature; /*< [degC] Calibration temperature*/
- float ref_latitude; /*< [deg] Calibration latitude*/
- float ref_longitude; /*< [deg] Calibration longitude*/
- uint8_t state; /*< NAS current state*/
-} mavlink_nas_tm_t;
-
-#define MAVLINK_MSG_ID_NAS_TM_LEN 77
-#define MAVLINK_MSG_ID_NAS_TM_MIN_LEN 77
-#define MAVLINK_MSG_ID_206_LEN 77
-#define MAVLINK_MSG_ID_206_MIN_LEN 77
-
-#define MAVLINK_MSG_ID_NAS_TM_CRC 66
-#define MAVLINK_MSG_ID_206_CRC 66
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_NAS_TM { \
- 206, \
- "NAS_TM", \
- 19, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_nas_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 76, offsetof(mavlink_nas_tm_t, state) }, \
- { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nas_tm_t, nas_n) }, \
- { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nas_tm_t, nas_e) }, \
- { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nas_tm_t, nas_d) }, \
- { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_nas_tm_t, nas_vn) }, \
- { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_nas_tm_t, nas_ve) }, \
- { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_nas_tm_t, nas_vd) }, \
- { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_nas_tm_t, nas_qx) }, \
- { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_nas_tm_t, nas_qy) }, \
- { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_nas_tm_t, nas_qz) }, \
- { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_nas_tm_t, nas_qw) }, \
- { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_nas_tm_t, nas_bias_x) }, \
- { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_nas_tm_t, nas_bias_y) }, \
- { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_nas_tm_t, nas_bias_z) }, \
- { "ref_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_nas_tm_t, ref_pressure) }, \
- { "ref_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_nas_tm_t, ref_temperature) }, \
- { "ref_latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_nas_tm_t, ref_latitude) }, \
- { "ref_longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_nas_tm_t, ref_longitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_NAS_TM { \
- "NAS_TM", \
- 19, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_nas_tm_t, timestamp) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 76, offsetof(mavlink_nas_tm_t, state) }, \
- { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nas_tm_t, nas_n) }, \
- { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nas_tm_t, nas_e) }, \
- { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nas_tm_t, nas_d) }, \
- { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_nas_tm_t, nas_vn) }, \
- { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_nas_tm_t, nas_ve) }, \
- { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_nas_tm_t, nas_vd) }, \
- { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_nas_tm_t, nas_qx) }, \
- { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_nas_tm_t, nas_qy) }, \
- { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_nas_tm_t, nas_qz) }, \
- { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_nas_tm_t, nas_qw) }, \
- { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_nas_tm_t, nas_bias_x) }, \
- { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_nas_tm_t, nas_bias_y) }, \
- { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_nas_tm_t, nas_bias_z) }, \
- { "ref_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_nas_tm_t, ref_pressure) }, \
- { "ref_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_nas_tm_t, ref_temperature) }, \
- { "ref_latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_nas_tm_t, ref_latitude) }, \
- { "ref_longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_nas_tm_t, ref_longitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a nas_tm 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] When was this logged
- * @param state NAS current state
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on x axis
- * @param nas_bias_z Navigation system gyroscope bias on x axis
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_temperature [degC] Calibration temperature
- * @param ref_latitude [deg] Calibration latitude
- * @param ref_longitude [deg] Calibration longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_nas_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t state, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float ref_pressure, float ref_temperature, float ref_latitude, float ref_longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NAS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, nas_n);
- _mav_put_float(buf, 12, nas_e);
- _mav_put_float(buf, 16, nas_d);
- _mav_put_float(buf, 20, nas_vn);
- _mav_put_float(buf, 24, nas_ve);
- _mav_put_float(buf, 28, nas_vd);
- _mav_put_float(buf, 32, nas_qx);
- _mav_put_float(buf, 36, nas_qy);
- _mav_put_float(buf, 40, nas_qz);
- _mav_put_float(buf, 44, nas_qw);
- _mav_put_float(buf, 48, nas_bias_x);
- _mav_put_float(buf, 52, nas_bias_y);
- _mav_put_float(buf, 56, nas_bias_z);
- _mav_put_float(buf, 60, ref_pressure);
- _mav_put_float(buf, 64, ref_temperature);
- _mav_put_float(buf, 68, ref_latitude);
- _mav_put_float(buf, 72, ref_longitude);
- _mav_put_uint8_t(buf, 76, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAS_TM_LEN);
-#else
- mavlink_nas_tm_t packet;
- packet.timestamp = timestamp;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.ref_pressure = ref_pressure;
- packet.ref_temperature = ref_temperature;
- packet.ref_latitude = ref_latitude;
- packet.ref_longitude = ref_longitude;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NAS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-}
-
-/**
- * @brief Pack a nas_tm 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] When was this logged
- * @param state NAS current state
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on x axis
- * @param nas_bias_z Navigation system gyroscope bias on x axis
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_temperature [degC] Calibration temperature
- * @param ref_latitude [deg] Calibration latitude
- * @param ref_longitude [deg] Calibration longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_nas_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t state,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,float ref_pressure,float ref_temperature,float ref_latitude,float ref_longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NAS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, nas_n);
- _mav_put_float(buf, 12, nas_e);
- _mav_put_float(buf, 16, nas_d);
- _mav_put_float(buf, 20, nas_vn);
- _mav_put_float(buf, 24, nas_ve);
- _mav_put_float(buf, 28, nas_vd);
- _mav_put_float(buf, 32, nas_qx);
- _mav_put_float(buf, 36, nas_qy);
- _mav_put_float(buf, 40, nas_qz);
- _mav_put_float(buf, 44, nas_qw);
- _mav_put_float(buf, 48, nas_bias_x);
- _mav_put_float(buf, 52, nas_bias_y);
- _mav_put_float(buf, 56, nas_bias_z);
- _mav_put_float(buf, 60, ref_pressure);
- _mav_put_float(buf, 64, ref_temperature);
- _mav_put_float(buf, 68, ref_latitude);
- _mav_put_float(buf, 72, ref_longitude);
- _mav_put_uint8_t(buf, 76, state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAS_TM_LEN);
-#else
- mavlink_nas_tm_t packet;
- packet.timestamp = timestamp;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.ref_pressure = ref_pressure;
- packet.ref_temperature = ref_temperature;
- packet.ref_latitude = ref_latitude;
- packet.ref_longitude = ref_longitude;
- packet.state = state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NAS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-}
-
-/**
- * @brief Encode a nas_tm 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 nas_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_nas_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nas_tm_t* nas_tm)
-{
- return mavlink_msg_nas_tm_pack(system_id, component_id, msg, nas_tm->timestamp, nas_tm->state, nas_tm->nas_n, nas_tm->nas_e, nas_tm->nas_d, nas_tm->nas_vn, nas_tm->nas_ve, nas_tm->nas_vd, nas_tm->nas_qx, nas_tm->nas_qy, nas_tm->nas_qz, nas_tm->nas_qw, nas_tm->nas_bias_x, nas_tm->nas_bias_y, nas_tm->nas_bias_z, nas_tm->ref_pressure, nas_tm->ref_temperature, nas_tm->ref_latitude, nas_tm->ref_longitude);
-}
-
-/**
- * @brief Encode a nas_tm 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 nas_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_nas_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nas_tm_t* nas_tm)
-{
- return mavlink_msg_nas_tm_pack_chan(system_id, component_id, chan, msg, nas_tm->timestamp, nas_tm->state, nas_tm->nas_n, nas_tm->nas_e, nas_tm->nas_d, nas_tm->nas_vn, nas_tm->nas_ve, nas_tm->nas_vd, nas_tm->nas_qx, nas_tm->nas_qy, nas_tm->nas_qz, nas_tm->nas_qw, nas_tm->nas_bias_x, nas_tm->nas_bias_y, nas_tm->nas_bias_z, nas_tm->ref_pressure, nas_tm->ref_temperature, nas_tm->ref_latitude, nas_tm->ref_longitude);
-}
-
-/**
- * @brief Send a nas_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param state NAS current state
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on x axis
- * @param nas_bias_z Navigation system gyroscope bias on x axis
- * @param ref_pressure [Pa] Calibration pressure
- * @param ref_temperature [degC] Calibration temperature
- * @param ref_latitude [deg] Calibration latitude
- * @param ref_longitude [deg] Calibration longitude
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_nas_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float ref_pressure, float ref_temperature, float ref_latitude, float ref_longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NAS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, nas_n);
- _mav_put_float(buf, 12, nas_e);
- _mav_put_float(buf, 16, nas_d);
- _mav_put_float(buf, 20, nas_vn);
- _mav_put_float(buf, 24, nas_ve);
- _mav_put_float(buf, 28, nas_vd);
- _mav_put_float(buf, 32, nas_qx);
- _mav_put_float(buf, 36, nas_qy);
- _mav_put_float(buf, 40, nas_qz);
- _mav_put_float(buf, 44, nas_qw);
- _mav_put_float(buf, 48, nas_bias_x);
- _mav_put_float(buf, 52, nas_bias_y);
- _mav_put_float(buf, 56, nas_bias_z);
- _mav_put_float(buf, 60, ref_pressure);
- _mav_put_float(buf, 64, ref_temperature);
- _mav_put_float(buf, 68, ref_latitude);
- _mav_put_float(buf, 72, ref_longitude);
- _mav_put_uint8_t(buf, 76, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAS_TM, buf, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-#else
- mavlink_nas_tm_t packet;
- packet.timestamp = timestamp;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.ref_pressure = ref_pressure;
- packet.ref_temperature = ref_temperature;
- packet.ref_latitude = ref_latitude;
- packet.ref_longitude = ref_longitude;
- packet.state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAS_TM, (const char *)&packet, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a nas_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_nas_tm_send_struct(mavlink_channel_t chan, const mavlink_nas_tm_t* nas_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_nas_tm_send(chan, nas_tm->timestamp, nas_tm->state, nas_tm->nas_n, nas_tm->nas_e, nas_tm->nas_d, nas_tm->nas_vn, nas_tm->nas_ve, nas_tm->nas_vd, nas_tm->nas_qx, nas_tm->nas_qy, nas_tm->nas_qz, nas_tm->nas_qw, nas_tm->nas_bias_x, nas_tm->nas_bias_y, nas_tm->nas_bias_z, nas_tm->ref_pressure, nas_tm->ref_temperature, nas_tm->ref_latitude, nas_tm->ref_longitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAS_TM, (const char *)nas_tm, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_NAS_TM_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_nas_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t state, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, float ref_pressure, float ref_temperature, float ref_latitude, float ref_longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, nas_n);
- _mav_put_float(buf, 12, nas_e);
- _mav_put_float(buf, 16, nas_d);
- _mav_put_float(buf, 20, nas_vn);
- _mav_put_float(buf, 24, nas_ve);
- _mav_put_float(buf, 28, nas_vd);
- _mav_put_float(buf, 32, nas_qx);
- _mav_put_float(buf, 36, nas_qy);
- _mav_put_float(buf, 40, nas_qz);
- _mav_put_float(buf, 44, nas_qw);
- _mav_put_float(buf, 48, nas_bias_x);
- _mav_put_float(buf, 52, nas_bias_y);
- _mav_put_float(buf, 56, nas_bias_z);
- _mav_put_float(buf, 60, ref_pressure);
- _mav_put_float(buf, 64, ref_temperature);
- _mav_put_float(buf, 68, ref_latitude);
- _mav_put_float(buf, 72, ref_longitude);
- _mav_put_uint8_t(buf, 76, state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAS_TM, buf, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-#else
- mavlink_nas_tm_t *packet = (mavlink_nas_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->nas_n = nas_n;
- packet->nas_e = nas_e;
- packet->nas_d = nas_d;
- packet->nas_vn = nas_vn;
- packet->nas_ve = nas_ve;
- packet->nas_vd = nas_vd;
- packet->nas_qx = nas_qx;
- packet->nas_qy = nas_qy;
- packet->nas_qz = nas_qz;
- packet->nas_qw = nas_qw;
- packet->nas_bias_x = nas_bias_x;
- packet->nas_bias_y = nas_bias_y;
- packet->nas_bias_z = nas_bias_z;
- packet->ref_pressure = ref_pressure;
- packet->ref_temperature = ref_temperature;
- packet->ref_latitude = ref_latitude;
- packet->ref_longitude = ref_longitude;
- packet->state = state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAS_TM, (const char *)packet, MAVLINK_MSG_ID_NAS_TM_MIN_LEN, MAVLINK_MSG_ID_NAS_TM_LEN, MAVLINK_MSG_ID_NAS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE NAS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from nas_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_nas_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field state from nas_tm message
- *
- * @return NAS current state
- */
-static inline uint8_t mavlink_msg_nas_tm_get_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 76);
-}
-
-/**
- * @brief Get field nas_n from nas_tm message
- *
- * @return [deg] Navigation system estimated noth position
- */
-static inline float mavlink_msg_nas_tm_get_nas_n(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field nas_e from nas_tm message
- *
- * @return [deg] Navigation system estimated east position
- */
-static inline float mavlink_msg_nas_tm_get_nas_e(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field nas_d from nas_tm message
- *
- * @return [m] Navigation system estimated down position
- */
-static inline float mavlink_msg_nas_tm_get_nas_d(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field nas_vn from nas_tm message
- *
- * @return [m/s] Navigation system estimated north velocity
- */
-static inline float mavlink_msg_nas_tm_get_nas_vn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field nas_ve from nas_tm message
- *
- * @return [m/s] Navigation system estimated east velocity
- */
-static inline float mavlink_msg_nas_tm_get_nas_ve(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field nas_vd from nas_tm message
- *
- * @return [m/s] Navigation system estimated down velocity
- */
-static inline float mavlink_msg_nas_tm_get_nas_vd(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field nas_qx from nas_tm message
- *
- * @return [deg] Navigation system estimated attitude (qx)
- */
-static inline float mavlink_msg_nas_tm_get_nas_qx(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field nas_qy from nas_tm message
- *
- * @return [deg] Navigation system estimated attitude (qy)
- */
-static inline float mavlink_msg_nas_tm_get_nas_qy(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field nas_qz from nas_tm message
- *
- * @return [deg] Navigation system estimated attitude (qz)
- */
-static inline float mavlink_msg_nas_tm_get_nas_qz(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field nas_qw from nas_tm message
- *
- * @return [deg] Navigation system estimated attitude (qw)
- */
-static inline float mavlink_msg_nas_tm_get_nas_qw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field nas_bias_x from nas_tm message
- *
- * @return Navigation system gyroscope bias on x axis
- */
-static inline float mavlink_msg_nas_tm_get_nas_bias_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field nas_bias_y from nas_tm message
- *
- * @return Navigation system gyroscope bias on x axis
- */
-static inline float mavlink_msg_nas_tm_get_nas_bias_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field nas_bias_z from nas_tm message
- *
- * @return Navigation system gyroscope bias on x axis
- */
-static inline float mavlink_msg_nas_tm_get_nas_bias_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field ref_pressure from nas_tm message
- *
- * @return [Pa] Calibration pressure
- */
-static inline float mavlink_msg_nas_tm_get_ref_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field ref_temperature from nas_tm message
- *
- * @return [degC] Calibration temperature
- */
-static inline float mavlink_msg_nas_tm_get_ref_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field ref_latitude from nas_tm message
- *
- * @return [deg] Calibration latitude
- */
-static inline float mavlink_msg_nas_tm_get_ref_latitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field ref_longitude from nas_tm message
- *
- * @return [deg] Calibration longitude
- */
-static inline float mavlink_msg_nas_tm_get_ref_longitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 72);
-}
-
-/**
- * @brief Decode a nas_tm message into a struct
- *
- * @param msg The message to decode
- * @param nas_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_nas_tm_decode(const mavlink_message_t* msg, mavlink_nas_tm_t* nas_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- nas_tm->timestamp = mavlink_msg_nas_tm_get_timestamp(msg);
- nas_tm->nas_n = mavlink_msg_nas_tm_get_nas_n(msg);
- nas_tm->nas_e = mavlink_msg_nas_tm_get_nas_e(msg);
- nas_tm->nas_d = mavlink_msg_nas_tm_get_nas_d(msg);
- nas_tm->nas_vn = mavlink_msg_nas_tm_get_nas_vn(msg);
- nas_tm->nas_ve = mavlink_msg_nas_tm_get_nas_ve(msg);
- nas_tm->nas_vd = mavlink_msg_nas_tm_get_nas_vd(msg);
- nas_tm->nas_qx = mavlink_msg_nas_tm_get_nas_qx(msg);
- nas_tm->nas_qy = mavlink_msg_nas_tm_get_nas_qy(msg);
- nas_tm->nas_qz = mavlink_msg_nas_tm_get_nas_qz(msg);
- nas_tm->nas_qw = mavlink_msg_nas_tm_get_nas_qw(msg);
- nas_tm->nas_bias_x = mavlink_msg_nas_tm_get_nas_bias_x(msg);
- nas_tm->nas_bias_y = mavlink_msg_nas_tm_get_nas_bias_y(msg);
- nas_tm->nas_bias_z = mavlink_msg_nas_tm_get_nas_bias_z(msg);
- nas_tm->ref_pressure = mavlink_msg_nas_tm_get_ref_pressure(msg);
- nas_tm->ref_temperature = mavlink_msg_nas_tm_get_ref_temperature(msg);
- nas_tm->ref_latitude = mavlink_msg_nas_tm_get_ref_latitude(msg);
- nas_tm->ref_longitude = mavlink_msg_nas_tm_get_ref_longitude(msg);
- nas_tm->state = mavlink_msg_nas_tm_get_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_NAS_TM_LEN? msg->len : MAVLINK_MSG_ID_NAS_TM_LEN;
- memset(nas_tm, 0, MAVLINK_MSG_ID_NAS_TM_LEN);
- memcpy(nas_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_payload_flight_tm.h b/mavlink_lib/pyxis/mavlink_msg_payload_flight_tm.h
deleted file mode 100644
index 52fda9f319613a2b2bebc93ea799d6fa19c11739..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_payload_flight_tm.h
+++ /dev/null
@@ -1,1263 +0,0 @@
-#pragma once
-// MESSAGE PAYLOAD_FLIGHT_TM PACKING
-
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM 208
-
-
-typedef struct __mavlink_payload_flight_tm_t {
- uint64_t timestamp; /*< [us] Timestamp in milliseconds*/
- float pressure_ada; /*< [Pa] Atmospheric pressure estimated by ADA*/
- float pressure_digi; /*< [Pa] Pressure from digital sensor*/
- float pressure_static; /*< [Pa] Pressure from static port*/
- float pressure_dpl; /*< [Pa] Pressure from deployment vane sensor*/
- float airspeed_pitot; /*< [m/s] Pitot airspeed*/
- float altitude_agl; /*< [m] Altitude above ground level*/
- float acc_x; /*< [m/s^2] Acceleration on X axis (body)*/
- float acc_y; /*< [m/s^2] Acceleration on Y axis (body)*/
- float acc_z; /*< [m/s^2] Acceleration on Z axis (body)*/
- float gyro_x; /*< [rad/s] Angular speed on X axis (body)*/
- float gyro_y; /*< [rad/s] Angular speed on Y axis (body)*/
- float gyro_z; /*< [rad/s] Angular speed on Z axis (body)*/
- float mag_x; /*< [uT] Magnetic field on X axis (body)*/
- float mag_y; /*< [uT] Magnetic field on Y axis (body)*/
- float mag_z; /*< [uT] Magnetic field on Z axis (body)*/
- float gps_lat; /*< [deg] Latitude*/
- float gps_lon; /*< [deg] Longitude*/
- float gps_alt; /*< [m] GPS Altitude*/
- float left_servo_angle; /*< [deg] Left servo motor angle*/
- float right_servo_angle; /*< [deg] Right servo motor angle*/
- float nas_n; /*< [deg] Navigation system estimated noth position*/
- float nas_e; /*< [deg] Navigation system estimated east position*/
- float nas_d; /*< [m] Navigation system estimated down position*/
- float nas_vn; /*< [m/s] Navigation system estimated north velocity*/
- float nas_ve; /*< [m/s] Navigation system estimated east velocity*/
- float nas_vd; /*< [m/s] Navigation system estimated down velocity*/
- float nas_qx; /*< [deg] Navigation system estimated attitude (qx)*/
- float nas_qy; /*< [deg] Navigation system estimated attitude (qy)*/
- float nas_qz; /*< [deg] Navigation system estimated attitude (qz)*/
- float nas_qw; /*< [deg] Navigation system estimated attitude (qw)*/
- float nas_bias_x; /*< Navigation system gyroscope bias on x axis*/
- float nas_bias_y; /*< Navigation system gyroscope bias on x axis*/
- float nas_bias_z; /*< Navigation system gyroscope bias on x axis*/
- float vbat; /*< [V] Battery voltage*/
- float vsupply_5v; /*< [V] Power supply 5V*/
- float temperature; /*< [degC] Temperature*/
- uint8_t ada_state; /*< ADA Controller State*/
- uint8_t fmm_state; /*< Flight Mode Manager State*/
- uint8_t nas_state; /*< Navigation System FSM State*/
- uint8_t gps_fix; /*< GPS fix (1 = fix, 0 = no fix)*/
- uint8_t pin_nosecone; /*< Nosecone pin status (1 = connected, 0 = disconnected)*/
- int8_t logger_error; /*< Logger error (0 = no error)*/
-} mavlink_payload_flight_tm_t;
-
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN 158
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN 158
-#define MAVLINK_MSG_ID_208_LEN 158
-#define MAVLINK_MSG_ID_208_MIN_LEN 158
-
-#define MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC 193
-#define MAVLINK_MSG_ID_208_CRC 193
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM { \
- 208, \
- "PAYLOAD_FLIGHT_TM", \
- 43, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_flight_tm_t, timestamp) }, \
- { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 152, offsetof(mavlink_payload_flight_tm_t, ada_state) }, \
- { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 153, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \
- { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 154, offsetof(mavlink_payload_flight_tm_t, nas_state) }, \
- { "pressure_ada", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_payload_flight_tm_t, pressure_ada) }, \
- { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_payload_flight_tm_t, pressure_digi) }, \
- { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_payload_flight_tm_t, pressure_static) }, \
- { "pressure_dpl", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_payload_flight_tm_t, pressure_dpl) }, \
- { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_payload_flight_tm_t, airspeed_pitot) }, \
- { "altitude_agl", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_payload_flight_tm_t, altitude_agl) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_payload_flight_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_payload_flight_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_payload_flight_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_payload_flight_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_payload_flight_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_payload_flight_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_payload_flight_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_flight_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_flight_tm_t, mag_z) }, \
- { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 155, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \
- { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_flight_tm_t, gps_lat) }, \
- { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_payload_flight_tm_t, gps_lon) }, \
- { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_payload_flight_tm_t, gps_alt) }, \
- { "left_servo_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_payload_flight_tm_t, left_servo_angle) }, \
- { "right_servo_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_payload_flight_tm_t, right_servo_angle) }, \
- { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_payload_flight_tm_t, nas_n) }, \
- { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_payload_flight_tm_t, nas_e) }, \
- { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_payload_flight_tm_t, nas_d) }, \
- { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_payload_flight_tm_t, nas_vn) }, \
- { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_payload_flight_tm_t, nas_ve) }, \
- { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_payload_flight_tm_t, nas_vd) }, \
- { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_payload_flight_tm_t, nas_qx) }, \
- { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_payload_flight_tm_t, nas_qy) }, \
- { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_payload_flight_tm_t, nas_qz) }, \
- { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_payload_flight_tm_t, nas_qw) }, \
- { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_payload_flight_tm_t, nas_bias_x) }, \
- { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_payload_flight_tm_t, nas_bias_y) }, \
- { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_payload_flight_tm_t, nas_bias_z) }, \
- { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \
- { "vbat", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_payload_flight_tm_t, vbat) }, \
- { "vsupply_5v", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_flight_tm_t, vsupply_5v) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
- { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 157, offsetof(mavlink_payload_flight_tm_t, logger_error) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM { \
- "PAYLOAD_FLIGHT_TM", \
- 43, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_flight_tm_t, timestamp) }, \
- { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 152, offsetof(mavlink_payload_flight_tm_t, ada_state) }, \
- { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 153, offsetof(mavlink_payload_flight_tm_t, fmm_state) }, \
- { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 154, offsetof(mavlink_payload_flight_tm_t, nas_state) }, \
- { "pressure_ada", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_payload_flight_tm_t, pressure_ada) }, \
- { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_payload_flight_tm_t, pressure_digi) }, \
- { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_payload_flight_tm_t, pressure_static) }, \
- { "pressure_dpl", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_payload_flight_tm_t, pressure_dpl) }, \
- { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_payload_flight_tm_t, airspeed_pitot) }, \
- { "altitude_agl", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_payload_flight_tm_t, altitude_agl) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_payload_flight_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_payload_flight_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_payload_flight_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_payload_flight_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_payload_flight_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_payload_flight_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_payload_flight_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_flight_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_flight_tm_t, mag_z) }, \
- { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 155, offsetof(mavlink_payload_flight_tm_t, gps_fix) }, \
- { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_flight_tm_t, gps_lat) }, \
- { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_payload_flight_tm_t, gps_lon) }, \
- { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_payload_flight_tm_t, gps_alt) }, \
- { "left_servo_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_payload_flight_tm_t, left_servo_angle) }, \
- { "right_servo_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_payload_flight_tm_t, right_servo_angle) }, \
- { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_payload_flight_tm_t, nas_n) }, \
- { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_payload_flight_tm_t, nas_e) }, \
- { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_payload_flight_tm_t, nas_d) }, \
- { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_payload_flight_tm_t, nas_vn) }, \
- { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_payload_flight_tm_t, nas_ve) }, \
- { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_payload_flight_tm_t, nas_vd) }, \
- { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_payload_flight_tm_t, nas_qx) }, \
- { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_payload_flight_tm_t, nas_qy) }, \
- { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_payload_flight_tm_t, nas_qz) }, \
- { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_payload_flight_tm_t, nas_qw) }, \
- { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_payload_flight_tm_t, nas_bias_x) }, \
- { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_payload_flight_tm_t, nas_bias_y) }, \
- { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_payload_flight_tm_t, nas_bias_z) }, \
- { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_payload_flight_tm_t, pin_nosecone) }, \
- { "vbat", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_payload_flight_tm_t, vbat) }, \
- { "vsupply_5v", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_payload_flight_tm_t, vsupply_5v) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_payload_flight_tm_t, temperature) }, \
- { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 157, offsetof(mavlink_payload_flight_tm_t, logger_error) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a payload_flight_tm 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 in milliseconds
- * @param ada_state ADA Controller State
- * @param fmm_state Flight Mode Manager State
- * @param nas_state Navigation System FSM State
- * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane sensor
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param altitude_agl [m] Altitude above ground level
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param left_servo_angle [deg] Left servo motor angle
- * @param right_servo_angle [deg] Right servo motor angle
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on x axis
- * @param nas_bias_z Navigation system gyroscope bias on x axis
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param vbat [V] Battery voltage
- * @param vsupply_5v [V] Power supply 5V
- * @param temperature [degC] Temperature
- * @param logger_error Logger error (0 = no error)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t nas_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_nosecone, float vbat, float vsupply_5v, float temperature, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_ada);
- _mav_put_float(buf, 12, pressure_digi);
- _mav_put_float(buf, 16, pressure_static);
- _mav_put_float(buf, 20, pressure_dpl);
- _mav_put_float(buf, 24, airspeed_pitot);
- _mav_put_float(buf, 28, altitude_agl);
- _mav_put_float(buf, 32, acc_x);
- _mav_put_float(buf, 36, acc_y);
- _mav_put_float(buf, 40, acc_z);
- _mav_put_float(buf, 44, gyro_x);
- _mav_put_float(buf, 48, gyro_y);
- _mav_put_float(buf, 52, gyro_z);
- _mav_put_float(buf, 56, mag_x);
- _mav_put_float(buf, 60, mag_y);
- _mav_put_float(buf, 64, mag_z);
- _mav_put_float(buf, 68, gps_lat);
- _mav_put_float(buf, 72, gps_lon);
- _mav_put_float(buf, 76, gps_alt);
- _mav_put_float(buf, 80, left_servo_angle);
- _mav_put_float(buf, 84, right_servo_angle);
- _mav_put_float(buf, 88, nas_n);
- _mav_put_float(buf, 92, nas_e);
- _mav_put_float(buf, 96, nas_d);
- _mav_put_float(buf, 100, nas_vn);
- _mav_put_float(buf, 104, nas_ve);
- _mav_put_float(buf, 108, nas_vd);
- _mav_put_float(buf, 112, nas_qx);
- _mav_put_float(buf, 116, nas_qy);
- _mav_put_float(buf, 120, nas_qz);
- _mav_put_float(buf, 124, nas_qw);
- _mav_put_float(buf, 128, nas_bias_x);
- _mav_put_float(buf, 132, nas_bias_y);
- _mav_put_float(buf, 136, nas_bias_z);
- _mav_put_float(buf, 140, vbat);
- _mav_put_float(buf, 144, vsupply_5v);
- _mav_put_float(buf, 148, temperature);
- _mav_put_uint8_t(buf, 152, ada_state);
- _mav_put_uint8_t(buf, 153, fmm_state);
- _mav_put_uint8_t(buf, 154, nas_state);
- _mav_put_uint8_t(buf, 155, gps_fix);
- _mav_put_uint8_t(buf, 156, pin_nosecone);
- _mav_put_int8_t(buf, 157, logger_error);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
-#else
- mavlink_payload_flight_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_ada = pressure_ada;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.pressure_dpl = pressure_dpl;
- packet.airspeed_pitot = airspeed_pitot;
- packet.altitude_agl = altitude_agl;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.left_servo_angle = left_servo_angle;
- packet.right_servo_angle = right_servo_angle;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.vbat = vbat;
- packet.vsupply_5v = vsupply_5v;
- packet.temperature = temperature;
- packet.ada_state = ada_state;
- packet.fmm_state = fmm_state;
- packet.nas_state = nas_state;
- packet.gps_fix = gps_fix;
- packet.pin_nosecone = pin_nosecone;
- packet.logger_error = logger_error;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-}
-
-/**
- * @brief Pack a payload_flight_tm 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 in milliseconds
- * @param ada_state ADA Controller State
- * @param fmm_state Flight Mode Manager State
- * @param nas_state Navigation System FSM State
- * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane sensor
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param altitude_agl [m] Altitude above ground level
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param left_servo_angle [deg] Left servo motor angle
- * @param right_servo_angle [deg] Right servo motor angle
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on x axis
- * @param nas_bias_z Navigation system gyroscope bias on x axis
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param vbat [V] Battery voltage
- * @param vsupply_5v [V] Power supply 5V
- * @param temperature [degC] Temperature
- * @param logger_error Logger error (0 = no error)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_payload_flight_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t ada_state,uint8_t fmm_state,uint8_t nas_state,float pressure_ada,float pressure_digi,float pressure_static,float pressure_dpl,float airspeed_pitot,float altitude_agl,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float left_servo_angle,float right_servo_angle,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,uint8_t pin_nosecone,float vbat,float vsupply_5v,float temperature,int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_ada);
- _mav_put_float(buf, 12, pressure_digi);
- _mav_put_float(buf, 16, pressure_static);
- _mav_put_float(buf, 20, pressure_dpl);
- _mav_put_float(buf, 24, airspeed_pitot);
- _mav_put_float(buf, 28, altitude_agl);
- _mav_put_float(buf, 32, acc_x);
- _mav_put_float(buf, 36, acc_y);
- _mav_put_float(buf, 40, acc_z);
- _mav_put_float(buf, 44, gyro_x);
- _mav_put_float(buf, 48, gyro_y);
- _mav_put_float(buf, 52, gyro_z);
- _mav_put_float(buf, 56, mag_x);
- _mav_put_float(buf, 60, mag_y);
- _mav_put_float(buf, 64, mag_z);
- _mav_put_float(buf, 68, gps_lat);
- _mav_put_float(buf, 72, gps_lon);
- _mav_put_float(buf, 76, gps_alt);
- _mav_put_float(buf, 80, left_servo_angle);
- _mav_put_float(buf, 84, right_servo_angle);
- _mav_put_float(buf, 88, nas_n);
- _mav_put_float(buf, 92, nas_e);
- _mav_put_float(buf, 96, nas_d);
- _mav_put_float(buf, 100, nas_vn);
- _mav_put_float(buf, 104, nas_ve);
- _mav_put_float(buf, 108, nas_vd);
- _mav_put_float(buf, 112, nas_qx);
- _mav_put_float(buf, 116, nas_qy);
- _mav_put_float(buf, 120, nas_qz);
- _mav_put_float(buf, 124, nas_qw);
- _mav_put_float(buf, 128, nas_bias_x);
- _mav_put_float(buf, 132, nas_bias_y);
- _mav_put_float(buf, 136, nas_bias_z);
- _mav_put_float(buf, 140, vbat);
- _mav_put_float(buf, 144, vsupply_5v);
- _mav_put_float(buf, 148, temperature);
- _mav_put_uint8_t(buf, 152, ada_state);
- _mav_put_uint8_t(buf, 153, fmm_state);
- _mav_put_uint8_t(buf, 154, nas_state);
- _mav_put_uint8_t(buf, 155, gps_fix);
- _mav_put_uint8_t(buf, 156, pin_nosecone);
- _mav_put_int8_t(buf, 157, logger_error);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
-#else
- mavlink_payload_flight_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_ada = pressure_ada;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.pressure_dpl = pressure_dpl;
- packet.airspeed_pitot = airspeed_pitot;
- packet.altitude_agl = altitude_agl;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.left_servo_angle = left_servo_angle;
- packet.right_servo_angle = right_servo_angle;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.vbat = vbat;
- packet.vsupply_5v = vsupply_5v;
- packet.temperature = temperature;
- packet.ada_state = ada_state;
- packet.fmm_state = fmm_state;
- packet.nas_state = nas_state;
- packet.gps_fix = gps_fix;
- packet.pin_nosecone = pin_nosecone;
- packet.logger_error = logger_error;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-}
-
-/**
- * @brief Encode a payload_flight_tm 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 payload_flight_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_payload_flight_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_payload_flight_tm_t* payload_flight_tm)
-{
- return mavlink_msg_payload_flight_tm_pack(system_id, component_id, msg, payload_flight_tm->timestamp, payload_flight_tm->ada_state, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->pressure_ada, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->pressure_dpl, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->pin_nosecone, payload_flight_tm->vbat, payload_flight_tm->vsupply_5v, payload_flight_tm->temperature, payload_flight_tm->logger_error);
-}
-
-/**
- * @brief Encode a payload_flight_tm 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 payload_flight_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_payload_flight_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_payload_flight_tm_t* payload_flight_tm)
-{
- return mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, chan, msg, payload_flight_tm->timestamp, payload_flight_tm->ada_state, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->pressure_ada, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->pressure_dpl, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->pin_nosecone, payload_flight_tm->vbat, payload_flight_tm->vsupply_5v, payload_flight_tm->temperature, payload_flight_tm->logger_error);
-}
-
-/**
- * @brief Send a payload_flight_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp in milliseconds
- * @param ada_state ADA Controller State
- * @param fmm_state Flight Mode Manager State
- * @param nas_state Navigation System FSM State
- * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane sensor
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param altitude_agl [m] Altitude above ground level
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param left_servo_angle [deg] Left servo motor angle
- * @param right_servo_angle [deg] Right servo motor angle
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on x axis
- * @param nas_bias_z Navigation system gyroscope bias on x axis
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param vbat [V] Battery voltage
- * @param vsupply_5v [V] Power supply 5V
- * @param temperature [degC] Temperature
- * @param logger_error Logger error (0 = no error)
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_payload_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t nas_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_nosecone, float vbat, float vsupply_5v, float temperature, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_ada);
- _mav_put_float(buf, 12, pressure_digi);
- _mav_put_float(buf, 16, pressure_static);
- _mav_put_float(buf, 20, pressure_dpl);
- _mav_put_float(buf, 24, airspeed_pitot);
- _mav_put_float(buf, 28, altitude_agl);
- _mav_put_float(buf, 32, acc_x);
- _mav_put_float(buf, 36, acc_y);
- _mav_put_float(buf, 40, acc_z);
- _mav_put_float(buf, 44, gyro_x);
- _mav_put_float(buf, 48, gyro_y);
- _mav_put_float(buf, 52, gyro_z);
- _mav_put_float(buf, 56, mag_x);
- _mav_put_float(buf, 60, mag_y);
- _mav_put_float(buf, 64, mag_z);
- _mav_put_float(buf, 68, gps_lat);
- _mav_put_float(buf, 72, gps_lon);
- _mav_put_float(buf, 76, gps_alt);
- _mav_put_float(buf, 80, left_servo_angle);
- _mav_put_float(buf, 84, right_servo_angle);
- _mav_put_float(buf, 88, nas_n);
- _mav_put_float(buf, 92, nas_e);
- _mav_put_float(buf, 96, nas_d);
- _mav_put_float(buf, 100, nas_vn);
- _mav_put_float(buf, 104, nas_ve);
- _mav_put_float(buf, 108, nas_vd);
- _mav_put_float(buf, 112, nas_qx);
- _mav_put_float(buf, 116, nas_qy);
- _mav_put_float(buf, 120, nas_qz);
- _mav_put_float(buf, 124, nas_qw);
- _mav_put_float(buf, 128, nas_bias_x);
- _mav_put_float(buf, 132, nas_bias_y);
- _mav_put_float(buf, 136, nas_bias_z);
- _mav_put_float(buf, 140, vbat);
- _mav_put_float(buf, 144, vsupply_5v);
- _mav_put_float(buf, 148, temperature);
- _mav_put_uint8_t(buf, 152, ada_state);
- _mav_put_uint8_t(buf, 153, fmm_state);
- _mav_put_uint8_t(buf, 154, nas_state);
- _mav_put_uint8_t(buf, 155, gps_fix);
- _mav_put_uint8_t(buf, 156, pin_nosecone);
- _mav_put_int8_t(buf, 157, logger_error);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-#else
- mavlink_payload_flight_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_ada = pressure_ada;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.pressure_dpl = pressure_dpl;
- packet.airspeed_pitot = airspeed_pitot;
- packet.altitude_agl = altitude_agl;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.left_servo_angle = left_servo_angle;
- packet.right_servo_angle = right_servo_angle;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.vbat = vbat;
- packet.vsupply_5v = vsupply_5v;
- packet.temperature = temperature;
- packet.ada_state = ada_state;
- packet.fmm_state = fmm_state;
- packet.nas_state = nas_state;
- packet.gps_fix = gps_fix;
- packet.pin_nosecone = pin_nosecone;
- packet.logger_error = logger_error;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, (const char *)&packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a payload_flight_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_payload_flight_tm_send_struct(mavlink_channel_t chan, const mavlink_payload_flight_tm_t* payload_flight_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_payload_flight_tm_send(chan, payload_flight_tm->timestamp, payload_flight_tm->ada_state, payload_flight_tm->fmm_state, payload_flight_tm->nas_state, payload_flight_tm->pressure_ada, payload_flight_tm->pressure_digi, payload_flight_tm->pressure_static, payload_flight_tm->pressure_dpl, payload_flight_tm->airspeed_pitot, payload_flight_tm->altitude_agl, payload_flight_tm->acc_x, payload_flight_tm->acc_y, payload_flight_tm->acc_z, payload_flight_tm->gyro_x, payload_flight_tm->gyro_y, payload_flight_tm->gyro_z, payload_flight_tm->mag_x, payload_flight_tm->mag_y, payload_flight_tm->mag_z, payload_flight_tm->gps_fix, payload_flight_tm->gps_lat, payload_flight_tm->gps_lon, payload_flight_tm->gps_alt, payload_flight_tm->left_servo_angle, payload_flight_tm->right_servo_angle, payload_flight_tm->nas_n, payload_flight_tm->nas_e, payload_flight_tm->nas_d, payload_flight_tm->nas_vn, payload_flight_tm->nas_ve, payload_flight_tm->nas_vd, payload_flight_tm->nas_qx, payload_flight_tm->nas_qy, payload_flight_tm->nas_qz, payload_flight_tm->nas_qw, payload_flight_tm->nas_bias_x, payload_flight_tm->nas_bias_y, payload_flight_tm->nas_bias_z, payload_flight_tm->pin_nosecone, payload_flight_tm->vbat, payload_flight_tm->vsupply_5v, payload_flight_tm->temperature, payload_flight_tm->logger_error);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, (const char *)payload_flight_tm, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_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_payload_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t nas_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float left_servo_angle, float right_servo_angle, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_nosecone, float vbat, float vsupply_5v, float temperature, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_ada);
- _mav_put_float(buf, 12, pressure_digi);
- _mav_put_float(buf, 16, pressure_static);
- _mav_put_float(buf, 20, pressure_dpl);
- _mav_put_float(buf, 24, airspeed_pitot);
- _mav_put_float(buf, 28, altitude_agl);
- _mav_put_float(buf, 32, acc_x);
- _mav_put_float(buf, 36, acc_y);
- _mav_put_float(buf, 40, acc_z);
- _mav_put_float(buf, 44, gyro_x);
- _mav_put_float(buf, 48, gyro_y);
- _mav_put_float(buf, 52, gyro_z);
- _mav_put_float(buf, 56, mag_x);
- _mav_put_float(buf, 60, mag_y);
- _mav_put_float(buf, 64, mag_z);
- _mav_put_float(buf, 68, gps_lat);
- _mav_put_float(buf, 72, gps_lon);
- _mav_put_float(buf, 76, gps_alt);
- _mav_put_float(buf, 80, left_servo_angle);
- _mav_put_float(buf, 84, right_servo_angle);
- _mav_put_float(buf, 88, nas_n);
- _mav_put_float(buf, 92, nas_e);
- _mav_put_float(buf, 96, nas_d);
- _mav_put_float(buf, 100, nas_vn);
- _mav_put_float(buf, 104, nas_ve);
- _mav_put_float(buf, 108, nas_vd);
- _mav_put_float(buf, 112, nas_qx);
- _mav_put_float(buf, 116, nas_qy);
- _mav_put_float(buf, 120, nas_qz);
- _mav_put_float(buf, 124, nas_qw);
- _mav_put_float(buf, 128, nas_bias_x);
- _mav_put_float(buf, 132, nas_bias_y);
- _mav_put_float(buf, 136, nas_bias_z);
- _mav_put_float(buf, 140, vbat);
- _mav_put_float(buf, 144, vsupply_5v);
- _mav_put_float(buf, 148, temperature);
- _mav_put_uint8_t(buf, 152, ada_state);
- _mav_put_uint8_t(buf, 153, fmm_state);
- _mav_put_uint8_t(buf, 154, nas_state);
- _mav_put_uint8_t(buf, 155, gps_fix);
- _mav_put_uint8_t(buf, 156, pin_nosecone);
- _mav_put_int8_t(buf, 157, logger_error);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, buf, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-#else
- mavlink_payload_flight_tm_t *packet = (mavlink_payload_flight_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->pressure_ada = pressure_ada;
- packet->pressure_digi = pressure_digi;
- packet->pressure_static = pressure_static;
- packet->pressure_dpl = pressure_dpl;
- packet->airspeed_pitot = airspeed_pitot;
- packet->altitude_agl = altitude_agl;
- packet->acc_x = acc_x;
- packet->acc_y = acc_y;
- packet->acc_z = acc_z;
- packet->gyro_x = gyro_x;
- packet->gyro_y = gyro_y;
- packet->gyro_z = gyro_z;
- packet->mag_x = mag_x;
- packet->mag_y = mag_y;
- packet->mag_z = mag_z;
- packet->gps_lat = gps_lat;
- packet->gps_lon = gps_lon;
- packet->gps_alt = gps_alt;
- packet->left_servo_angle = left_servo_angle;
- packet->right_servo_angle = right_servo_angle;
- packet->nas_n = nas_n;
- packet->nas_e = nas_e;
- packet->nas_d = nas_d;
- packet->nas_vn = nas_vn;
- packet->nas_ve = nas_ve;
- packet->nas_vd = nas_vd;
- packet->nas_qx = nas_qx;
- packet->nas_qy = nas_qy;
- packet->nas_qz = nas_qz;
- packet->nas_qw = nas_qw;
- packet->nas_bias_x = nas_bias_x;
- packet->nas_bias_y = nas_bias_y;
- packet->nas_bias_z = nas_bias_z;
- packet->vbat = vbat;
- packet->vsupply_5v = vsupply_5v;
- packet->temperature = temperature;
- packet->ada_state = ada_state;
- packet->fmm_state = fmm_state;
- packet->nas_state = nas_state;
- packet->gps_fix = gps_fix;
- packet->pin_nosecone = pin_nosecone;
- packet->logger_error = logger_error;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM, (const char *)packet, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE PAYLOAD_FLIGHT_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from payload_flight_tm message
- *
- * @return [us] Timestamp in milliseconds
- */
-static inline uint64_t mavlink_msg_payload_flight_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field ada_state from payload_flight_tm message
- *
- * @return ADA Controller State
- */
-static inline uint8_t mavlink_msg_payload_flight_tm_get_ada_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 152);
-}
-
-/**
- * @brief Get field fmm_state from payload_flight_tm message
- *
- * @return Flight Mode Manager State
- */
-static inline uint8_t mavlink_msg_payload_flight_tm_get_fmm_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 153);
-}
-
-/**
- * @brief Get field nas_state from payload_flight_tm message
- *
- * @return Navigation System FSM State
- */
-static inline uint8_t mavlink_msg_payload_flight_tm_get_nas_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 154);
-}
-
-/**
- * @brief Get field pressure_ada from payload_flight_tm message
- *
- * @return [Pa] Atmospheric pressure estimated by ADA
- */
-static inline float mavlink_msg_payload_flight_tm_get_pressure_ada(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field pressure_digi from payload_flight_tm message
- *
- * @return [Pa] Pressure from digital sensor
- */
-static inline float mavlink_msg_payload_flight_tm_get_pressure_digi(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field pressure_static from payload_flight_tm message
- *
- * @return [Pa] Pressure from static port
- */
-static inline float mavlink_msg_payload_flight_tm_get_pressure_static(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field pressure_dpl from payload_flight_tm message
- *
- * @return [Pa] Pressure from deployment vane sensor
- */
-static inline float mavlink_msg_payload_flight_tm_get_pressure_dpl(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field airspeed_pitot from payload_flight_tm message
- *
- * @return [m/s] Pitot airspeed
- */
-static inline float mavlink_msg_payload_flight_tm_get_airspeed_pitot(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field altitude_agl from payload_flight_tm message
- *
- * @return [m] Altitude above ground level
- */
-static inline float mavlink_msg_payload_flight_tm_get_altitude_agl(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field acc_x from payload_flight_tm message
- *
- * @return [m/s^2] Acceleration on X axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_acc_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field acc_y from payload_flight_tm message
- *
- * @return [m/s^2] Acceleration on Y axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_acc_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field acc_z from payload_flight_tm message
- *
- * @return [m/s^2] Acceleration on Z axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_acc_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field gyro_x from payload_flight_tm message
- *
- * @return [rad/s] Angular speed on X axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_gyro_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field gyro_y from payload_flight_tm message
- *
- * @return [rad/s] Angular speed on Y axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_gyro_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field gyro_z from payload_flight_tm message
- *
- * @return [rad/s] Angular speed on Z axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_gyro_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field mag_x from payload_flight_tm message
- *
- * @return [uT] Magnetic field on X axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_mag_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field mag_y from payload_flight_tm message
- *
- * @return [uT] Magnetic field on Y axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_mag_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field mag_z from payload_flight_tm message
- *
- * @return [uT] Magnetic field on Z axis (body)
- */
-static inline float mavlink_msg_payload_flight_tm_get_mag_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field gps_fix from payload_flight_tm message
- *
- * @return GPS fix (1 = fix, 0 = no fix)
- */
-static inline uint8_t mavlink_msg_payload_flight_tm_get_gps_fix(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 155);
-}
-
-/**
- * @brief Get field gps_lat from payload_flight_tm message
- *
- * @return [deg] Latitude
- */
-static inline float mavlink_msg_payload_flight_tm_get_gps_lat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field gps_lon from payload_flight_tm message
- *
- * @return [deg] Longitude
- */
-static inline float mavlink_msg_payload_flight_tm_get_gps_lon(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 72);
-}
-
-/**
- * @brief Get field gps_alt from payload_flight_tm message
- *
- * @return [m] GPS Altitude
- */
-static inline float mavlink_msg_payload_flight_tm_get_gps_alt(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 76);
-}
-
-/**
- * @brief Get field left_servo_angle from payload_flight_tm message
- *
- * @return [deg] Left servo motor angle
- */
-static inline float mavlink_msg_payload_flight_tm_get_left_servo_angle(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 80);
-}
-
-/**
- * @brief Get field right_servo_angle from payload_flight_tm message
- *
- * @return [deg] Right servo motor angle
- */
-static inline float mavlink_msg_payload_flight_tm_get_right_servo_angle(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 84);
-}
-
-/**
- * @brief Get field nas_n from payload_flight_tm message
- *
- * @return [deg] Navigation system estimated noth position
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_n(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 88);
-}
-
-/**
- * @brief Get field nas_e from payload_flight_tm message
- *
- * @return [deg] Navigation system estimated east position
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_e(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 92);
-}
-
-/**
- * @brief Get field nas_d from payload_flight_tm message
- *
- * @return [m] Navigation system estimated down position
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_d(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 96);
-}
-
-/**
- * @brief Get field nas_vn from payload_flight_tm message
- *
- * @return [m/s] Navigation system estimated north velocity
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_vn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 100);
-}
-
-/**
- * @brief Get field nas_ve from payload_flight_tm message
- *
- * @return [m/s] Navigation system estimated east velocity
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_ve(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 104);
-}
-
-/**
- * @brief Get field nas_vd from payload_flight_tm message
- *
- * @return [m/s] Navigation system estimated down velocity
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_vd(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 108);
-}
-
-/**
- * @brief Get field nas_qx from payload_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qx)
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_qx(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 112);
-}
-
-/**
- * @brief Get field nas_qy from payload_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qy)
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_qy(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 116);
-}
-
-/**
- * @brief Get field nas_qz from payload_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qz)
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_qz(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 120);
-}
-
-/**
- * @brief Get field nas_qw from payload_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qw)
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_qw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 124);
-}
-
-/**
- * @brief Get field nas_bias_x from payload_flight_tm message
- *
- * @return Navigation system gyroscope bias on x axis
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_bias_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 128);
-}
-
-/**
- * @brief Get field nas_bias_y from payload_flight_tm message
- *
- * @return Navigation system gyroscope bias on x axis
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_bias_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 132);
-}
-
-/**
- * @brief Get field nas_bias_z from payload_flight_tm message
- *
- * @return Navigation system gyroscope bias on x axis
- */
-static inline float mavlink_msg_payload_flight_tm_get_nas_bias_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 136);
-}
-
-/**
- * @brief Get field pin_nosecone from payload_flight_tm message
- *
- * @return Nosecone pin status (1 = connected, 0 = disconnected)
- */
-static inline uint8_t mavlink_msg_payload_flight_tm_get_pin_nosecone(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 156);
-}
-
-/**
- * @brief Get field vbat from payload_flight_tm message
- *
- * @return [V] Battery voltage
- */
-static inline float mavlink_msg_payload_flight_tm_get_vbat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 140);
-}
-
-/**
- * @brief Get field vsupply_5v from payload_flight_tm message
- *
- * @return [V] Power supply 5V
- */
-static inline float mavlink_msg_payload_flight_tm_get_vsupply_5v(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 144);
-}
-
-/**
- * @brief Get field temperature from payload_flight_tm message
- *
- * @return [degC] Temperature
- */
-static inline float mavlink_msg_payload_flight_tm_get_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 148);
-}
-
-/**
- * @brief Get field logger_error from payload_flight_tm message
- *
- * @return Logger error (0 = no error)
- */
-static inline int8_t mavlink_msg_payload_flight_tm_get_logger_error(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int8_t(msg, 157);
-}
-
-/**
- * @brief Decode a payload_flight_tm message into a struct
- *
- * @param msg The message to decode
- * @param payload_flight_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_payload_flight_tm_decode(const mavlink_message_t* msg, mavlink_payload_flight_tm_t* payload_flight_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- payload_flight_tm->timestamp = mavlink_msg_payload_flight_tm_get_timestamp(msg);
- payload_flight_tm->pressure_ada = mavlink_msg_payload_flight_tm_get_pressure_ada(msg);
- payload_flight_tm->pressure_digi = mavlink_msg_payload_flight_tm_get_pressure_digi(msg);
- payload_flight_tm->pressure_static = mavlink_msg_payload_flight_tm_get_pressure_static(msg);
- payload_flight_tm->pressure_dpl = mavlink_msg_payload_flight_tm_get_pressure_dpl(msg);
- payload_flight_tm->airspeed_pitot = mavlink_msg_payload_flight_tm_get_airspeed_pitot(msg);
- payload_flight_tm->altitude_agl = mavlink_msg_payload_flight_tm_get_altitude_agl(msg);
- payload_flight_tm->acc_x = mavlink_msg_payload_flight_tm_get_acc_x(msg);
- payload_flight_tm->acc_y = mavlink_msg_payload_flight_tm_get_acc_y(msg);
- payload_flight_tm->acc_z = mavlink_msg_payload_flight_tm_get_acc_z(msg);
- payload_flight_tm->gyro_x = mavlink_msg_payload_flight_tm_get_gyro_x(msg);
- payload_flight_tm->gyro_y = mavlink_msg_payload_flight_tm_get_gyro_y(msg);
- payload_flight_tm->gyro_z = mavlink_msg_payload_flight_tm_get_gyro_z(msg);
- payload_flight_tm->mag_x = mavlink_msg_payload_flight_tm_get_mag_x(msg);
- payload_flight_tm->mag_y = mavlink_msg_payload_flight_tm_get_mag_y(msg);
- payload_flight_tm->mag_z = mavlink_msg_payload_flight_tm_get_mag_z(msg);
- payload_flight_tm->gps_lat = mavlink_msg_payload_flight_tm_get_gps_lat(msg);
- payload_flight_tm->gps_lon = mavlink_msg_payload_flight_tm_get_gps_lon(msg);
- payload_flight_tm->gps_alt = mavlink_msg_payload_flight_tm_get_gps_alt(msg);
- payload_flight_tm->left_servo_angle = mavlink_msg_payload_flight_tm_get_left_servo_angle(msg);
- payload_flight_tm->right_servo_angle = mavlink_msg_payload_flight_tm_get_right_servo_angle(msg);
- payload_flight_tm->nas_n = mavlink_msg_payload_flight_tm_get_nas_n(msg);
- payload_flight_tm->nas_e = mavlink_msg_payload_flight_tm_get_nas_e(msg);
- payload_flight_tm->nas_d = mavlink_msg_payload_flight_tm_get_nas_d(msg);
- payload_flight_tm->nas_vn = mavlink_msg_payload_flight_tm_get_nas_vn(msg);
- payload_flight_tm->nas_ve = mavlink_msg_payload_flight_tm_get_nas_ve(msg);
- payload_flight_tm->nas_vd = mavlink_msg_payload_flight_tm_get_nas_vd(msg);
- payload_flight_tm->nas_qx = mavlink_msg_payload_flight_tm_get_nas_qx(msg);
- payload_flight_tm->nas_qy = mavlink_msg_payload_flight_tm_get_nas_qy(msg);
- payload_flight_tm->nas_qz = mavlink_msg_payload_flight_tm_get_nas_qz(msg);
- payload_flight_tm->nas_qw = mavlink_msg_payload_flight_tm_get_nas_qw(msg);
- payload_flight_tm->nas_bias_x = mavlink_msg_payload_flight_tm_get_nas_bias_x(msg);
- payload_flight_tm->nas_bias_y = mavlink_msg_payload_flight_tm_get_nas_bias_y(msg);
- payload_flight_tm->nas_bias_z = mavlink_msg_payload_flight_tm_get_nas_bias_z(msg);
- payload_flight_tm->vbat = mavlink_msg_payload_flight_tm_get_vbat(msg);
- payload_flight_tm->vsupply_5v = mavlink_msg_payload_flight_tm_get_vsupply_5v(msg);
- payload_flight_tm->temperature = mavlink_msg_payload_flight_tm_get_temperature(msg);
- payload_flight_tm->ada_state = mavlink_msg_payload_flight_tm_get_ada_state(msg);
- payload_flight_tm->fmm_state = mavlink_msg_payload_flight_tm_get_fmm_state(msg);
- payload_flight_tm->nas_state = mavlink_msg_payload_flight_tm_get_nas_state(msg);
- payload_flight_tm->gps_fix = mavlink_msg_payload_flight_tm_get_gps_fix(msg);
- payload_flight_tm->pin_nosecone = mavlink_msg_payload_flight_tm_get_pin_nosecone(msg);
- payload_flight_tm->logger_error = mavlink_msg_payload_flight_tm_get_logger_error(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN? msg->len : MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN;
- memset(payload_flight_tm, 0, MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN);
- memcpy(payload_flight_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_payload_stats_tm.h b/mavlink_lib/pyxis/mavlink_msg_payload_stats_tm.h
deleted file mode 100644
index ec5b0525749f8c0ef27fc66b406ed6b4b23e099f..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_payload_stats_tm.h
+++ /dev/null
@@ -1,563 +0,0 @@
-#pragma once
-// MESSAGE PAYLOAD_STATS_TM PACKING
-
-#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM 210
-
-
-typedef struct __mavlink_payload_stats_tm_t {
- uint64_t liftoff_max_acc_ts; /*< [us] System clock at the maximum liftoff acceleration*/
- uint64_t dpl_ts; /*< [us] System clock at drouge deployment*/
- uint64_t max_z_speed_ts; /*< [us] System clock at ADA max vertical speed*/
- uint64_t apogee_ts; /*< [us] System clock at apogee*/
- float liftoff_max_acc; /*< [m/s2] Maximum liftoff acceleration*/
- float dpl_max_acc; /*< [m/s2] Max acceleration during drouge deployment*/
- float max_z_speed; /*< [m/s] Max measured vertical speed - ADA*/
- float max_airspeed_pitot; /*< [m/s] Max speed read by the pitot tube*/
- float max_speed_altitude; /*< [m] Altitude at max speed*/
- float apogee_lat; /*< [deg] Apogee latitude*/
- float apogee_lon; /*< [deg] Apogee longitude*/
- float apogee_alt; /*< [m] Apogee altitude*/
- float min_pressure; /*< [Pa] Apogee pressure - Digital barometer*/
- float cpu_load; /*< CPU load in percentage*/
- uint32_t free_heap; /*< Amount of available heap in memory*/
-} mavlink_payload_stats_tm_t;
-
-#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN 76
-#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN 76
-#define MAVLINK_MSG_ID_210_LEN 76
-#define MAVLINK_MSG_ID_210_MIN_LEN 76
-
-#define MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC 115
-#define MAVLINK_MSG_ID_210_CRC 115
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM { \
- 210, \
- "PAYLOAD_STATS_TM", \
- 15, \
- { { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc_ts) }, \
- { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc) }, \
- { "dpl_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_payload_stats_tm_t, dpl_ts) }, \
- { "dpl_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_payload_stats_tm_t, dpl_max_acc) }, \
- { "max_z_speed_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_payload_stats_tm_t, max_z_speed_ts) }, \
- { "max_z_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_payload_stats_tm_t, max_z_speed) }, \
- { "max_airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_payload_stats_tm_t, max_airspeed_pitot) }, \
- { "max_speed_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_payload_stats_tm_t, max_speed_altitude) }, \
- { "apogee_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 24, offsetof(mavlink_payload_stats_tm_t, apogee_ts) }, \
- { "apogee_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_payload_stats_tm_t, apogee_lat) }, \
- { "apogee_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_payload_stats_tm_t, apogee_lon) }, \
- { "apogee_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_stats_tm_t, apogee_alt) }, \
- { "min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_stats_tm_t, min_pressure) }, \
- { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_stats_tm_t, cpu_load) }, \
- { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 72, offsetof(mavlink_payload_stats_tm_t, free_heap) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM { \
- "PAYLOAD_STATS_TM", \
- 15, \
- { { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc_ts) }, \
- { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_payload_stats_tm_t, liftoff_max_acc) }, \
- { "dpl_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_payload_stats_tm_t, dpl_ts) }, \
- { "dpl_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_payload_stats_tm_t, dpl_max_acc) }, \
- { "max_z_speed_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_payload_stats_tm_t, max_z_speed_ts) }, \
- { "max_z_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_payload_stats_tm_t, max_z_speed) }, \
- { "max_airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_payload_stats_tm_t, max_airspeed_pitot) }, \
- { "max_speed_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_payload_stats_tm_t, max_speed_altitude) }, \
- { "apogee_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 24, offsetof(mavlink_payload_stats_tm_t, apogee_ts) }, \
- { "apogee_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_payload_stats_tm_t, apogee_lat) }, \
- { "apogee_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_payload_stats_tm_t, apogee_lon) }, \
- { "apogee_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_payload_stats_tm_t, apogee_alt) }, \
- { "min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_payload_stats_tm_t, min_pressure) }, \
- { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_payload_stats_tm_t, cpu_load) }, \
- { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 72, offsetof(mavlink_payload_stats_tm_t, free_heap) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a payload_stats_tm 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 liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param dpl_ts [us] System clock at drouge deployment
- * @param dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param max_z_speed_ts [us] System clock at ADA max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed - ADA
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [us] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param apogee_alt [m] Apogee altitude
- * @param min_pressure [Pa] Apogee pressure - Digital barometer
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_payload_stats_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 8, dpl_ts);
- _mav_put_uint64_t(buf, 16, max_z_speed_ts);
- _mav_put_uint64_t(buf, 24, apogee_ts);
- _mav_put_float(buf, 32, liftoff_max_acc);
- _mav_put_float(buf, 36, dpl_max_acc);
- _mav_put_float(buf, 40, max_z_speed);
- _mav_put_float(buf, 44, max_airspeed_pitot);
- _mav_put_float(buf, 48, max_speed_altitude);
- _mav_put_float(buf, 52, apogee_lat);
- _mav_put_float(buf, 56, apogee_lon);
- _mav_put_float(buf, 60, apogee_alt);
- _mav_put_float(buf, 64, min_pressure);
- _mav_put_float(buf, 68, cpu_load);
- _mav_put_uint32_t(buf, 72, free_heap);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
-#else
- mavlink_payload_stats_tm_t packet;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.dpl_ts = dpl_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.dpl_max_acc = dpl_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.apogee_alt = apogee_alt;
- packet.min_pressure = min_pressure;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PAYLOAD_STATS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-}
-
-/**
- * @brief Pack a payload_stats_tm 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 liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param dpl_ts [us] System clock at drouge deployment
- * @param dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param max_z_speed_ts [us] System clock at ADA max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed - ADA
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [us] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param apogee_alt [m] Apogee altitude
- * @param min_pressure [Pa] Apogee pressure - Digital barometer
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_payload_stats_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t liftoff_max_acc_ts,float liftoff_max_acc,uint64_t dpl_ts,float dpl_max_acc,uint64_t max_z_speed_ts,float max_z_speed,float max_airspeed_pitot,float max_speed_altitude,uint64_t apogee_ts,float apogee_lat,float apogee_lon,float apogee_alt,float min_pressure,float cpu_load,uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 8, dpl_ts);
- _mav_put_uint64_t(buf, 16, max_z_speed_ts);
- _mav_put_uint64_t(buf, 24, apogee_ts);
- _mav_put_float(buf, 32, liftoff_max_acc);
- _mav_put_float(buf, 36, dpl_max_acc);
- _mav_put_float(buf, 40, max_z_speed);
- _mav_put_float(buf, 44, max_airspeed_pitot);
- _mav_put_float(buf, 48, max_speed_altitude);
- _mav_put_float(buf, 52, apogee_lat);
- _mav_put_float(buf, 56, apogee_lon);
- _mav_put_float(buf, 60, apogee_alt);
- _mav_put_float(buf, 64, min_pressure);
- _mav_put_float(buf, 68, cpu_load);
- _mav_put_uint32_t(buf, 72, free_heap);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
-#else
- mavlink_payload_stats_tm_t packet;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.dpl_ts = dpl_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.dpl_max_acc = dpl_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.apogee_alt = apogee_alt;
- packet.min_pressure = min_pressure;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PAYLOAD_STATS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-}
-
-/**
- * @brief Encode a payload_stats_tm 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 payload_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_payload_stats_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_payload_stats_tm_t* payload_stats_tm)
-{
- return mavlink_msg_payload_stats_tm_pack(system_id, component_id, msg, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->max_z_speed_ts, payload_stats_tm->max_z_speed, payload_stats_tm->max_airspeed_pitot, payload_stats_tm->max_speed_altitude, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap);
-}
-
-/**
- * @brief Encode a payload_stats_tm 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 payload_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_payload_stats_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_payload_stats_tm_t* payload_stats_tm)
-{
- return mavlink_msg_payload_stats_tm_pack_chan(system_id, component_id, chan, msg, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->max_z_speed_ts, payload_stats_tm->max_z_speed, payload_stats_tm->max_airspeed_pitot, payload_stats_tm->max_speed_altitude, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap);
-}
-
-/**
- * @brief Send a payload_stats_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param dpl_ts [us] System clock at drouge deployment
- * @param dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param max_z_speed_ts [us] System clock at ADA max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed - ADA
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [us] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param apogee_alt [m] Apogee altitude
- * @param min_pressure [Pa] Apogee pressure - Digital barometer
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_payload_stats_tm_send(mavlink_channel_t chan, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 8, dpl_ts);
- _mav_put_uint64_t(buf, 16, max_z_speed_ts);
- _mav_put_uint64_t(buf, 24, apogee_ts);
- _mav_put_float(buf, 32, liftoff_max_acc);
- _mav_put_float(buf, 36, dpl_max_acc);
- _mav_put_float(buf, 40, max_z_speed);
- _mav_put_float(buf, 44, max_airspeed_pitot);
- _mav_put_float(buf, 48, max_speed_altitude);
- _mav_put_float(buf, 52, apogee_lat);
- _mav_put_float(buf, 56, apogee_lon);
- _mav_put_float(buf, 60, apogee_alt);
- _mav_put_float(buf, 64, min_pressure);
- _mav_put_float(buf, 68, cpu_load);
- _mav_put_uint32_t(buf, 72, free_heap);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM, buf, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-#else
- mavlink_payload_stats_tm_t packet;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.dpl_ts = dpl_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.dpl_max_acc = dpl_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.apogee_alt = apogee_alt;
- packet.min_pressure = min_pressure;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM, (const char *)&packet, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a payload_stats_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_payload_stats_tm_send_struct(mavlink_channel_t chan, const mavlink_payload_stats_tm_t* payload_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_payload_stats_tm_send(chan, payload_stats_tm->liftoff_max_acc_ts, payload_stats_tm->liftoff_max_acc, payload_stats_tm->dpl_ts, payload_stats_tm->dpl_max_acc, payload_stats_tm->max_z_speed_ts, payload_stats_tm->max_z_speed, payload_stats_tm->max_airspeed_pitot, payload_stats_tm->max_speed_altitude, payload_stats_tm->apogee_ts, payload_stats_tm->apogee_lat, payload_stats_tm->apogee_lon, payload_stats_tm->apogee_alt, payload_stats_tm->min_pressure, payload_stats_tm->cpu_load, payload_stats_tm->free_heap);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM, (const char *)payload_stats_tm, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_PAYLOAD_STATS_TM_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_payload_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 8, dpl_ts);
- _mav_put_uint64_t(buf, 16, max_z_speed_ts);
- _mav_put_uint64_t(buf, 24, apogee_ts);
- _mav_put_float(buf, 32, liftoff_max_acc);
- _mav_put_float(buf, 36, dpl_max_acc);
- _mav_put_float(buf, 40, max_z_speed);
- _mav_put_float(buf, 44, max_airspeed_pitot);
- _mav_put_float(buf, 48, max_speed_altitude);
- _mav_put_float(buf, 52, apogee_lat);
- _mav_put_float(buf, 56, apogee_lon);
- _mav_put_float(buf, 60, apogee_alt);
- _mav_put_float(buf, 64, min_pressure);
- _mav_put_float(buf, 68, cpu_load);
- _mav_put_uint32_t(buf, 72, free_heap);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM, buf, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-#else
- mavlink_payload_stats_tm_t *packet = (mavlink_payload_stats_tm_t *)msgbuf;
- packet->liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet->dpl_ts = dpl_ts;
- packet->max_z_speed_ts = max_z_speed_ts;
- packet->apogee_ts = apogee_ts;
- packet->liftoff_max_acc = liftoff_max_acc;
- packet->dpl_max_acc = dpl_max_acc;
- packet->max_z_speed = max_z_speed;
- packet->max_airspeed_pitot = max_airspeed_pitot;
- packet->max_speed_altitude = max_speed_altitude;
- packet->apogee_lat = apogee_lat;
- packet->apogee_lon = apogee_lon;
- packet->apogee_alt = apogee_alt;
- packet->min_pressure = min_pressure;
- packet->cpu_load = cpu_load;
- packet->free_heap = free_heap;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PAYLOAD_STATS_TM, (const char *)packet, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE PAYLOAD_STATS_TM UNPACKING
-
-
-/**
- * @brief Get field liftoff_max_acc_ts from payload_stats_tm message
- *
- * @return [us] System clock at the maximum liftoff acceleration
- */
-static inline uint64_t mavlink_msg_payload_stats_tm_get_liftoff_max_acc_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field liftoff_max_acc from payload_stats_tm message
- *
- * @return [m/s2] Maximum liftoff acceleration
- */
-static inline float mavlink_msg_payload_stats_tm_get_liftoff_max_acc(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field dpl_ts from payload_stats_tm message
- *
- * @return [us] System clock at drouge deployment
- */
-static inline uint64_t mavlink_msg_payload_stats_tm_get_dpl_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 8);
-}
-
-/**
- * @brief Get field dpl_max_acc from payload_stats_tm message
- *
- * @return [m/s2] Max acceleration during drouge deployment
- */
-static inline float mavlink_msg_payload_stats_tm_get_dpl_max_acc(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field max_z_speed_ts from payload_stats_tm message
- *
- * @return [us] System clock at ADA max vertical speed
- */
-static inline uint64_t mavlink_msg_payload_stats_tm_get_max_z_speed_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 16);
-}
-
-/**
- * @brief Get field max_z_speed from payload_stats_tm message
- *
- * @return [m/s] Max measured vertical speed - ADA
- */
-static inline float mavlink_msg_payload_stats_tm_get_max_z_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field max_airspeed_pitot from payload_stats_tm message
- *
- * @return [m/s] Max speed read by the pitot tube
- */
-static inline float mavlink_msg_payload_stats_tm_get_max_airspeed_pitot(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field max_speed_altitude from payload_stats_tm message
- *
- * @return [m] Altitude at max speed
- */
-static inline float mavlink_msg_payload_stats_tm_get_max_speed_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field apogee_ts from payload_stats_tm message
- *
- * @return [us] System clock at apogee
- */
-static inline uint64_t mavlink_msg_payload_stats_tm_get_apogee_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 24);
-}
-
-/**
- * @brief Get field apogee_lat from payload_stats_tm message
- *
- * @return [deg] Apogee latitude
- */
-static inline float mavlink_msg_payload_stats_tm_get_apogee_lat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field apogee_lon from payload_stats_tm message
- *
- * @return [deg] Apogee longitude
- */
-static inline float mavlink_msg_payload_stats_tm_get_apogee_lon(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field apogee_alt from payload_stats_tm message
- *
- * @return [m] Apogee altitude
- */
-static inline float mavlink_msg_payload_stats_tm_get_apogee_alt(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field min_pressure from payload_stats_tm message
- *
- * @return [Pa] Apogee pressure - Digital barometer
- */
-static inline float mavlink_msg_payload_stats_tm_get_min_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field cpu_load from payload_stats_tm message
- *
- * @return CPU load in percentage
- */
-static inline float mavlink_msg_payload_stats_tm_get_cpu_load(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field free_heap from payload_stats_tm message
- *
- * @return Amount of available heap in memory
- */
-static inline uint32_t mavlink_msg_payload_stats_tm_get_free_heap(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 72);
-}
-
-/**
- * @brief Decode a payload_stats_tm message into a struct
- *
- * @param msg The message to decode
- * @param payload_stats_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_payload_stats_tm_decode(const mavlink_message_t* msg, mavlink_payload_stats_tm_t* payload_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- payload_stats_tm->liftoff_max_acc_ts = mavlink_msg_payload_stats_tm_get_liftoff_max_acc_ts(msg);
- payload_stats_tm->dpl_ts = mavlink_msg_payload_stats_tm_get_dpl_ts(msg);
- payload_stats_tm->max_z_speed_ts = mavlink_msg_payload_stats_tm_get_max_z_speed_ts(msg);
- payload_stats_tm->apogee_ts = mavlink_msg_payload_stats_tm_get_apogee_ts(msg);
- payload_stats_tm->liftoff_max_acc = mavlink_msg_payload_stats_tm_get_liftoff_max_acc(msg);
- payload_stats_tm->dpl_max_acc = mavlink_msg_payload_stats_tm_get_dpl_max_acc(msg);
- payload_stats_tm->max_z_speed = mavlink_msg_payload_stats_tm_get_max_z_speed(msg);
- payload_stats_tm->max_airspeed_pitot = mavlink_msg_payload_stats_tm_get_max_airspeed_pitot(msg);
- payload_stats_tm->max_speed_altitude = mavlink_msg_payload_stats_tm_get_max_speed_altitude(msg);
- payload_stats_tm->apogee_lat = mavlink_msg_payload_stats_tm_get_apogee_lat(msg);
- payload_stats_tm->apogee_lon = mavlink_msg_payload_stats_tm_get_apogee_lon(msg);
- payload_stats_tm->apogee_alt = mavlink_msg_payload_stats_tm_get_apogee_alt(msg);
- payload_stats_tm->min_pressure = mavlink_msg_payload_stats_tm_get_min_pressure(msg);
- payload_stats_tm->cpu_load = mavlink_msg_payload_stats_tm_get_cpu_load(msg);
- payload_stats_tm->free_heap = mavlink_msg_payload_stats_tm_get_free_heap(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN? msg->len : MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN;
- memset(payload_stats_tm, 0, MAVLINK_MSG_ID_PAYLOAD_STATS_TM_LEN);
- memcpy(payload_stats_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_pin_tm.h b/mavlink_lib/pyxis/mavlink_msg_pin_tm.h
deleted file mode 100644
index 80cc7d6547bd54d6257b5450532274f2c13126ac..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_pin_tm.h
+++ /dev/null
@@ -1,313 +0,0 @@
-#pragma once
-// MESSAGE PIN_TM PACKING
-
-#define MAVLINK_MSG_ID_PIN_TM 113
-
-
-typedef struct __mavlink_pin_tm_t {
- uint64_t timestamp; /*< [us] Timestamp*/
- uint64_t last_change_timestamp; /*< Last change timestamp of pin*/
- uint8_t pin_id; /*< A member of the PinsList enum*/
- uint8_t changes_counter; /*< Number of changes of pin*/
- uint8_t current_state; /*< Current state of pin*/
-} mavlink_pin_tm_t;
-
-#define MAVLINK_MSG_ID_PIN_TM_LEN 19
-#define MAVLINK_MSG_ID_PIN_TM_MIN_LEN 19
-#define MAVLINK_MSG_ID_113_LEN 19
-#define MAVLINK_MSG_ID_113_MIN_LEN 19
-
-#define MAVLINK_MSG_ID_PIN_TM_CRC 255
-#define MAVLINK_MSG_ID_113_CRC 255
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_PIN_TM { \
- 113, \
- "PIN_TM", \
- 5, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_pin_tm_t, timestamp) }, \
- { "pin_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_pin_tm_t, pin_id) }, \
- { "last_change_timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_pin_tm_t, last_change_timestamp) }, \
- { "changes_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_pin_tm_t, changes_counter) }, \
- { "current_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_pin_tm_t, current_state) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_PIN_TM { \
- "PIN_TM", \
- 5, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_pin_tm_t, timestamp) }, \
- { "pin_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_pin_tm_t, pin_id) }, \
- { "last_change_timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_pin_tm_t, last_change_timestamp) }, \
- { "changes_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_pin_tm_t, changes_counter) }, \
- { "current_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_pin_tm_t, current_state) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a pin_tm 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
- * @param pin_id A member of the PinsList enum
- * @param last_change_timestamp Last change timestamp of pin
- * @param changes_counter Number of changes of pin
- * @param current_state Current state of pin
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_pin_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t pin_id, uint64_t last_change_timestamp, uint8_t changes_counter, uint8_t current_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PIN_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, last_change_timestamp);
- _mav_put_uint8_t(buf, 16, pin_id);
- _mav_put_uint8_t(buf, 17, changes_counter);
- _mav_put_uint8_t(buf, 18, current_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PIN_TM_LEN);
-#else
- mavlink_pin_tm_t packet;
- packet.timestamp = timestamp;
- packet.last_change_timestamp = last_change_timestamp;
- packet.pin_id = pin_id;
- packet.changes_counter = changes_counter;
- packet.current_state = current_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PIN_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PIN_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-}
-
-/**
- * @brief Pack a pin_tm 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
- * @param pin_id A member of the PinsList enum
- * @param last_change_timestamp Last change timestamp of pin
- * @param changes_counter Number of changes of pin
- * @param current_state Current state of pin
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_pin_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t pin_id,uint64_t last_change_timestamp,uint8_t changes_counter,uint8_t current_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PIN_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, last_change_timestamp);
- _mav_put_uint8_t(buf, 16, pin_id);
- _mav_put_uint8_t(buf, 17, changes_counter);
- _mav_put_uint8_t(buf, 18, current_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PIN_TM_LEN);
-#else
- mavlink_pin_tm_t packet;
- packet.timestamp = timestamp;
- packet.last_change_timestamp = last_change_timestamp;
- packet.pin_id = pin_id;
- packet.changes_counter = changes_counter;
- packet.current_state = current_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PIN_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PIN_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-}
-
-/**
- * @brief Encode a pin_tm 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 pin_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_pin_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pin_tm_t* pin_tm)
-{
- return mavlink_msg_pin_tm_pack(system_id, component_id, msg, pin_tm->timestamp, pin_tm->pin_id, pin_tm->last_change_timestamp, pin_tm->changes_counter, pin_tm->current_state);
-}
-
-/**
- * @brief Encode a pin_tm 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 pin_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_pin_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_pin_tm_t* pin_tm)
-{
- return mavlink_msg_pin_tm_pack_chan(system_id, component_id, chan, msg, pin_tm->timestamp, pin_tm->pin_id, pin_tm->last_change_timestamp, pin_tm->changes_counter, pin_tm->current_state);
-}
-
-/**
- * @brief Send a pin_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp
- * @param pin_id A member of the PinsList enum
- * @param last_change_timestamp Last change timestamp of pin
- * @param changes_counter Number of changes of pin
- * @param current_state Current state of pin
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_pin_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t pin_id, uint64_t last_change_timestamp, uint8_t changes_counter, uint8_t current_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PIN_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, last_change_timestamp);
- _mav_put_uint8_t(buf, 16, pin_id);
- _mav_put_uint8_t(buf, 17, changes_counter);
- _mav_put_uint8_t(buf, 18, current_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PIN_TM, buf, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-#else
- mavlink_pin_tm_t packet;
- packet.timestamp = timestamp;
- packet.last_change_timestamp = last_change_timestamp;
- packet.pin_id = pin_id;
- packet.changes_counter = changes_counter;
- packet.current_state = current_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PIN_TM, (const char *)&packet, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a pin_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_pin_tm_send_struct(mavlink_channel_t chan, const mavlink_pin_tm_t* pin_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_pin_tm_send(chan, pin_tm->timestamp, pin_tm->pin_id, pin_tm->last_change_timestamp, pin_tm->changes_counter, pin_tm->current_state);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PIN_TM, (const char *)pin_tm, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_PIN_TM_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_pin_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t pin_id, uint64_t last_change_timestamp, uint8_t changes_counter, uint8_t current_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, last_change_timestamp);
- _mav_put_uint8_t(buf, 16, pin_id);
- _mav_put_uint8_t(buf, 17, changes_counter);
- _mav_put_uint8_t(buf, 18, current_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PIN_TM, buf, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-#else
- mavlink_pin_tm_t *packet = (mavlink_pin_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->last_change_timestamp = last_change_timestamp;
- packet->pin_id = pin_id;
- packet->changes_counter = changes_counter;
- packet->current_state = current_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PIN_TM, (const char *)packet, MAVLINK_MSG_ID_PIN_TM_MIN_LEN, MAVLINK_MSG_ID_PIN_TM_LEN, MAVLINK_MSG_ID_PIN_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE PIN_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from pin_tm message
- *
- * @return [us] Timestamp
- */
-static inline uint64_t mavlink_msg_pin_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field pin_id from pin_tm message
- *
- * @return A member of the PinsList enum
- */
-static inline uint8_t mavlink_msg_pin_tm_get_pin_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 16);
-}
-
-/**
- * @brief Get field last_change_timestamp from pin_tm message
- *
- * @return Last change timestamp of pin
- */
-static inline uint64_t mavlink_msg_pin_tm_get_last_change_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 8);
-}
-
-/**
- * @brief Get field changes_counter from pin_tm message
- *
- * @return Number of changes of pin
- */
-static inline uint8_t mavlink_msg_pin_tm_get_changes_counter(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 17);
-}
-
-/**
- * @brief Get field current_state from pin_tm message
- *
- * @return Current state of pin
- */
-static inline uint8_t mavlink_msg_pin_tm_get_current_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 18);
-}
-
-/**
- * @brief Decode a pin_tm message into a struct
- *
- * @param msg The message to decode
- * @param pin_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_pin_tm_decode(const mavlink_message_t* msg, mavlink_pin_tm_t* pin_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- pin_tm->timestamp = mavlink_msg_pin_tm_get_timestamp(msg);
- pin_tm->last_change_timestamp = mavlink_msg_pin_tm_get_last_change_timestamp(msg);
- pin_tm->pin_id = mavlink_msg_pin_tm_get_pin_id(msg);
- pin_tm->changes_counter = mavlink_msg_pin_tm_get_changes_counter(msg);
- pin_tm->current_state = mavlink_msg_pin_tm_get_current_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_PIN_TM_LEN? msg->len : MAVLINK_MSG_ID_PIN_TM_LEN;
- memset(pin_tm, 0, MAVLINK_MSG_ID_PIN_TM_LEN);
- memcpy(pin_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_ping_tc.h b/mavlink_lib/pyxis/mavlink_msg_ping_tc.h
deleted file mode 100644
index 99a2895f9933675f201a98a080067ebf3b33bb66..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_ping_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE PING_TC PACKING
-
-#define MAVLINK_MSG_ID_PING_TC 1
-
-
-typedef struct __mavlink_ping_tc_t {
- uint64_t timestamp; /*< Timestamp to identify when it was sent*/
-} mavlink_ping_tc_t;
-
-#define MAVLINK_MSG_ID_PING_TC_LEN 8
-#define MAVLINK_MSG_ID_PING_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_1_LEN 8
-#define MAVLINK_MSG_ID_1_MIN_LEN 8
-
-#define MAVLINK_MSG_ID_PING_TC_CRC 136
-#define MAVLINK_MSG_ID_1_CRC 136
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_PING_TC { \
- 1, \
- "PING_TC", \
- 1, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_tc_t, timestamp) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_PING_TC { \
- "PING_TC", \
- 1, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_tc_t, timestamp) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ping_tc 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 Timestamp to identify when it was sent
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ping_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_TC_LEN);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PING_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-}
-
-/**
- * @brief Pack a ping_tc 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 Timestamp to identify when it was sent
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ping_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_TC_LEN);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PING_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-}
-
-/**
- * @brief Encode a ping_tc 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_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ping_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_tc_t* ping_tc)
-{
- return mavlink_msg_ping_tc_pack(system_id, component_id, msg, ping_tc->timestamp);
-}
-
-/**
- * @brief Encode a ping_tc 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_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ping_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ping_tc_t* ping_tc)
-{
- return mavlink_msg_ping_tc_pack_chan(system_id, component_id, chan, msg, ping_tc->timestamp);
-}
-
-/**
- * @brief Send a ping_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp Timestamp to identify when it was sent
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ping_tc_send(mavlink_channel_t chan, uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, buf, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)&packet, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a ping_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ping_tc_send_struct(mavlink_channel_t chan, const mavlink_ping_tc_t* ping_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ping_tc_send(chan, ping_tc->timestamp);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)ping_tc, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_PING_TC_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_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, buf, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#else
- mavlink_ping_tc_t *packet = (mavlink_ping_tc_t *)msgbuf;
- packet->timestamp = timestamp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)packet, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE PING_TC UNPACKING
-
-
-/**
- * @brief Get field timestamp from ping_tc message
- *
- * @return Timestamp to identify when it was sent
- */
-static inline uint64_t mavlink_msg_ping_tc_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Decode a ping_tc message into a struct
- *
- * @param msg The message to decode
- * @param ping_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ping_tc_decode(const mavlink_message_t* msg, mavlink_ping_tc_t* ping_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ping_tc->timestamp = mavlink_msg_ping_tc_get_timestamp(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_PING_TC_LEN? msg->len : MAVLINK_MSG_ID_PING_TC_LEN;
- memset(ping_tc, 0, MAVLINK_MSG_ID_PING_TC_LEN);
- memcpy(ping_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_pressure_tm.h b/mavlink_lib/pyxis/mavlink_msg_pressure_tm.h
deleted file mode 100644
index 0c5f1ba586b00b6f1511d55ec730e1dd17f21a5c..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_pressure_tm.h
+++ /dev/null
@@ -1,255 +0,0 @@
-#pragma once
-// MESSAGE PRESSURE_TM PACKING
-
-#define MAVLINK_MSG_ID_PRESSURE_TM 104
-
-
-typedef struct __mavlink_pressure_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float pressure; /*< [Pa] Pressure of the digital barometer*/
- char sensor_id[20]; /*< Sensor name*/
-} mavlink_pressure_tm_t;
-
-#define MAVLINK_MSG_ID_PRESSURE_TM_LEN 32
-#define MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_104_LEN 32
-#define MAVLINK_MSG_ID_104_MIN_LEN 32
-
-#define MAVLINK_MSG_ID_PRESSURE_TM_CRC 239
-#define MAVLINK_MSG_ID_104_CRC 239
-
-#define MAVLINK_MSG_PRESSURE_TM_FIELD_SENSOR_ID_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_PRESSURE_TM { \
- 104, \
- "PRESSURE_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_pressure_tm_t, timestamp) }, \
- { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_pressure_tm_t, sensor_id) }, \
- { "pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_pressure_tm_t, pressure) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_PRESSURE_TM { \
- "PRESSURE_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_pressure_tm_t, timestamp) }, \
- { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_pressure_tm_t, sensor_id) }, \
- { "pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_pressure_tm_t, pressure) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a pressure_tm 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] When was this logged
- * @param sensor_id Sensor name
- * @param pressure [Pa] Pressure of the digital barometer
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_pressure_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_id, float pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PRESSURE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure);
- _mav_put_char_array(buf, 12, sensor_id, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PRESSURE_TM_LEN);
-#else
- mavlink_pressure_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure = pressure;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PRESSURE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PRESSURE_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-}
-
-/**
- * @brief Pack a pressure_tm 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] When was this logged
- * @param sensor_id Sensor name
- * @param pressure [Pa] Pressure of the digital barometer
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_pressure_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_id,float pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PRESSURE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure);
- _mav_put_char_array(buf, 12, sensor_id, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PRESSURE_TM_LEN);
-#else
- mavlink_pressure_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure = pressure;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PRESSURE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PRESSURE_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-}
-
-/**
- * @brief Encode a pressure_tm 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 pressure_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_pressure_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pressure_tm_t* pressure_tm)
-{
- return mavlink_msg_pressure_tm_pack(system_id, component_id, msg, pressure_tm->timestamp, pressure_tm->sensor_id, pressure_tm->pressure);
-}
-
-/**
- * @brief Encode a pressure_tm 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 pressure_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_pressure_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_pressure_tm_t* pressure_tm)
-{
- return mavlink_msg_pressure_tm_pack_chan(system_id, component_id, chan, msg, pressure_tm->timestamp, pressure_tm->sensor_id, pressure_tm->pressure);
-}
-
-/**
- * @brief Send a pressure_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_id Sensor name
- * @param pressure [Pa] Pressure of the digital barometer
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_pressure_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_id, float pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PRESSURE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure);
- _mav_put_char_array(buf, 12, sensor_id, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PRESSURE_TM, buf, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-#else
- mavlink_pressure_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure = pressure;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PRESSURE_TM, (const char *)&packet, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a pressure_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_pressure_tm_send_struct(mavlink_channel_t chan, const mavlink_pressure_tm_t* pressure_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_pressure_tm_send(chan, pressure_tm->timestamp, pressure_tm->sensor_id, pressure_tm->pressure);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PRESSURE_TM, (const char *)pressure_tm, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_PRESSURE_TM_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_pressure_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_id, float pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure);
- _mav_put_char_array(buf, 12, sensor_id, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PRESSURE_TM, buf, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-#else
- mavlink_pressure_tm_t *packet = (mavlink_pressure_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->pressure = pressure;
- mav_array_memcpy(packet->sensor_id, sensor_id, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PRESSURE_TM, (const char *)packet, MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN, MAVLINK_MSG_ID_PRESSURE_TM_LEN, MAVLINK_MSG_ID_PRESSURE_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE PRESSURE_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from pressure_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_pressure_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_id from pressure_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_pressure_tm_get_sensor_id(const mavlink_message_t* msg, char *sensor_id)
-{
- return _MAV_RETURN_char_array(msg, sensor_id, 20, 12);
-}
-
-/**
- * @brief Get field pressure from pressure_tm message
- *
- * @return [Pa] Pressure of the digital barometer
- */
-static inline float mavlink_msg_pressure_tm_get_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Decode a pressure_tm message into a struct
- *
- * @param msg The message to decode
- * @param pressure_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_pressure_tm_decode(const mavlink_message_t* msg, mavlink_pressure_tm_t* pressure_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- pressure_tm->timestamp = mavlink_msg_pressure_tm_get_timestamp(msg);
- pressure_tm->pressure = mavlink_msg_pressure_tm_get_pressure(msg);
- mavlink_msg_pressure_tm_get_sensor_id(msg, pressure_tm->sensor_id);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_PRESSURE_TM_LEN? msg->len : MAVLINK_MSG_ID_PRESSURE_TM_LEN;
- memset(pressure_tm, 0, MAVLINK_MSG_ID_PRESSURE_TM_LEN);
- memcpy(pressure_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_raw_event_tc.h b/mavlink_lib/pyxis/mavlink_msg_raw_event_tc.h
deleted file mode 100644
index fe6d60a1b38e429fc0f0049aa21234613d3c8e99..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_raw_event_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE RAW_EVENT_TC PACKING
-
-#define MAVLINK_MSG_ID_RAW_EVENT_TC 13
-
-
-typedef struct __mavlink_raw_event_tc_t {
- uint8_t topic_id; /*< Id of the topic to which the event should be posted*/
- uint8_t event_id; /*< Id of the event to be posted*/
-} mavlink_raw_event_tc_t;
-
-#define MAVLINK_MSG_ID_RAW_EVENT_TC_LEN 2
-#define MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN 2
-#define MAVLINK_MSG_ID_13_LEN 2
-#define MAVLINK_MSG_ID_13_MIN_LEN 2
-
-#define MAVLINK_MSG_ID_RAW_EVENT_TC_CRC 218
-#define MAVLINK_MSG_ID_13_CRC 218
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_RAW_EVENT_TC { \
- 13, \
- "RAW_EVENT_TC", \
- 2, \
- { { "topic_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_raw_event_tc_t, topic_id) }, \
- { "event_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_raw_event_tc_t, event_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_RAW_EVENT_TC { \
- "RAW_EVENT_TC", \
- 2, \
- { { "topic_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_raw_event_tc_t, topic_id) }, \
- { "event_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_raw_event_tc_t, event_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a raw_event_tc 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 topic_id Id of the topic to which the event should be posted
- * @param event_id Id of the event to be posted
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_raw_event_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t topic_id, uint8_t event_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_EVENT_TC_LEN];
- _mav_put_uint8_t(buf, 0, topic_id);
- _mav_put_uint8_t(buf, 1, event_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#else
- mavlink_raw_event_tc_t packet;
- packet.topic_id = topic_id;
- packet.event_id = event_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RAW_EVENT_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-}
-
-/**
- * @brief Pack a raw_event_tc 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 topic_id Id of the topic to which the event should be posted
- * @param event_id Id of the event to be posted
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_raw_event_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t topic_id,uint8_t event_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_EVENT_TC_LEN];
- _mav_put_uint8_t(buf, 0, topic_id);
- _mav_put_uint8_t(buf, 1, event_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#else
- mavlink_raw_event_tc_t packet;
- packet.topic_id = topic_id;
- packet.event_id = event_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RAW_EVENT_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-}
-
-/**
- * @brief Encode a raw_event_tc 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_event_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_raw_event_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_event_tc_t* raw_event_tc)
-{
- return mavlink_msg_raw_event_tc_pack(system_id, component_id, msg, raw_event_tc->topic_id, raw_event_tc->event_id);
-}
-
-/**
- * @brief Encode a raw_event_tc 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_event_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_raw_event_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_event_tc_t* raw_event_tc)
-{
- return mavlink_msg_raw_event_tc_pack_chan(system_id, component_id, chan, msg, raw_event_tc->topic_id, raw_event_tc->event_id);
-}
-
-/**
- * @brief Send a raw_event_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param topic_id Id of the topic to which the event should be posted
- * @param event_id Id of the event to be posted
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_raw_event_tc_send(mavlink_channel_t chan, uint8_t topic_id, uint8_t event_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_EVENT_TC_LEN];
- _mav_put_uint8_t(buf, 0, topic_id);
- _mav_put_uint8_t(buf, 1, event_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, buf, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#else
- mavlink_raw_event_tc_t packet;
- packet.topic_id = topic_id;
- packet.event_id = event_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, (const char *)&packet, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a raw_event_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_raw_event_tc_send_struct(mavlink_channel_t chan, const mavlink_raw_event_tc_t* raw_event_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_raw_event_tc_send(chan, raw_event_tc->topic_id, raw_event_tc->event_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, (const char *)raw_event_tc, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_RAW_EVENT_TC_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_event_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t topic_id, uint8_t event_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, topic_id);
- _mav_put_uint8_t(buf, 1, event_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, buf, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#else
- mavlink_raw_event_tc_t *packet = (mavlink_raw_event_tc_t *)msgbuf;
- packet->topic_id = topic_id;
- packet->event_id = event_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, (const char *)packet, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE RAW_EVENT_TC UNPACKING
-
-
-/**
- * @brief Get field topic_id from raw_event_tc message
- *
- * @return Id of the topic to which the event should be posted
- */
-static inline uint8_t mavlink_msg_raw_event_tc_get_topic_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field event_id from raw_event_tc message
- *
- * @return Id of the event to be posted
- */
-static inline uint8_t mavlink_msg_raw_event_tc_get_event_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Decode a raw_event_tc message into a struct
- *
- * @param msg The message to decode
- * @param raw_event_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_raw_event_tc_decode(const mavlink_message_t* msg, mavlink_raw_event_tc_t* raw_event_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- raw_event_tc->topic_id = mavlink_msg_raw_event_tc_get_topic_id(msg);
- raw_event_tc->event_id = mavlink_msg_raw_event_tc_get_event_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_RAW_EVENT_TC_LEN? msg->len : MAVLINK_MSG_ID_RAW_EVENT_TC_LEN;
- memset(raw_event_tc, 0, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
- memcpy(raw_event_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_receiver_tm.h b/mavlink_lib/pyxis/mavlink_msg_receiver_tm.h
deleted file mode 100644
index 2b222434d12522999e051c41d2d1a32931f9ee9f..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_receiver_tm.h
+++ /dev/null
@@ -1,313 +0,0 @@
-#pragma once
-// MESSAGE RECEIVER_TM PACKING
-
-#define MAVLINK_MSG_ID_RECEIVER_TM 150
-
-
-typedef struct __mavlink_receiver_tm_t {
- uint64_t timestamp; /*< [us] Timestamp*/
- uint64_t rx_bitrate; /*< [kb/s] Rx bitrate*/
- uint64_t tx_bitrate; /*< [kb/s] Tx bitrate*/
- float rssi; /*< [dBm] Rssi*/
- float fei; /*< [Hz] Fei*/
-} mavlink_receiver_tm_t;
-
-#define MAVLINK_MSG_ID_RECEIVER_TM_LEN 32
-#define MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_150_LEN 32
-#define MAVLINK_MSG_ID_150_MIN_LEN 32
-
-#define MAVLINK_MSG_ID_RECEIVER_TM_CRC 109
-#define MAVLINK_MSG_ID_150_CRC 109
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_RECEIVER_TM { \
- 150, \
- "RECEIVER_TM", \
- 5, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_receiver_tm_t, timestamp) }, \
- { "rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_receiver_tm_t, rssi) }, \
- { "fei", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_receiver_tm_t, fei) }, \
- { "rx_bitrate", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_receiver_tm_t, rx_bitrate) }, \
- { "tx_bitrate", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_receiver_tm_t, tx_bitrate) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_RECEIVER_TM { \
- "RECEIVER_TM", \
- 5, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_receiver_tm_t, timestamp) }, \
- { "rssi", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_receiver_tm_t, rssi) }, \
- { "fei", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_receiver_tm_t, fei) }, \
- { "rx_bitrate", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_receiver_tm_t, rx_bitrate) }, \
- { "tx_bitrate", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_receiver_tm_t, tx_bitrate) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a receiver_tm 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
- * @param rssi [dBm] Rssi
- * @param fei [Hz] Fei
- * @param rx_bitrate [kb/s] Rx bitrate
- * @param tx_bitrate [kb/s] Tx bitrate
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_receiver_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, float rssi, float fei, uint64_t rx_bitrate, uint64_t tx_bitrate)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RECEIVER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, rx_bitrate);
- _mav_put_uint64_t(buf, 16, tx_bitrate);
- _mav_put_float(buf, 24, rssi);
- _mav_put_float(buf, 28, fei);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
-#else
- mavlink_receiver_tm_t packet;
- packet.timestamp = timestamp;
- packet.rx_bitrate = rx_bitrate;
- packet.tx_bitrate = tx_bitrate;
- packet.rssi = rssi;
- packet.fei = fei;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RECEIVER_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-}
-
-/**
- * @brief Pack a receiver_tm 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
- * @param rssi [dBm] Rssi
- * @param fei [Hz] Fei
- * @param rx_bitrate [kb/s] Rx bitrate
- * @param tx_bitrate [kb/s] Tx bitrate
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_receiver_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,float rssi,float fei,uint64_t rx_bitrate,uint64_t tx_bitrate)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RECEIVER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, rx_bitrate);
- _mav_put_uint64_t(buf, 16, tx_bitrate);
- _mav_put_float(buf, 24, rssi);
- _mav_put_float(buf, 28, fei);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
-#else
- mavlink_receiver_tm_t packet;
- packet.timestamp = timestamp;
- packet.rx_bitrate = rx_bitrate;
- packet.tx_bitrate = tx_bitrate;
- packet.rssi = rssi;
- packet.fei = fei;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RECEIVER_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-}
-
-/**
- * @brief Encode a receiver_tm 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 receiver_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_receiver_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_receiver_tm_t* receiver_tm)
-{
- return mavlink_msg_receiver_tm_pack(system_id, component_id, msg, receiver_tm->timestamp, receiver_tm->rssi, receiver_tm->fei, receiver_tm->rx_bitrate, receiver_tm->tx_bitrate);
-}
-
-/**
- * @brief Encode a receiver_tm 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 receiver_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_receiver_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_receiver_tm_t* receiver_tm)
-{
- return mavlink_msg_receiver_tm_pack_chan(system_id, component_id, chan, msg, receiver_tm->timestamp, receiver_tm->rssi, receiver_tm->fei, receiver_tm->rx_bitrate, receiver_tm->tx_bitrate);
-}
-
-/**
- * @brief Send a receiver_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp
- * @param rssi [dBm] Rssi
- * @param fei [Hz] Fei
- * @param rx_bitrate [kb/s] Rx bitrate
- * @param tx_bitrate [kb/s] Tx bitrate
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_receiver_tm_send(mavlink_channel_t chan, uint64_t timestamp, float rssi, float fei, uint64_t rx_bitrate, uint64_t tx_bitrate)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RECEIVER_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint64_t(buf, 8, rx_bitrate);
- _mav_put_uint64_t(buf, 16, tx_bitrate);
- _mav_put_float(buf, 24, rssi);
- _mav_put_float(buf, 28, fei);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, buf, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-#else
- mavlink_receiver_tm_t packet;
- packet.timestamp = timestamp;
- packet.rx_bitrate = rx_bitrate;
- packet.tx_bitrate = tx_bitrate;
- packet.rssi = rssi;
- packet.fei = fei;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, (const char *)&packet, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a receiver_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_receiver_tm_send_struct(mavlink_channel_t chan, const mavlink_receiver_tm_t* receiver_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_receiver_tm_send(chan, receiver_tm->timestamp, receiver_tm->rssi, receiver_tm->fei, receiver_tm->rx_bitrate, receiver_tm->tx_bitrate);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, (const char *)receiver_tm, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_RECEIVER_TM_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_receiver_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float rssi, float fei, uint64_t rx_bitrate, uint64_t tx_bitrate)
-{
-#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, rx_bitrate);
- _mav_put_uint64_t(buf, 16, tx_bitrate);
- _mav_put_float(buf, 24, rssi);
- _mav_put_float(buf, 28, fei);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, buf, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-#else
- mavlink_receiver_tm_t *packet = (mavlink_receiver_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->rx_bitrate = rx_bitrate;
- packet->tx_bitrate = tx_bitrate;
- packet->rssi = rssi;
- packet->fei = fei;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RECEIVER_TM, (const char *)packet, MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN, MAVLINK_MSG_ID_RECEIVER_TM_LEN, MAVLINK_MSG_ID_RECEIVER_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE RECEIVER_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from receiver_tm message
- *
- * @return [us] Timestamp
- */
-static inline uint64_t mavlink_msg_receiver_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field rssi from receiver_tm message
- *
- * @return [dBm] Rssi
- */
-static inline float mavlink_msg_receiver_tm_get_rssi(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field fei from receiver_tm message
- *
- * @return [Hz] Fei
- */
-static inline float mavlink_msg_receiver_tm_get_fei(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field rx_bitrate from receiver_tm message
- *
- * @return [kb/s] Rx bitrate
- */
-static inline uint64_t mavlink_msg_receiver_tm_get_rx_bitrate(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 8);
-}
-
-/**
- * @brief Get field tx_bitrate from receiver_tm message
- *
- * @return [kb/s] Tx bitrate
- */
-static inline uint64_t mavlink_msg_receiver_tm_get_tx_bitrate(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 16);
-}
-
-/**
- * @brief Decode a receiver_tm message into a struct
- *
- * @param msg The message to decode
- * @param receiver_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_receiver_tm_decode(const mavlink_message_t* msg, mavlink_receiver_tm_t* receiver_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- receiver_tm->timestamp = mavlink_msg_receiver_tm_get_timestamp(msg);
- receiver_tm->rx_bitrate = mavlink_msg_receiver_tm_get_rx_bitrate(msg);
- receiver_tm->tx_bitrate = mavlink_msg_receiver_tm_get_tx_bitrate(msg);
- receiver_tm->rssi = mavlink_msg_receiver_tm_get_rssi(msg);
- receiver_tm->fei = mavlink_msg_receiver_tm_get_fei(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_RECEIVER_TM_LEN? msg->len : MAVLINK_MSG_ID_RECEIVER_TM_LEN;
- memset(receiver_tm, 0, MAVLINK_MSG_ID_RECEIVER_TM_LEN);
- memcpy(receiver_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_reset_servo_tc.h b/mavlink_lib/pyxis/mavlink_msg_reset_servo_tc.h
deleted file mode 100644
index 3194a30241ddfb4d40efc96b727240c69f4842ac..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_reset_servo_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE RESET_SERVO_TC PACKING
-
-#define MAVLINK_MSG_ID_RESET_SERVO_TC 8
-
-
-typedef struct __mavlink_reset_servo_tc_t {
- uint8_t servo_id; /*< A member of the ServosList enum*/
-} mavlink_reset_servo_tc_t;
-
-#define MAVLINK_MSG_ID_RESET_SERVO_TC_LEN 1
-#define MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_8_LEN 1
-#define MAVLINK_MSG_ID_8_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_RESET_SERVO_TC_CRC 226
-#define MAVLINK_MSG_ID_8_CRC 226
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_RESET_SERVO_TC { \
- 8, \
- "RESET_SERVO_TC", \
- 1, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_reset_servo_tc_t, servo_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_RESET_SERVO_TC { \
- "RESET_SERVO_TC", \
- 1, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_reset_servo_tc_t, servo_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a reset_servo_tc 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 servo_id A member of the ServosList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_reset_servo_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RESET_SERVO_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN);
-#else
- mavlink_reset_servo_tc_t packet;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RESET_SERVO_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-}
-
-/**
- * @brief Pack a reset_servo_tc 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 servo_id A member of the ServosList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_reset_servo_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RESET_SERVO_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN);
-#else
- mavlink_reset_servo_tc_t packet;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RESET_SERVO_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-}
-
-/**
- * @brief Encode a reset_servo_tc 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 reset_servo_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_reset_servo_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_reset_servo_tc_t* reset_servo_tc)
-{
- return mavlink_msg_reset_servo_tc_pack(system_id, component_id, msg, reset_servo_tc->servo_id);
-}
-
-/**
- * @brief Encode a reset_servo_tc 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 reset_servo_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_reset_servo_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_reset_servo_tc_t* reset_servo_tc)
-{
- return mavlink_msg_reset_servo_tc_pack_chan(system_id, component_id, chan, msg, reset_servo_tc->servo_id);
-}
-
-/**
- * @brief Send a reset_servo_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param servo_id A member of the ServosList enum
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_reset_servo_tc_send(mavlink_channel_t chan, uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RESET_SERVO_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESET_SERVO_TC, buf, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-#else
- mavlink_reset_servo_tc_t packet;
- packet.servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESET_SERVO_TC, (const char *)&packet, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a reset_servo_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_reset_servo_tc_send_struct(mavlink_channel_t chan, const mavlink_reset_servo_tc_t* reset_servo_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_reset_servo_tc_send(chan, reset_servo_tc->servo_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESET_SERVO_TC, (const char *)reset_servo_tc, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_RESET_SERVO_TC_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_reset_servo_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESET_SERVO_TC, buf, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-#else
- mavlink_reset_servo_tc_t *packet = (mavlink_reset_servo_tc_t *)msgbuf;
- packet->servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESET_SERVO_TC, (const char *)packet, MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN, MAVLINK_MSG_ID_RESET_SERVO_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE RESET_SERVO_TC UNPACKING
-
-
-/**
- * @brief Get field servo_id from reset_servo_tc message
- *
- * @return A member of the ServosList enum
- */
-static inline uint8_t mavlink_msg_reset_servo_tc_get_servo_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a reset_servo_tc message into a struct
- *
- * @param msg The message to decode
- * @param reset_servo_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_reset_servo_tc_decode(const mavlink_message_t* msg, mavlink_reset_servo_tc_t* reset_servo_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- reset_servo_tc->servo_id = mavlink_msg_reset_servo_tc_get_servo_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_RESET_SERVO_TC_LEN? msg->len : MAVLINK_MSG_ID_RESET_SERVO_TC_LEN;
- memset(reset_servo_tc, 0, MAVLINK_MSG_ID_RESET_SERVO_TC_LEN);
- memcpy(reset_servo_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_rocket_flight_tm.h b/mavlink_lib/pyxis/mavlink_msg_rocket_flight_tm.h
deleted file mode 100644
index b390c634fd28d4059046e2efbd508cfde9899de8..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_rocket_flight_tm.h
+++ /dev/null
@@ -1,1413 +0,0 @@
-#pragma once
-// MESSAGE ROCKET_FLIGHT_TM PACKING
-
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM 207
-
-
-typedef struct __mavlink_rocket_flight_tm_t {
- uint64_t timestamp; /*< [us] Timestamp in milliseconds*/
- float pressure_ada; /*< [Pa] Atmospheric pressure estimated by ADA*/
- float pressure_digi; /*< [Pa] Pressure from digital sensor*/
- float pressure_static; /*< [Pa] Pressure from static port*/
- float pressure_dpl; /*< [Pa] Pressure from deployment vane sensor*/
- float airspeed_pitot; /*< [m/s] Pitot airspeed*/
- float altitude_agl; /*< [m] Altitude above ground level*/
- float ada_vert_speed; /*< [m/s] Vertical speed estimated by ADA*/
- float acc_x; /*< [m/s^2] Acceleration on X axis (body)*/
- float acc_y; /*< [m/s^2] Acceleration on Y axis (body)*/
- float acc_z; /*< [m/s^2] Acceleration on Z axis (body)*/
- float gyro_x; /*< [rad/s] Angular speed on X axis (body)*/
- float gyro_y; /*< [rad/s] Angular speed on Y axis (body)*/
- float gyro_z; /*< [rad/s] Angular speed on Z axis (body)*/
- float mag_x; /*< [uT] Magnetic field on X axis (body)*/
- float mag_y; /*< [uT] Magnetic field on Y axis (body)*/
- float mag_z; /*< [uT] Magnetic field on Z axis (body)*/
- float gps_lat; /*< [deg] Latitude*/
- float gps_lon; /*< [deg] Longitude*/
- float gps_alt; /*< [m] GPS Altitude*/
- float abk_angle; /*< [deg] Air Brakes angle*/
- float abk_estimated_cd; /*< Estimated drag coefficient*/
- float parachute_load; /*< Parachute load cell value*/
- float nas_n; /*< [deg] Navigation system estimated noth position*/
- float nas_e; /*< [deg] Navigation system estimated east position*/
- float nas_d; /*< [m] Navigation system estimated down position*/
- float nas_vn; /*< [m/s] Navigation system estimated north velocity*/
- float nas_ve; /*< [m/s] Navigation system estimated east velocity*/
- float nas_vd; /*< [m/s] Navigation system estimated down velocity*/
- float nas_qx; /*< [deg] Navigation system estimated attitude (qx)*/
- float nas_qy; /*< [deg] Navigation system estimated attitude (qy)*/
- float nas_qz; /*< [deg] Navigation system estimated attitude (qz)*/
- float nas_qw; /*< [deg] Navigation system estimated attitude (qw)*/
- float nas_bias_x; /*< Navigation system gyroscope bias on x axis*/
- float nas_bias_y; /*< Navigation system gyroscope bias on x axis*/
- float nas_bias_z; /*< Navigation system gyroscope bias on x axis*/
- float vbat; /*< [V] Battery voltage*/
- float temperature; /*< [degC] Temperature*/
- uint8_t ada_state; /*< ADA Controller State*/
- uint8_t fmm_state; /*< Flight Mode Manager State*/
- uint8_t dpl_state; /*< Deployment Controller State*/
- uint8_t abk_state; /*< Airbrake FSM state*/
- uint8_t nas_state; /*< Navigation System FSM State*/
- uint8_t gps_fix; /*< GPS fix (1 = fix, 0 = no fix)*/
- uint8_t pin_launch; /*< Launch pin status (1 = connected, 0 = disconnected)*/
- uint8_t pin_nosecone; /*< Nosecone pin status (1 = connected, 0 = disconnected)*/
- uint8_t pin_expulsion; /*< Servo sensor status (1 = actuated, 0 = idle)*/
- uint8_t cutter_presence; /*< Cutter presence status (1 = present, 0 = missing)*/
- int8_t logger_error; /*< Logger error (0 = no error, -1 otherwise)*/
-} mavlink_rocket_flight_tm_t;
-
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN 167
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN 167
-#define MAVLINK_MSG_ID_207_LEN 167
-#define MAVLINK_MSG_ID_207_MIN_LEN 167
-
-#define MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC 184
-#define MAVLINK_MSG_ID_207_CRC 184
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM { \
- 207, \
- "ROCKET_FLIGHT_TM", \
- 49, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_flight_tm_t, timestamp) }, \
- { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_rocket_flight_tm_t, ada_state) }, \
- { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_rocket_flight_tm_t, fmm_state) }, \
- { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_rocket_flight_tm_t, dpl_state) }, \
- { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_rocket_flight_tm_t, abk_state) }, \
- { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_rocket_flight_tm_t, nas_state) }, \
- { "pressure_ada", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_rocket_flight_tm_t, pressure_ada) }, \
- { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_rocket_flight_tm_t, pressure_digi) }, \
- { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_rocket_flight_tm_t, pressure_static) }, \
- { "pressure_dpl", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_rocket_flight_tm_t, pressure_dpl) }, \
- { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_rocket_flight_tm_t, airspeed_pitot) }, \
- { "altitude_agl", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_rocket_flight_tm_t, altitude_agl) }, \
- { "ada_vert_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_rocket_flight_tm_t, ada_vert_speed) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_rocket_flight_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_rocket_flight_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_rocket_flight_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_rocket_flight_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_rocket_flight_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_rocket_flight_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_rocket_flight_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_flight_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_flight_tm_t, mag_z) }, \
- { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_rocket_flight_tm_t, gps_fix) }, \
- { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_flight_tm_t, gps_lat) }, \
- { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_flight_tm_t, gps_lon) }, \
- { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_flight_tm_t, gps_alt) }, \
- { "abk_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_flight_tm_t, abk_angle) }, \
- { "abk_estimated_cd", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_rocket_flight_tm_t, abk_estimated_cd) }, \
- { "parachute_load", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_rocket_flight_tm_t, parachute_load) }, \
- { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_rocket_flight_tm_t, nas_n) }, \
- { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_rocket_flight_tm_t, nas_e) }, \
- { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_rocket_flight_tm_t, nas_d) }, \
- { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_rocket_flight_tm_t, nas_vn) }, \
- { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_rocket_flight_tm_t, nas_ve) }, \
- { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_rocket_flight_tm_t, nas_vd) }, \
- { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_rocket_flight_tm_t, nas_qx) }, \
- { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_rocket_flight_tm_t, nas_qy) }, \
- { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_rocket_flight_tm_t, nas_qz) }, \
- { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_rocket_flight_tm_t, nas_qw) }, \
- { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_rocket_flight_tm_t, nas_bias_x) }, \
- { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_rocket_flight_tm_t, nas_bias_y) }, \
- { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_rocket_flight_tm_t, nas_bias_z) }, \
- { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 162, offsetof(mavlink_rocket_flight_tm_t, pin_launch) }, \
- { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 163, offsetof(mavlink_rocket_flight_tm_t, pin_nosecone) }, \
- { "pin_expulsion", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_rocket_flight_tm_t, pin_expulsion) }, \
- { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_rocket_flight_tm_t, cutter_presence) }, \
- { "vbat", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, vbat) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \
- { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 166, offsetof(mavlink_rocket_flight_tm_t, logger_error) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM { \
- "ROCKET_FLIGHT_TM", \
- 49, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_flight_tm_t, timestamp) }, \
- { "ada_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_rocket_flight_tm_t, ada_state) }, \
- { "fmm_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_rocket_flight_tm_t, fmm_state) }, \
- { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 158, offsetof(mavlink_rocket_flight_tm_t, dpl_state) }, \
- { "abk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 159, offsetof(mavlink_rocket_flight_tm_t, abk_state) }, \
- { "nas_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 160, offsetof(mavlink_rocket_flight_tm_t, nas_state) }, \
- { "pressure_ada", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_rocket_flight_tm_t, pressure_ada) }, \
- { "pressure_digi", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_rocket_flight_tm_t, pressure_digi) }, \
- { "pressure_static", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_rocket_flight_tm_t, pressure_static) }, \
- { "pressure_dpl", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_rocket_flight_tm_t, pressure_dpl) }, \
- { "airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_rocket_flight_tm_t, airspeed_pitot) }, \
- { "altitude_agl", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_rocket_flight_tm_t, altitude_agl) }, \
- { "ada_vert_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_rocket_flight_tm_t, ada_vert_speed) }, \
- { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_rocket_flight_tm_t, acc_x) }, \
- { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_rocket_flight_tm_t, acc_y) }, \
- { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_rocket_flight_tm_t, acc_z) }, \
- { "gyro_x", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_rocket_flight_tm_t, gyro_x) }, \
- { "gyro_y", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_rocket_flight_tm_t, gyro_y) }, \
- { "gyro_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_rocket_flight_tm_t, gyro_z) }, \
- { "mag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_rocket_flight_tm_t, mag_x) }, \
- { "mag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_flight_tm_t, mag_y) }, \
- { "mag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_flight_tm_t, mag_z) }, \
- { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 161, offsetof(mavlink_rocket_flight_tm_t, gps_fix) }, \
- { "gps_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_flight_tm_t, gps_lat) }, \
- { "gps_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_flight_tm_t, gps_lon) }, \
- { "gps_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_flight_tm_t, gps_alt) }, \
- { "abk_angle", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_flight_tm_t, abk_angle) }, \
- { "abk_estimated_cd", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_rocket_flight_tm_t, abk_estimated_cd) }, \
- { "parachute_load", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_rocket_flight_tm_t, parachute_load) }, \
- { "nas_n", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_rocket_flight_tm_t, nas_n) }, \
- { "nas_e", NULL, MAVLINK_TYPE_FLOAT, 0, 100, offsetof(mavlink_rocket_flight_tm_t, nas_e) }, \
- { "nas_d", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_rocket_flight_tm_t, nas_d) }, \
- { "nas_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 108, offsetof(mavlink_rocket_flight_tm_t, nas_vn) }, \
- { "nas_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 112, offsetof(mavlink_rocket_flight_tm_t, nas_ve) }, \
- { "nas_vd", NULL, MAVLINK_TYPE_FLOAT, 0, 116, offsetof(mavlink_rocket_flight_tm_t, nas_vd) }, \
- { "nas_qx", NULL, MAVLINK_TYPE_FLOAT, 0, 120, offsetof(mavlink_rocket_flight_tm_t, nas_qx) }, \
- { "nas_qy", NULL, MAVLINK_TYPE_FLOAT, 0, 124, offsetof(mavlink_rocket_flight_tm_t, nas_qy) }, \
- { "nas_qz", NULL, MAVLINK_TYPE_FLOAT, 0, 128, offsetof(mavlink_rocket_flight_tm_t, nas_qz) }, \
- { "nas_qw", NULL, MAVLINK_TYPE_FLOAT, 0, 132, offsetof(mavlink_rocket_flight_tm_t, nas_qw) }, \
- { "nas_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 136, offsetof(mavlink_rocket_flight_tm_t, nas_bias_x) }, \
- { "nas_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 140, offsetof(mavlink_rocket_flight_tm_t, nas_bias_y) }, \
- { "nas_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 144, offsetof(mavlink_rocket_flight_tm_t, nas_bias_z) }, \
- { "pin_launch", NULL, MAVLINK_TYPE_UINT8_T, 0, 162, offsetof(mavlink_rocket_flight_tm_t, pin_launch) }, \
- { "pin_nosecone", NULL, MAVLINK_TYPE_UINT8_T, 0, 163, offsetof(mavlink_rocket_flight_tm_t, pin_nosecone) }, \
- { "pin_expulsion", NULL, MAVLINK_TYPE_UINT8_T, 0, 164, offsetof(mavlink_rocket_flight_tm_t, pin_expulsion) }, \
- { "cutter_presence", NULL, MAVLINK_TYPE_UINT8_T, 0, 165, offsetof(mavlink_rocket_flight_tm_t, cutter_presence) }, \
- { "vbat", NULL, MAVLINK_TYPE_FLOAT, 0, 148, offsetof(mavlink_rocket_flight_tm_t, vbat) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 152, offsetof(mavlink_rocket_flight_tm_t, temperature) }, \
- { "logger_error", NULL, MAVLINK_TYPE_INT8_T, 0, 166, offsetof(mavlink_rocket_flight_tm_t, logger_error) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a rocket_flight_tm 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 in milliseconds
- * @param ada_state ADA Controller State
- * @param fmm_state Flight Mode Manager State
- * @param dpl_state Deployment Controller State
- * @param abk_state Airbrake FSM state
- * @param nas_state Navigation System FSM State
- * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane sensor
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param altitude_agl [m] Altitude above ground level
- * @param ada_vert_speed [m/s] Vertical speed estimated by ADA
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param abk_angle [deg] Air Brakes angle
- * @param abk_estimated_cd Estimated drag coefficient
- * @param parachute_load Parachute load cell value
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on x axis
- * @param nas_bias_z Navigation system gyroscope bias on x axis
- * @param pin_launch Launch pin status (1 = connected, 0 = disconnected)
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param pin_expulsion Servo sensor status (1 = actuated, 0 = idle)
- * @param cutter_presence Cutter presence status (1 = present, 0 = missing)
- * @param vbat [V] Battery voltage
- * @param temperature [degC] Temperature
- * @param logger_error Logger error (0 = no error, -1 otherwise)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float abk_estimated_cd, float parachute_load, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float vbat, float temperature, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_ada);
- _mav_put_float(buf, 12, pressure_digi);
- _mav_put_float(buf, 16, pressure_static);
- _mav_put_float(buf, 20, pressure_dpl);
- _mav_put_float(buf, 24, airspeed_pitot);
- _mav_put_float(buf, 28, altitude_agl);
- _mav_put_float(buf, 32, ada_vert_speed);
- _mav_put_float(buf, 36, acc_x);
- _mav_put_float(buf, 40, acc_y);
- _mav_put_float(buf, 44, acc_z);
- _mav_put_float(buf, 48, gyro_x);
- _mav_put_float(buf, 52, gyro_y);
- _mav_put_float(buf, 56, gyro_z);
- _mav_put_float(buf, 60, mag_x);
- _mav_put_float(buf, 64, mag_y);
- _mav_put_float(buf, 68, mag_z);
- _mav_put_float(buf, 72, gps_lat);
- _mav_put_float(buf, 76, gps_lon);
- _mav_put_float(buf, 80, gps_alt);
- _mav_put_float(buf, 84, abk_angle);
- _mav_put_float(buf, 88, abk_estimated_cd);
- _mav_put_float(buf, 92, parachute_load);
- _mav_put_float(buf, 96, nas_n);
- _mav_put_float(buf, 100, nas_e);
- _mav_put_float(buf, 104, nas_d);
- _mav_put_float(buf, 108, nas_vn);
- _mav_put_float(buf, 112, nas_ve);
- _mav_put_float(buf, 116, nas_vd);
- _mav_put_float(buf, 120, nas_qx);
- _mav_put_float(buf, 124, nas_qy);
- _mav_put_float(buf, 128, nas_qz);
- _mav_put_float(buf, 132, nas_qw);
- _mav_put_float(buf, 136, nas_bias_x);
- _mav_put_float(buf, 140, nas_bias_y);
- _mav_put_float(buf, 144, nas_bias_z);
- _mav_put_float(buf, 148, vbat);
- _mav_put_float(buf, 152, temperature);
- _mav_put_uint8_t(buf, 156, ada_state);
- _mav_put_uint8_t(buf, 157, fmm_state);
- _mav_put_uint8_t(buf, 158, dpl_state);
- _mav_put_uint8_t(buf, 159, abk_state);
- _mav_put_uint8_t(buf, 160, nas_state);
- _mav_put_uint8_t(buf, 161, gps_fix);
- _mav_put_uint8_t(buf, 162, pin_launch);
- _mav_put_uint8_t(buf, 163, pin_nosecone);
- _mav_put_uint8_t(buf, 164, pin_expulsion);
- _mav_put_uint8_t(buf, 165, cutter_presence);
- _mav_put_int8_t(buf, 166, logger_error);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
-#else
- mavlink_rocket_flight_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_ada = pressure_ada;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.pressure_dpl = pressure_dpl;
- packet.airspeed_pitot = airspeed_pitot;
- packet.altitude_agl = altitude_agl;
- packet.ada_vert_speed = ada_vert_speed;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.abk_angle = abk_angle;
- packet.abk_estimated_cd = abk_estimated_cd;
- packet.parachute_load = parachute_load;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.vbat = vbat;
- packet.temperature = temperature;
- packet.ada_state = ada_state;
- packet.fmm_state = fmm_state;
- packet.dpl_state = dpl_state;
- packet.abk_state = abk_state;
- packet.nas_state = nas_state;
- packet.gps_fix = gps_fix;
- packet.pin_launch = pin_launch;
- packet.pin_nosecone = pin_nosecone;
- packet.pin_expulsion = pin_expulsion;
- packet.cutter_presence = cutter_presence;
- packet.logger_error = logger_error;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ROCKET_FLIGHT_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-}
-
-/**
- * @brief Pack a rocket_flight_tm 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 in milliseconds
- * @param ada_state ADA Controller State
- * @param fmm_state Flight Mode Manager State
- * @param dpl_state Deployment Controller State
- * @param abk_state Airbrake FSM state
- * @param nas_state Navigation System FSM State
- * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane sensor
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param altitude_agl [m] Altitude above ground level
- * @param ada_vert_speed [m/s] Vertical speed estimated by ADA
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param abk_angle [deg] Air Brakes angle
- * @param abk_estimated_cd Estimated drag coefficient
- * @param parachute_load Parachute load cell value
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on x axis
- * @param nas_bias_z Navigation system gyroscope bias on x axis
- * @param pin_launch Launch pin status (1 = connected, 0 = disconnected)
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param pin_expulsion Servo sensor status (1 = actuated, 0 = idle)
- * @param cutter_presence Cutter presence status (1 = present, 0 = missing)
- * @param vbat [V] Battery voltage
- * @param temperature [degC] Temperature
- * @param logger_error Logger error (0 = no error, -1 otherwise)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_rocket_flight_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t ada_state,uint8_t fmm_state,uint8_t dpl_state,uint8_t abk_state,uint8_t nas_state,float pressure_ada,float pressure_digi,float pressure_static,float pressure_dpl,float airspeed_pitot,float altitude_agl,float ada_vert_speed,float acc_x,float acc_y,float acc_z,float gyro_x,float gyro_y,float gyro_z,float mag_x,float mag_y,float mag_z,uint8_t gps_fix,float gps_lat,float gps_lon,float gps_alt,float abk_angle,float abk_estimated_cd,float parachute_load,float nas_n,float nas_e,float nas_d,float nas_vn,float nas_ve,float nas_vd,float nas_qx,float nas_qy,float nas_qz,float nas_qw,float nas_bias_x,float nas_bias_y,float nas_bias_z,uint8_t pin_launch,uint8_t pin_nosecone,uint8_t pin_expulsion,uint8_t cutter_presence,float vbat,float temperature,int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_ada);
- _mav_put_float(buf, 12, pressure_digi);
- _mav_put_float(buf, 16, pressure_static);
- _mav_put_float(buf, 20, pressure_dpl);
- _mav_put_float(buf, 24, airspeed_pitot);
- _mav_put_float(buf, 28, altitude_agl);
- _mav_put_float(buf, 32, ada_vert_speed);
- _mav_put_float(buf, 36, acc_x);
- _mav_put_float(buf, 40, acc_y);
- _mav_put_float(buf, 44, acc_z);
- _mav_put_float(buf, 48, gyro_x);
- _mav_put_float(buf, 52, gyro_y);
- _mav_put_float(buf, 56, gyro_z);
- _mav_put_float(buf, 60, mag_x);
- _mav_put_float(buf, 64, mag_y);
- _mav_put_float(buf, 68, mag_z);
- _mav_put_float(buf, 72, gps_lat);
- _mav_put_float(buf, 76, gps_lon);
- _mav_put_float(buf, 80, gps_alt);
- _mav_put_float(buf, 84, abk_angle);
- _mav_put_float(buf, 88, abk_estimated_cd);
- _mav_put_float(buf, 92, parachute_load);
- _mav_put_float(buf, 96, nas_n);
- _mav_put_float(buf, 100, nas_e);
- _mav_put_float(buf, 104, nas_d);
- _mav_put_float(buf, 108, nas_vn);
- _mav_put_float(buf, 112, nas_ve);
- _mav_put_float(buf, 116, nas_vd);
- _mav_put_float(buf, 120, nas_qx);
- _mav_put_float(buf, 124, nas_qy);
- _mav_put_float(buf, 128, nas_qz);
- _mav_put_float(buf, 132, nas_qw);
- _mav_put_float(buf, 136, nas_bias_x);
- _mav_put_float(buf, 140, nas_bias_y);
- _mav_put_float(buf, 144, nas_bias_z);
- _mav_put_float(buf, 148, vbat);
- _mav_put_float(buf, 152, temperature);
- _mav_put_uint8_t(buf, 156, ada_state);
- _mav_put_uint8_t(buf, 157, fmm_state);
- _mav_put_uint8_t(buf, 158, dpl_state);
- _mav_put_uint8_t(buf, 159, abk_state);
- _mav_put_uint8_t(buf, 160, nas_state);
- _mav_put_uint8_t(buf, 161, gps_fix);
- _mav_put_uint8_t(buf, 162, pin_launch);
- _mav_put_uint8_t(buf, 163, pin_nosecone);
- _mav_put_uint8_t(buf, 164, pin_expulsion);
- _mav_put_uint8_t(buf, 165, cutter_presence);
- _mav_put_int8_t(buf, 166, logger_error);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
-#else
- mavlink_rocket_flight_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_ada = pressure_ada;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.pressure_dpl = pressure_dpl;
- packet.airspeed_pitot = airspeed_pitot;
- packet.altitude_agl = altitude_agl;
- packet.ada_vert_speed = ada_vert_speed;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.abk_angle = abk_angle;
- packet.abk_estimated_cd = abk_estimated_cd;
- packet.parachute_load = parachute_load;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.vbat = vbat;
- packet.temperature = temperature;
- packet.ada_state = ada_state;
- packet.fmm_state = fmm_state;
- packet.dpl_state = dpl_state;
- packet.abk_state = abk_state;
- packet.nas_state = nas_state;
- packet.gps_fix = gps_fix;
- packet.pin_launch = pin_launch;
- packet.pin_nosecone = pin_nosecone;
- packet.pin_expulsion = pin_expulsion;
- packet.cutter_presence = cutter_presence;
- packet.logger_error = logger_error;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ROCKET_FLIGHT_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-}
-
-/**
- * @brief Encode a rocket_flight_tm 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 rocket_flight_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_rocket_flight_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rocket_flight_tm_t* rocket_flight_tm)
-{
- return mavlink_msg_rocket_flight_tm_pack(system_id, component_id, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->abk_estimated_cd, rocket_flight_tm->parachute_load, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->vbat, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
-}
-
-/**
- * @brief Encode a rocket_flight_tm 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 rocket_flight_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_rocket_flight_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rocket_flight_tm_t* rocket_flight_tm)
-{
- return mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, chan, msg, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->abk_estimated_cd, rocket_flight_tm->parachute_load, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->vbat, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
-}
-
-/**
- * @brief Send a rocket_flight_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp in milliseconds
- * @param ada_state ADA Controller State
- * @param fmm_state Flight Mode Manager State
- * @param dpl_state Deployment Controller State
- * @param abk_state Airbrake FSM state
- * @param nas_state Navigation System FSM State
- * @param pressure_ada [Pa] Atmospheric pressure estimated by ADA
- * @param pressure_digi [Pa] Pressure from digital sensor
- * @param pressure_static [Pa] Pressure from static port
- * @param pressure_dpl [Pa] Pressure from deployment vane sensor
- * @param airspeed_pitot [m/s] Pitot airspeed
- * @param altitude_agl [m] Altitude above ground level
- * @param ada_vert_speed [m/s] Vertical speed estimated by ADA
- * @param acc_x [m/s^2] Acceleration on X axis (body)
- * @param acc_y [m/s^2] Acceleration on Y axis (body)
- * @param acc_z [m/s^2] Acceleration on Z axis (body)
- * @param gyro_x [rad/s] Angular speed on X axis (body)
- * @param gyro_y [rad/s] Angular speed on Y axis (body)
- * @param gyro_z [rad/s] Angular speed on Z axis (body)
- * @param mag_x [uT] Magnetic field on X axis (body)
- * @param mag_y [uT] Magnetic field on Y axis (body)
- * @param mag_z [uT] Magnetic field on Z axis (body)
- * @param gps_fix GPS fix (1 = fix, 0 = no fix)
- * @param gps_lat [deg] Latitude
- * @param gps_lon [deg] Longitude
- * @param gps_alt [m] GPS Altitude
- * @param abk_angle [deg] Air Brakes angle
- * @param abk_estimated_cd Estimated drag coefficient
- * @param parachute_load Parachute load cell value
- * @param nas_n [deg] Navigation system estimated noth position
- * @param nas_e [deg] Navigation system estimated east position
- * @param nas_d [m] Navigation system estimated down position
- * @param nas_vn [m/s] Navigation system estimated north velocity
- * @param nas_ve [m/s] Navigation system estimated east velocity
- * @param nas_vd [m/s] Navigation system estimated down velocity
- * @param nas_qx [deg] Navigation system estimated attitude (qx)
- * @param nas_qy [deg] Navigation system estimated attitude (qy)
- * @param nas_qz [deg] Navigation system estimated attitude (qz)
- * @param nas_qw [deg] Navigation system estimated attitude (qw)
- * @param nas_bias_x Navigation system gyroscope bias on x axis
- * @param nas_bias_y Navigation system gyroscope bias on x axis
- * @param nas_bias_z Navigation system gyroscope bias on x axis
- * @param pin_launch Launch pin status (1 = connected, 0 = disconnected)
- * @param pin_nosecone Nosecone pin status (1 = connected, 0 = disconnected)
- * @param pin_expulsion Servo sensor status (1 = actuated, 0 = idle)
- * @param cutter_presence Cutter presence status (1 = present, 0 = missing)
- * @param vbat [V] Battery voltage
- * @param temperature [degC] Temperature
- * @param logger_error Logger error (0 = no error, -1 otherwise)
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_rocket_flight_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float abk_estimated_cd, float parachute_load, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float vbat, float temperature, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_ada);
- _mav_put_float(buf, 12, pressure_digi);
- _mav_put_float(buf, 16, pressure_static);
- _mav_put_float(buf, 20, pressure_dpl);
- _mav_put_float(buf, 24, airspeed_pitot);
- _mav_put_float(buf, 28, altitude_agl);
- _mav_put_float(buf, 32, ada_vert_speed);
- _mav_put_float(buf, 36, acc_x);
- _mav_put_float(buf, 40, acc_y);
- _mav_put_float(buf, 44, acc_z);
- _mav_put_float(buf, 48, gyro_x);
- _mav_put_float(buf, 52, gyro_y);
- _mav_put_float(buf, 56, gyro_z);
- _mav_put_float(buf, 60, mag_x);
- _mav_put_float(buf, 64, mag_y);
- _mav_put_float(buf, 68, mag_z);
- _mav_put_float(buf, 72, gps_lat);
- _mav_put_float(buf, 76, gps_lon);
- _mav_put_float(buf, 80, gps_alt);
- _mav_put_float(buf, 84, abk_angle);
- _mav_put_float(buf, 88, abk_estimated_cd);
- _mav_put_float(buf, 92, parachute_load);
- _mav_put_float(buf, 96, nas_n);
- _mav_put_float(buf, 100, nas_e);
- _mav_put_float(buf, 104, nas_d);
- _mav_put_float(buf, 108, nas_vn);
- _mav_put_float(buf, 112, nas_ve);
- _mav_put_float(buf, 116, nas_vd);
- _mav_put_float(buf, 120, nas_qx);
- _mav_put_float(buf, 124, nas_qy);
- _mav_put_float(buf, 128, nas_qz);
- _mav_put_float(buf, 132, nas_qw);
- _mav_put_float(buf, 136, nas_bias_x);
- _mav_put_float(buf, 140, nas_bias_y);
- _mav_put_float(buf, 144, nas_bias_z);
- _mav_put_float(buf, 148, vbat);
- _mav_put_float(buf, 152, temperature);
- _mav_put_uint8_t(buf, 156, ada_state);
- _mav_put_uint8_t(buf, 157, fmm_state);
- _mav_put_uint8_t(buf, 158, dpl_state);
- _mav_put_uint8_t(buf, 159, abk_state);
- _mav_put_uint8_t(buf, 160, nas_state);
- _mav_put_uint8_t(buf, 161, gps_fix);
- _mav_put_uint8_t(buf, 162, pin_launch);
- _mav_put_uint8_t(buf, 163, pin_nosecone);
- _mav_put_uint8_t(buf, 164, pin_expulsion);
- _mav_put_uint8_t(buf, 165, cutter_presence);
- _mav_put_int8_t(buf, 166, logger_error);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-#else
- mavlink_rocket_flight_tm_t packet;
- packet.timestamp = timestamp;
- packet.pressure_ada = pressure_ada;
- packet.pressure_digi = pressure_digi;
- packet.pressure_static = pressure_static;
- packet.pressure_dpl = pressure_dpl;
- packet.airspeed_pitot = airspeed_pitot;
- packet.altitude_agl = altitude_agl;
- packet.ada_vert_speed = ada_vert_speed;
- packet.acc_x = acc_x;
- packet.acc_y = acc_y;
- packet.acc_z = acc_z;
- packet.gyro_x = gyro_x;
- packet.gyro_y = gyro_y;
- packet.gyro_z = gyro_z;
- packet.mag_x = mag_x;
- packet.mag_y = mag_y;
- packet.mag_z = mag_z;
- packet.gps_lat = gps_lat;
- packet.gps_lon = gps_lon;
- packet.gps_alt = gps_alt;
- packet.abk_angle = abk_angle;
- packet.abk_estimated_cd = abk_estimated_cd;
- packet.parachute_load = parachute_load;
- packet.nas_n = nas_n;
- packet.nas_e = nas_e;
- packet.nas_d = nas_d;
- packet.nas_vn = nas_vn;
- packet.nas_ve = nas_ve;
- packet.nas_vd = nas_vd;
- packet.nas_qx = nas_qx;
- packet.nas_qy = nas_qy;
- packet.nas_qz = nas_qz;
- packet.nas_qw = nas_qw;
- packet.nas_bias_x = nas_bias_x;
- packet.nas_bias_y = nas_bias_y;
- packet.nas_bias_z = nas_bias_z;
- packet.vbat = vbat;
- packet.temperature = temperature;
- packet.ada_state = ada_state;
- packet.fmm_state = fmm_state;
- packet.dpl_state = dpl_state;
- packet.abk_state = abk_state;
- packet.nas_state = nas_state;
- packet.gps_fix = gps_fix;
- packet.pin_launch = pin_launch;
- packet.pin_nosecone = pin_nosecone;
- packet.pin_expulsion = pin_expulsion;
- packet.cutter_presence = cutter_presence;
- packet.logger_error = logger_error;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, (const char *)&packet, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a rocket_flight_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_rocket_flight_tm_send_struct(mavlink_channel_t chan, const mavlink_rocket_flight_tm_t* rocket_flight_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_rocket_flight_tm_send(chan, rocket_flight_tm->timestamp, rocket_flight_tm->ada_state, rocket_flight_tm->fmm_state, rocket_flight_tm->dpl_state, rocket_flight_tm->abk_state, rocket_flight_tm->nas_state, rocket_flight_tm->pressure_ada, rocket_flight_tm->pressure_digi, rocket_flight_tm->pressure_static, rocket_flight_tm->pressure_dpl, rocket_flight_tm->airspeed_pitot, rocket_flight_tm->altitude_agl, rocket_flight_tm->ada_vert_speed, rocket_flight_tm->acc_x, rocket_flight_tm->acc_y, rocket_flight_tm->acc_z, rocket_flight_tm->gyro_x, rocket_flight_tm->gyro_y, rocket_flight_tm->gyro_z, rocket_flight_tm->mag_x, rocket_flight_tm->mag_y, rocket_flight_tm->mag_z, rocket_flight_tm->gps_fix, rocket_flight_tm->gps_lat, rocket_flight_tm->gps_lon, rocket_flight_tm->gps_alt, rocket_flight_tm->abk_angle, rocket_flight_tm->abk_estimated_cd, rocket_flight_tm->parachute_load, rocket_flight_tm->nas_n, rocket_flight_tm->nas_e, rocket_flight_tm->nas_d, rocket_flight_tm->nas_vn, rocket_flight_tm->nas_ve, rocket_flight_tm->nas_vd, rocket_flight_tm->nas_qx, rocket_flight_tm->nas_qy, rocket_flight_tm->nas_qz, rocket_flight_tm->nas_qw, rocket_flight_tm->nas_bias_x, rocket_flight_tm->nas_bias_y, rocket_flight_tm->nas_bias_z, rocket_flight_tm->pin_launch, rocket_flight_tm->pin_nosecone, rocket_flight_tm->pin_expulsion, rocket_flight_tm->cutter_presence, rocket_flight_tm->vbat, rocket_flight_tm->temperature, rocket_flight_tm->logger_error);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, (const char *)rocket_flight_tm, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_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_rocket_flight_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t ada_state, uint8_t fmm_state, uint8_t dpl_state, uint8_t abk_state, uint8_t nas_state, float pressure_ada, float pressure_digi, float pressure_static, float pressure_dpl, float airspeed_pitot, float altitude_agl, float ada_vert_speed, float acc_x, float acc_y, float acc_z, float gyro_x, float gyro_y, float gyro_z, float mag_x, float mag_y, float mag_z, uint8_t gps_fix, float gps_lat, float gps_lon, float gps_alt, float abk_angle, float abk_estimated_cd, float parachute_load, float nas_n, float nas_e, float nas_d, float nas_vn, float nas_ve, float nas_vd, float nas_qx, float nas_qy, float nas_qz, float nas_qw, float nas_bias_x, float nas_bias_y, float nas_bias_z, uint8_t pin_launch, uint8_t pin_nosecone, uint8_t pin_expulsion, uint8_t cutter_presence, float vbat, float temperature, int8_t logger_error)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, pressure_ada);
- _mav_put_float(buf, 12, pressure_digi);
- _mav_put_float(buf, 16, pressure_static);
- _mav_put_float(buf, 20, pressure_dpl);
- _mav_put_float(buf, 24, airspeed_pitot);
- _mav_put_float(buf, 28, altitude_agl);
- _mav_put_float(buf, 32, ada_vert_speed);
- _mav_put_float(buf, 36, acc_x);
- _mav_put_float(buf, 40, acc_y);
- _mav_put_float(buf, 44, acc_z);
- _mav_put_float(buf, 48, gyro_x);
- _mav_put_float(buf, 52, gyro_y);
- _mav_put_float(buf, 56, gyro_z);
- _mav_put_float(buf, 60, mag_x);
- _mav_put_float(buf, 64, mag_y);
- _mav_put_float(buf, 68, mag_z);
- _mav_put_float(buf, 72, gps_lat);
- _mav_put_float(buf, 76, gps_lon);
- _mav_put_float(buf, 80, gps_alt);
- _mav_put_float(buf, 84, abk_angle);
- _mav_put_float(buf, 88, abk_estimated_cd);
- _mav_put_float(buf, 92, parachute_load);
- _mav_put_float(buf, 96, nas_n);
- _mav_put_float(buf, 100, nas_e);
- _mav_put_float(buf, 104, nas_d);
- _mav_put_float(buf, 108, nas_vn);
- _mav_put_float(buf, 112, nas_ve);
- _mav_put_float(buf, 116, nas_vd);
- _mav_put_float(buf, 120, nas_qx);
- _mav_put_float(buf, 124, nas_qy);
- _mav_put_float(buf, 128, nas_qz);
- _mav_put_float(buf, 132, nas_qw);
- _mav_put_float(buf, 136, nas_bias_x);
- _mav_put_float(buf, 140, nas_bias_y);
- _mav_put_float(buf, 144, nas_bias_z);
- _mav_put_float(buf, 148, vbat);
- _mav_put_float(buf, 152, temperature);
- _mav_put_uint8_t(buf, 156, ada_state);
- _mav_put_uint8_t(buf, 157, fmm_state);
- _mav_put_uint8_t(buf, 158, dpl_state);
- _mav_put_uint8_t(buf, 159, abk_state);
- _mav_put_uint8_t(buf, 160, nas_state);
- _mav_put_uint8_t(buf, 161, gps_fix);
- _mav_put_uint8_t(buf, 162, pin_launch);
- _mav_put_uint8_t(buf, 163, pin_nosecone);
- _mav_put_uint8_t(buf, 164, pin_expulsion);
- _mav_put_uint8_t(buf, 165, cutter_presence);
- _mav_put_int8_t(buf, 166, logger_error);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, buf, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-#else
- mavlink_rocket_flight_tm_t *packet = (mavlink_rocket_flight_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->pressure_ada = pressure_ada;
- packet->pressure_digi = pressure_digi;
- packet->pressure_static = pressure_static;
- packet->pressure_dpl = pressure_dpl;
- packet->airspeed_pitot = airspeed_pitot;
- packet->altitude_agl = altitude_agl;
- packet->ada_vert_speed = ada_vert_speed;
- packet->acc_x = acc_x;
- packet->acc_y = acc_y;
- packet->acc_z = acc_z;
- packet->gyro_x = gyro_x;
- packet->gyro_y = gyro_y;
- packet->gyro_z = gyro_z;
- packet->mag_x = mag_x;
- packet->mag_y = mag_y;
- packet->mag_z = mag_z;
- packet->gps_lat = gps_lat;
- packet->gps_lon = gps_lon;
- packet->gps_alt = gps_alt;
- packet->abk_angle = abk_angle;
- packet->abk_estimated_cd = abk_estimated_cd;
- packet->parachute_load = parachute_load;
- packet->nas_n = nas_n;
- packet->nas_e = nas_e;
- packet->nas_d = nas_d;
- packet->nas_vn = nas_vn;
- packet->nas_ve = nas_ve;
- packet->nas_vd = nas_vd;
- packet->nas_qx = nas_qx;
- packet->nas_qy = nas_qy;
- packet->nas_qz = nas_qz;
- packet->nas_qw = nas_qw;
- packet->nas_bias_x = nas_bias_x;
- packet->nas_bias_y = nas_bias_y;
- packet->nas_bias_z = nas_bias_z;
- packet->vbat = vbat;
- packet->temperature = temperature;
- packet->ada_state = ada_state;
- packet->fmm_state = fmm_state;
- packet->dpl_state = dpl_state;
- packet->abk_state = abk_state;
- packet->nas_state = nas_state;
- packet->gps_fix = gps_fix;
- packet->pin_launch = pin_launch;
- packet->pin_nosecone = pin_nosecone;
- packet->pin_expulsion = pin_expulsion;
- packet->cutter_presence = cutter_presence;
- packet->logger_error = logger_error;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM, (const char *)packet, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ROCKET_FLIGHT_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from rocket_flight_tm message
- *
- * @return [us] Timestamp in milliseconds
- */
-static inline uint64_t mavlink_msg_rocket_flight_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field ada_state from rocket_flight_tm message
- *
- * @return ADA Controller State
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_ada_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 156);
-}
-
-/**
- * @brief Get field fmm_state from rocket_flight_tm message
- *
- * @return Flight Mode Manager State
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_fmm_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 157);
-}
-
-/**
- * @brief Get field dpl_state from rocket_flight_tm message
- *
- * @return Deployment Controller State
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_dpl_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 158);
-}
-
-/**
- * @brief Get field abk_state from rocket_flight_tm message
- *
- * @return Airbrake FSM state
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_abk_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 159);
-}
-
-/**
- * @brief Get field nas_state from rocket_flight_tm message
- *
- * @return Navigation System FSM State
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_nas_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 160);
-}
-
-/**
- * @brief Get field pressure_ada from rocket_flight_tm message
- *
- * @return [Pa] Atmospheric pressure estimated by ADA
- */
-static inline float mavlink_msg_rocket_flight_tm_get_pressure_ada(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field pressure_digi from rocket_flight_tm message
- *
- * @return [Pa] Pressure from digital sensor
- */
-static inline float mavlink_msg_rocket_flight_tm_get_pressure_digi(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field pressure_static from rocket_flight_tm message
- *
- * @return [Pa] Pressure from static port
- */
-static inline float mavlink_msg_rocket_flight_tm_get_pressure_static(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field pressure_dpl from rocket_flight_tm message
- *
- * @return [Pa] Pressure from deployment vane sensor
- */
-static inline float mavlink_msg_rocket_flight_tm_get_pressure_dpl(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field airspeed_pitot from rocket_flight_tm message
- *
- * @return [m/s] Pitot airspeed
- */
-static inline float mavlink_msg_rocket_flight_tm_get_airspeed_pitot(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field altitude_agl from rocket_flight_tm message
- *
- * @return [m] Altitude above ground level
- */
-static inline float mavlink_msg_rocket_flight_tm_get_altitude_agl(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field ada_vert_speed from rocket_flight_tm message
- *
- * @return [m/s] Vertical speed estimated by ADA
- */
-static inline float mavlink_msg_rocket_flight_tm_get_ada_vert_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field acc_x from rocket_flight_tm message
- *
- * @return [m/s^2] Acceleration on X axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_acc_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field acc_y from rocket_flight_tm message
- *
- * @return [m/s^2] Acceleration on Y axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_acc_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field acc_z from rocket_flight_tm message
- *
- * @return [m/s^2] Acceleration on Z axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_acc_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field gyro_x from rocket_flight_tm message
- *
- * @return [rad/s] Angular speed on X axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_gyro_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field gyro_y from rocket_flight_tm message
- *
- * @return [rad/s] Angular speed on Y axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_gyro_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field gyro_z from rocket_flight_tm message
- *
- * @return [rad/s] Angular speed on Z axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_gyro_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field mag_x from rocket_flight_tm message
- *
- * @return [uT] Magnetic field on X axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_mag_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field mag_y from rocket_flight_tm message
- *
- * @return [uT] Magnetic field on Y axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_mag_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field mag_z from rocket_flight_tm message
- *
- * @return [uT] Magnetic field on Z axis (body)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_mag_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field gps_fix from rocket_flight_tm message
- *
- * @return GPS fix (1 = fix, 0 = no fix)
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_gps_fix(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 161);
-}
-
-/**
- * @brief Get field gps_lat from rocket_flight_tm message
- *
- * @return [deg] Latitude
- */
-static inline float mavlink_msg_rocket_flight_tm_get_gps_lat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 72);
-}
-
-/**
- * @brief Get field gps_lon from rocket_flight_tm message
- *
- * @return [deg] Longitude
- */
-static inline float mavlink_msg_rocket_flight_tm_get_gps_lon(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 76);
-}
-
-/**
- * @brief Get field gps_alt from rocket_flight_tm message
- *
- * @return [m] GPS Altitude
- */
-static inline float mavlink_msg_rocket_flight_tm_get_gps_alt(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 80);
-}
-
-/**
- * @brief Get field abk_angle from rocket_flight_tm message
- *
- * @return [deg] Air Brakes angle
- */
-static inline float mavlink_msg_rocket_flight_tm_get_abk_angle(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 84);
-}
-
-/**
- * @brief Get field abk_estimated_cd from rocket_flight_tm message
- *
- * @return Estimated drag coefficient
- */
-static inline float mavlink_msg_rocket_flight_tm_get_abk_estimated_cd(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 88);
-}
-
-/**
- * @brief Get field parachute_load from rocket_flight_tm message
- *
- * @return Parachute load cell value
- */
-static inline float mavlink_msg_rocket_flight_tm_get_parachute_load(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 92);
-}
-
-/**
- * @brief Get field nas_n from rocket_flight_tm message
- *
- * @return [deg] Navigation system estimated noth position
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_n(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 96);
-}
-
-/**
- * @brief Get field nas_e from rocket_flight_tm message
- *
- * @return [deg] Navigation system estimated east position
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_e(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 100);
-}
-
-/**
- * @brief Get field nas_d from rocket_flight_tm message
- *
- * @return [m] Navigation system estimated down position
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_d(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 104);
-}
-
-/**
- * @brief Get field nas_vn from rocket_flight_tm message
- *
- * @return [m/s] Navigation system estimated north velocity
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_vn(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 108);
-}
-
-/**
- * @brief Get field nas_ve from rocket_flight_tm message
- *
- * @return [m/s] Navigation system estimated east velocity
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_ve(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 112);
-}
-
-/**
- * @brief Get field nas_vd from rocket_flight_tm message
- *
- * @return [m/s] Navigation system estimated down velocity
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_vd(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 116);
-}
-
-/**
- * @brief Get field nas_qx from rocket_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qx)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_qx(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 120);
-}
-
-/**
- * @brief Get field nas_qy from rocket_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qy)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_qy(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 124);
-}
-
-/**
- * @brief Get field nas_qz from rocket_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qz)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_qz(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 128);
-}
-
-/**
- * @brief Get field nas_qw from rocket_flight_tm message
- *
- * @return [deg] Navigation system estimated attitude (qw)
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_qw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 132);
-}
-
-/**
- * @brief Get field nas_bias_x from rocket_flight_tm message
- *
- * @return Navigation system gyroscope bias on x axis
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 136);
-}
-
-/**
- * @brief Get field nas_bias_y from rocket_flight_tm message
- *
- * @return Navigation system gyroscope bias on x axis
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 140);
-}
-
-/**
- * @brief Get field nas_bias_z from rocket_flight_tm message
- *
- * @return Navigation system gyroscope bias on x axis
- */
-static inline float mavlink_msg_rocket_flight_tm_get_nas_bias_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 144);
-}
-
-/**
- * @brief Get field pin_launch from rocket_flight_tm message
- *
- * @return Launch pin status (1 = connected, 0 = disconnected)
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_launch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 162);
-}
-
-/**
- * @brief Get field pin_nosecone from rocket_flight_tm message
- *
- * @return Nosecone pin status (1 = connected, 0 = disconnected)
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_nosecone(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 163);
-}
-
-/**
- * @brief Get field pin_expulsion from rocket_flight_tm message
- *
- * @return Servo sensor status (1 = actuated, 0 = idle)
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_pin_expulsion(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 164);
-}
-
-/**
- * @brief Get field cutter_presence from rocket_flight_tm message
- *
- * @return Cutter presence status (1 = present, 0 = missing)
- */
-static inline uint8_t mavlink_msg_rocket_flight_tm_get_cutter_presence(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 165);
-}
-
-/**
- * @brief Get field vbat from rocket_flight_tm message
- *
- * @return [V] Battery voltage
- */
-static inline float mavlink_msg_rocket_flight_tm_get_vbat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 148);
-}
-
-/**
- * @brief Get field temperature from rocket_flight_tm message
- *
- * @return [degC] Temperature
- */
-static inline float mavlink_msg_rocket_flight_tm_get_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 152);
-}
-
-/**
- * @brief Get field logger_error from rocket_flight_tm message
- *
- * @return Logger error (0 = no error, -1 otherwise)
- */
-static inline int8_t mavlink_msg_rocket_flight_tm_get_logger_error(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int8_t(msg, 166);
-}
-
-/**
- * @brief Decode a rocket_flight_tm message into a struct
- *
- * @param msg The message to decode
- * @param rocket_flight_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_rocket_flight_tm_decode(const mavlink_message_t* msg, mavlink_rocket_flight_tm_t* rocket_flight_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- rocket_flight_tm->timestamp = mavlink_msg_rocket_flight_tm_get_timestamp(msg);
- rocket_flight_tm->pressure_ada = mavlink_msg_rocket_flight_tm_get_pressure_ada(msg);
- rocket_flight_tm->pressure_digi = mavlink_msg_rocket_flight_tm_get_pressure_digi(msg);
- rocket_flight_tm->pressure_static = mavlink_msg_rocket_flight_tm_get_pressure_static(msg);
- rocket_flight_tm->pressure_dpl = mavlink_msg_rocket_flight_tm_get_pressure_dpl(msg);
- rocket_flight_tm->airspeed_pitot = mavlink_msg_rocket_flight_tm_get_airspeed_pitot(msg);
- rocket_flight_tm->altitude_agl = mavlink_msg_rocket_flight_tm_get_altitude_agl(msg);
- rocket_flight_tm->ada_vert_speed = mavlink_msg_rocket_flight_tm_get_ada_vert_speed(msg);
- rocket_flight_tm->acc_x = mavlink_msg_rocket_flight_tm_get_acc_x(msg);
- rocket_flight_tm->acc_y = mavlink_msg_rocket_flight_tm_get_acc_y(msg);
- rocket_flight_tm->acc_z = mavlink_msg_rocket_flight_tm_get_acc_z(msg);
- rocket_flight_tm->gyro_x = mavlink_msg_rocket_flight_tm_get_gyro_x(msg);
- rocket_flight_tm->gyro_y = mavlink_msg_rocket_flight_tm_get_gyro_y(msg);
- rocket_flight_tm->gyro_z = mavlink_msg_rocket_flight_tm_get_gyro_z(msg);
- rocket_flight_tm->mag_x = mavlink_msg_rocket_flight_tm_get_mag_x(msg);
- rocket_flight_tm->mag_y = mavlink_msg_rocket_flight_tm_get_mag_y(msg);
- rocket_flight_tm->mag_z = mavlink_msg_rocket_flight_tm_get_mag_z(msg);
- rocket_flight_tm->gps_lat = mavlink_msg_rocket_flight_tm_get_gps_lat(msg);
- rocket_flight_tm->gps_lon = mavlink_msg_rocket_flight_tm_get_gps_lon(msg);
- rocket_flight_tm->gps_alt = mavlink_msg_rocket_flight_tm_get_gps_alt(msg);
- rocket_flight_tm->abk_angle = mavlink_msg_rocket_flight_tm_get_abk_angle(msg);
- rocket_flight_tm->abk_estimated_cd = mavlink_msg_rocket_flight_tm_get_abk_estimated_cd(msg);
- rocket_flight_tm->parachute_load = mavlink_msg_rocket_flight_tm_get_parachute_load(msg);
- rocket_flight_tm->nas_n = mavlink_msg_rocket_flight_tm_get_nas_n(msg);
- rocket_flight_tm->nas_e = mavlink_msg_rocket_flight_tm_get_nas_e(msg);
- rocket_flight_tm->nas_d = mavlink_msg_rocket_flight_tm_get_nas_d(msg);
- rocket_flight_tm->nas_vn = mavlink_msg_rocket_flight_tm_get_nas_vn(msg);
- rocket_flight_tm->nas_ve = mavlink_msg_rocket_flight_tm_get_nas_ve(msg);
- rocket_flight_tm->nas_vd = mavlink_msg_rocket_flight_tm_get_nas_vd(msg);
- rocket_flight_tm->nas_qx = mavlink_msg_rocket_flight_tm_get_nas_qx(msg);
- rocket_flight_tm->nas_qy = mavlink_msg_rocket_flight_tm_get_nas_qy(msg);
- rocket_flight_tm->nas_qz = mavlink_msg_rocket_flight_tm_get_nas_qz(msg);
- rocket_flight_tm->nas_qw = mavlink_msg_rocket_flight_tm_get_nas_qw(msg);
- rocket_flight_tm->nas_bias_x = mavlink_msg_rocket_flight_tm_get_nas_bias_x(msg);
- rocket_flight_tm->nas_bias_y = mavlink_msg_rocket_flight_tm_get_nas_bias_y(msg);
- rocket_flight_tm->nas_bias_z = mavlink_msg_rocket_flight_tm_get_nas_bias_z(msg);
- rocket_flight_tm->vbat = mavlink_msg_rocket_flight_tm_get_vbat(msg);
- rocket_flight_tm->temperature = mavlink_msg_rocket_flight_tm_get_temperature(msg);
- rocket_flight_tm->ada_state = mavlink_msg_rocket_flight_tm_get_ada_state(msg);
- rocket_flight_tm->fmm_state = mavlink_msg_rocket_flight_tm_get_fmm_state(msg);
- rocket_flight_tm->dpl_state = mavlink_msg_rocket_flight_tm_get_dpl_state(msg);
- rocket_flight_tm->abk_state = mavlink_msg_rocket_flight_tm_get_abk_state(msg);
- rocket_flight_tm->nas_state = mavlink_msg_rocket_flight_tm_get_nas_state(msg);
- rocket_flight_tm->gps_fix = mavlink_msg_rocket_flight_tm_get_gps_fix(msg);
- rocket_flight_tm->pin_launch = mavlink_msg_rocket_flight_tm_get_pin_launch(msg);
- rocket_flight_tm->pin_nosecone = mavlink_msg_rocket_flight_tm_get_pin_nosecone(msg);
- rocket_flight_tm->pin_expulsion = mavlink_msg_rocket_flight_tm_get_pin_expulsion(msg);
- rocket_flight_tm->cutter_presence = mavlink_msg_rocket_flight_tm_get_cutter_presence(msg);
- rocket_flight_tm->logger_error = mavlink_msg_rocket_flight_tm_get_logger_error(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN? msg->len : MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN;
- memset(rocket_flight_tm, 0, MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_LEN);
- memcpy(rocket_flight_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_rocket_stats_tm.h b/mavlink_lib/pyxis/mavlink_msg_rocket_stats_tm.h
deleted file mode 100644
index a1c76b88f23b905165cf29648307bd396e8bd93e..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_rocket_stats_tm.h
+++ /dev/null
@@ -1,638 +0,0 @@
-#pragma once
-// MESSAGE ROCKET_STATS_TM PACKING
-
-#define MAVLINK_MSG_ID_ROCKET_STATS_TM 209
-
-
-typedef struct __mavlink_rocket_stats_tm_t {
- uint64_t liftoff_ts; /*< [us] System clock at liftoff*/
- uint64_t liftoff_max_acc_ts; /*< [us] System clock at the maximum liftoff acceleration*/
- uint64_t dpl_ts; /*< [us] System clock at drouge deployment*/
- uint64_t max_z_speed_ts; /*< [us] System clock at ADA max vertical speed*/
- uint64_t apogee_ts; /*< [us] System clock at apogee*/
- float liftoff_max_acc; /*< [m/s2] Maximum liftoff acceleration*/
- float dpl_max_acc; /*< [m/s2] Max acceleration during drouge deployment*/
- float max_z_speed; /*< [m/s] Max measured vertical speed - ADA*/
- float max_airspeed_pitot; /*< [m/s] Max speed read by the pitot tube*/
- float max_speed_altitude; /*< [m] Altitude at max speed*/
- float apogee_lat; /*< [deg] Apogee latitude*/
- float apogee_lon; /*< [deg] Apogee longitude*/
- float apogee_alt; /*< [m] Apogee altitude*/
- float min_pressure; /*< [Pa] Apogee pressure - Digital barometer*/
- float ada_min_pressure; /*< [Pa] Apogee pressure - ADA filtered*/
- float dpl_vane_max_pressure; /*< [Pa] Max pressure in the deployment bay during drogue deployment*/
- float cpu_load; /*< CPU load in percentage*/
- uint32_t free_heap; /*< Amount of available heap in memory*/
-} mavlink_rocket_stats_tm_t;
-
-#define MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN 92
-#define MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN 92
-#define MAVLINK_MSG_ID_209_LEN 92
-#define MAVLINK_MSG_ID_209_MIN_LEN 92
-
-#define MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC 245
-#define MAVLINK_MSG_ID_209_CRC 245
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM { \
- 209, \
- "ROCKET_STATS_TM", \
- 18, \
- { { "liftoff_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_stats_tm_t, liftoff_ts) }, \
- { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_rocket_stats_tm_t, liftoff_max_acc_ts) }, \
- { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_rocket_stats_tm_t, liftoff_max_acc) }, \
- { "dpl_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_rocket_stats_tm_t, dpl_ts) }, \
- { "dpl_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_rocket_stats_tm_t, dpl_max_acc) }, \
- { "max_z_speed_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 24, offsetof(mavlink_rocket_stats_tm_t, max_z_speed_ts) }, \
- { "max_z_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_rocket_stats_tm_t, max_z_speed) }, \
- { "max_airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_rocket_stats_tm_t, max_airspeed_pitot) }, \
- { "max_speed_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_rocket_stats_tm_t, max_speed_altitude) }, \
- { "apogee_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 32, offsetof(mavlink_rocket_stats_tm_t, apogee_ts) }, \
- { "apogee_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_rocket_stats_tm_t, apogee_lat) }, \
- { "apogee_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_stats_tm_t, apogee_lon) }, \
- { "apogee_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_stats_tm_t, apogee_alt) }, \
- { "min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_stats_tm_t, min_pressure) }, \
- { "ada_min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_stats_tm_t, ada_min_pressure) }, \
- { "dpl_vane_max_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_stats_tm_t, dpl_vane_max_pressure) }, \
- { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_stats_tm_t, cpu_load) }, \
- { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 88, offsetof(mavlink_rocket_stats_tm_t, free_heap) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM { \
- "ROCKET_STATS_TM", \
- 18, \
- { { "liftoff_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rocket_stats_tm_t, liftoff_ts) }, \
- { "liftoff_max_acc_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_rocket_stats_tm_t, liftoff_max_acc_ts) }, \
- { "liftoff_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_rocket_stats_tm_t, liftoff_max_acc) }, \
- { "dpl_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_rocket_stats_tm_t, dpl_ts) }, \
- { "dpl_max_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_rocket_stats_tm_t, dpl_max_acc) }, \
- { "max_z_speed_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 24, offsetof(mavlink_rocket_stats_tm_t, max_z_speed_ts) }, \
- { "max_z_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_rocket_stats_tm_t, max_z_speed) }, \
- { "max_airspeed_pitot", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_rocket_stats_tm_t, max_airspeed_pitot) }, \
- { "max_speed_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_rocket_stats_tm_t, max_speed_altitude) }, \
- { "apogee_ts", NULL, MAVLINK_TYPE_UINT64_T, 0, 32, offsetof(mavlink_rocket_stats_tm_t, apogee_ts) }, \
- { "apogee_lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_rocket_stats_tm_t, apogee_lat) }, \
- { "apogee_lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_rocket_stats_tm_t, apogee_lon) }, \
- { "apogee_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_rocket_stats_tm_t, apogee_alt) }, \
- { "min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_rocket_stats_tm_t, min_pressure) }, \
- { "ada_min_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_rocket_stats_tm_t, ada_min_pressure) }, \
- { "dpl_vane_max_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_rocket_stats_tm_t, dpl_vane_max_pressure) }, \
- { "cpu_load", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_rocket_stats_tm_t, cpu_load) }, \
- { "free_heap", NULL, MAVLINK_TYPE_UINT32_T, 0, 88, offsetof(mavlink_rocket_stats_tm_t, free_heap) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a rocket_stats_tm 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 liftoff_ts [us] System clock at liftoff
- * @param liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param dpl_ts [us] System clock at drouge deployment
- * @param dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param max_z_speed_ts [us] System clock at ADA max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed - ADA
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [us] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param apogee_alt [m] Apogee altitude
- * @param min_pressure [Pa] Apogee pressure - Digital barometer
- * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered
- * @param dpl_vane_max_pressure [Pa] Max pressure in the deployment bay during drogue deployment
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_rocket_stats_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float ada_min_pressure, float dpl_vane_max_pressure, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_ts);
- _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 16, dpl_ts);
- _mav_put_uint64_t(buf, 24, max_z_speed_ts);
- _mav_put_uint64_t(buf, 32, apogee_ts);
- _mav_put_float(buf, 40, liftoff_max_acc);
- _mav_put_float(buf, 44, dpl_max_acc);
- _mav_put_float(buf, 48, max_z_speed);
- _mav_put_float(buf, 52, max_airspeed_pitot);
- _mav_put_float(buf, 56, max_speed_altitude);
- _mav_put_float(buf, 60, apogee_lat);
- _mav_put_float(buf, 64, apogee_lon);
- _mav_put_float(buf, 68, apogee_alt);
- _mav_put_float(buf, 72, min_pressure);
- _mav_put_float(buf, 76, ada_min_pressure);
- _mav_put_float(buf, 80, dpl_vane_max_pressure);
- _mav_put_float(buf, 84, cpu_load);
- _mav_put_uint32_t(buf, 88, free_heap);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
-#else
- mavlink_rocket_stats_tm_t packet;
- packet.liftoff_ts = liftoff_ts;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.dpl_ts = dpl_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.dpl_max_acc = dpl_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.apogee_alt = apogee_alt;
- packet.min_pressure = min_pressure;
- packet.ada_min_pressure = ada_min_pressure;
- packet.dpl_vane_max_pressure = dpl_vane_max_pressure;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ROCKET_STATS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-}
-
-/**
- * @brief Pack a rocket_stats_tm 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 liftoff_ts [us] System clock at liftoff
- * @param liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param dpl_ts [us] System clock at drouge deployment
- * @param dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param max_z_speed_ts [us] System clock at ADA max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed - ADA
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [us] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param apogee_alt [m] Apogee altitude
- * @param min_pressure [Pa] Apogee pressure - Digital barometer
- * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered
- * @param dpl_vane_max_pressure [Pa] Max pressure in the deployment bay during drogue deployment
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_rocket_stats_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t liftoff_ts,uint64_t liftoff_max_acc_ts,float liftoff_max_acc,uint64_t dpl_ts,float dpl_max_acc,uint64_t max_z_speed_ts,float max_z_speed,float max_airspeed_pitot,float max_speed_altitude,uint64_t apogee_ts,float apogee_lat,float apogee_lon,float apogee_alt,float min_pressure,float ada_min_pressure,float dpl_vane_max_pressure,float cpu_load,uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_ts);
- _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 16, dpl_ts);
- _mav_put_uint64_t(buf, 24, max_z_speed_ts);
- _mav_put_uint64_t(buf, 32, apogee_ts);
- _mav_put_float(buf, 40, liftoff_max_acc);
- _mav_put_float(buf, 44, dpl_max_acc);
- _mav_put_float(buf, 48, max_z_speed);
- _mav_put_float(buf, 52, max_airspeed_pitot);
- _mav_put_float(buf, 56, max_speed_altitude);
- _mav_put_float(buf, 60, apogee_lat);
- _mav_put_float(buf, 64, apogee_lon);
- _mav_put_float(buf, 68, apogee_alt);
- _mav_put_float(buf, 72, min_pressure);
- _mav_put_float(buf, 76, ada_min_pressure);
- _mav_put_float(buf, 80, dpl_vane_max_pressure);
- _mav_put_float(buf, 84, cpu_load);
- _mav_put_uint32_t(buf, 88, free_heap);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
-#else
- mavlink_rocket_stats_tm_t packet;
- packet.liftoff_ts = liftoff_ts;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.dpl_ts = dpl_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.dpl_max_acc = dpl_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.apogee_alt = apogee_alt;
- packet.min_pressure = min_pressure;
- packet.ada_min_pressure = ada_min_pressure;
- packet.dpl_vane_max_pressure = dpl_vane_max_pressure;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ROCKET_STATS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-}
-
-/**
- * @brief Encode a rocket_stats_tm 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 rocket_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_rocket_stats_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rocket_stats_tm_t* rocket_stats_tm)
-{
- return mavlink_msg_rocket_stats_tm_pack(system_id, component_id, msg, rocket_stats_tm->liftoff_ts, rocket_stats_tm->liftoff_max_acc_ts, rocket_stats_tm->liftoff_max_acc, rocket_stats_tm->dpl_ts, rocket_stats_tm->dpl_max_acc, rocket_stats_tm->max_z_speed_ts, rocket_stats_tm->max_z_speed, rocket_stats_tm->max_airspeed_pitot, rocket_stats_tm->max_speed_altitude, rocket_stats_tm->apogee_ts, rocket_stats_tm->apogee_lat, rocket_stats_tm->apogee_lon, rocket_stats_tm->apogee_alt, rocket_stats_tm->min_pressure, rocket_stats_tm->ada_min_pressure, rocket_stats_tm->dpl_vane_max_pressure, rocket_stats_tm->cpu_load, rocket_stats_tm->free_heap);
-}
-
-/**
- * @brief Encode a rocket_stats_tm 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 rocket_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_rocket_stats_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rocket_stats_tm_t* rocket_stats_tm)
-{
- return mavlink_msg_rocket_stats_tm_pack_chan(system_id, component_id, chan, msg, rocket_stats_tm->liftoff_ts, rocket_stats_tm->liftoff_max_acc_ts, rocket_stats_tm->liftoff_max_acc, rocket_stats_tm->dpl_ts, rocket_stats_tm->dpl_max_acc, rocket_stats_tm->max_z_speed_ts, rocket_stats_tm->max_z_speed, rocket_stats_tm->max_airspeed_pitot, rocket_stats_tm->max_speed_altitude, rocket_stats_tm->apogee_ts, rocket_stats_tm->apogee_lat, rocket_stats_tm->apogee_lon, rocket_stats_tm->apogee_alt, rocket_stats_tm->min_pressure, rocket_stats_tm->ada_min_pressure, rocket_stats_tm->dpl_vane_max_pressure, rocket_stats_tm->cpu_load, rocket_stats_tm->free_heap);
-}
-
-/**
- * @brief Send a rocket_stats_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param liftoff_ts [us] System clock at liftoff
- * @param liftoff_max_acc_ts [us] System clock at the maximum liftoff acceleration
- * @param liftoff_max_acc [m/s2] Maximum liftoff acceleration
- * @param dpl_ts [us] System clock at drouge deployment
- * @param dpl_max_acc [m/s2] Max acceleration during drouge deployment
- * @param max_z_speed_ts [us] System clock at ADA max vertical speed
- * @param max_z_speed [m/s] Max measured vertical speed - ADA
- * @param max_airspeed_pitot [m/s] Max speed read by the pitot tube
- * @param max_speed_altitude [m] Altitude at max speed
- * @param apogee_ts [us] System clock at apogee
- * @param apogee_lat [deg] Apogee latitude
- * @param apogee_lon [deg] Apogee longitude
- * @param apogee_alt [m] Apogee altitude
- * @param min_pressure [Pa] Apogee pressure - Digital barometer
- * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered
- * @param dpl_vane_max_pressure [Pa] Max pressure in the deployment bay during drogue deployment
- * @param cpu_load CPU load in percentage
- * @param free_heap Amount of available heap in memory
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_rocket_stats_tm_send(mavlink_channel_t chan, uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float ada_min_pressure, float dpl_vane_max_pressure, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, liftoff_ts);
- _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 16, dpl_ts);
- _mav_put_uint64_t(buf, 24, max_z_speed_ts);
- _mav_put_uint64_t(buf, 32, apogee_ts);
- _mav_put_float(buf, 40, liftoff_max_acc);
- _mav_put_float(buf, 44, dpl_max_acc);
- _mav_put_float(buf, 48, max_z_speed);
- _mav_put_float(buf, 52, max_airspeed_pitot);
- _mav_put_float(buf, 56, max_speed_altitude);
- _mav_put_float(buf, 60, apogee_lat);
- _mav_put_float(buf, 64, apogee_lon);
- _mav_put_float(buf, 68, apogee_alt);
- _mav_put_float(buf, 72, min_pressure);
- _mav_put_float(buf, 76, ada_min_pressure);
- _mav_put_float(buf, 80, dpl_vane_max_pressure);
- _mav_put_float(buf, 84, cpu_load);
- _mav_put_uint32_t(buf, 88, free_heap);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_STATS_TM, buf, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-#else
- mavlink_rocket_stats_tm_t packet;
- packet.liftoff_ts = liftoff_ts;
- packet.liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet.dpl_ts = dpl_ts;
- packet.max_z_speed_ts = max_z_speed_ts;
- packet.apogee_ts = apogee_ts;
- packet.liftoff_max_acc = liftoff_max_acc;
- packet.dpl_max_acc = dpl_max_acc;
- packet.max_z_speed = max_z_speed;
- packet.max_airspeed_pitot = max_airspeed_pitot;
- packet.max_speed_altitude = max_speed_altitude;
- packet.apogee_lat = apogee_lat;
- packet.apogee_lon = apogee_lon;
- packet.apogee_alt = apogee_alt;
- packet.min_pressure = min_pressure;
- packet.ada_min_pressure = ada_min_pressure;
- packet.dpl_vane_max_pressure = dpl_vane_max_pressure;
- packet.cpu_load = cpu_load;
- packet.free_heap = free_heap;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_STATS_TM, (const char *)&packet, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a rocket_stats_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_rocket_stats_tm_send_struct(mavlink_channel_t chan, const mavlink_rocket_stats_tm_t* rocket_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_rocket_stats_tm_send(chan, rocket_stats_tm->liftoff_ts, rocket_stats_tm->liftoff_max_acc_ts, rocket_stats_tm->liftoff_max_acc, rocket_stats_tm->dpl_ts, rocket_stats_tm->dpl_max_acc, rocket_stats_tm->max_z_speed_ts, rocket_stats_tm->max_z_speed, rocket_stats_tm->max_airspeed_pitot, rocket_stats_tm->max_speed_altitude, rocket_stats_tm->apogee_ts, rocket_stats_tm->apogee_lat, rocket_stats_tm->apogee_lon, rocket_stats_tm->apogee_alt, rocket_stats_tm->min_pressure, rocket_stats_tm->ada_min_pressure, rocket_stats_tm->dpl_vane_max_pressure, rocket_stats_tm->cpu_load, rocket_stats_tm->free_heap);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_STATS_TM, (const char *)rocket_stats_tm, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ROCKET_STATS_TM_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_rocket_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t liftoff_ts, uint64_t liftoff_max_acc_ts, float liftoff_max_acc, uint64_t dpl_ts, float dpl_max_acc, uint64_t max_z_speed_ts, float max_z_speed, float max_airspeed_pitot, float max_speed_altitude, uint64_t apogee_ts, float apogee_lat, float apogee_lon, float apogee_alt, float min_pressure, float ada_min_pressure, float dpl_vane_max_pressure, float cpu_load, uint32_t free_heap)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, liftoff_ts);
- _mav_put_uint64_t(buf, 8, liftoff_max_acc_ts);
- _mav_put_uint64_t(buf, 16, dpl_ts);
- _mav_put_uint64_t(buf, 24, max_z_speed_ts);
- _mav_put_uint64_t(buf, 32, apogee_ts);
- _mav_put_float(buf, 40, liftoff_max_acc);
- _mav_put_float(buf, 44, dpl_max_acc);
- _mav_put_float(buf, 48, max_z_speed);
- _mav_put_float(buf, 52, max_airspeed_pitot);
- _mav_put_float(buf, 56, max_speed_altitude);
- _mav_put_float(buf, 60, apogee_lat);
- _mav_put_float(buf, 64, apogee_lon);
- _mav_put_float(buf, 68, apogee_alt);
- _mav_put_float(buf, 72, min_pressure);
- _mav_put_float(buf, 76, ada_min_pressure);
- _mav_put_float(buf, 80, dpl_vane_max_pressure);
- _mav_put_float(buf, 84, cpu_load);
- _mav_put_uint32_t(buf, 88, free_heap);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_STATS_TM, buf, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-#else
- mavlink_rocket_stats_tm_t *packet = (mavlink_rocket_stats_tm_t *)msgbuf;
- packet->liftoff_ts = liftoff_ts;
- packet->liftoff_max_acc_ts = liftoff_max_acc_ts;
- packet->dpl_ts = dpl_ts;
- packet->max_z_speed_ts = max_z_speed_ts;
- packet->apogee_ts = apogee_ts;
- packet->liftoff_max_acc = liftoff_max_acc;
- packet->dpl_max_acc = dpl_max_acc;
- packet->max_z_speed = max_z_speed;
- packet->max_airspeed_pitot = max_airspeed_pitot;
- packet->max_speed_altitude = max_speed_altitude;
- packet->apogee_lat = apogee_lat;
- packet->apogee_lon = apogee_lon;
- packet->apogee_alt = apogee_alt;
- packet->min_pressure = min_pressure;
- packet->ada_min_pressure = ada_min_pressure;
- packet->dpl_vane_max_pressure = dpl_vane_max_pressure;
- packet->cpu_load = cpu_load;
- packet->free_heap = free_heap;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROCKET_STATS_TM, (const char *)packet, MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN, MAVLINK_MSG_ID_ROCKET_STATS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ROCKET_STATS_TM UNPACKING
-
-
-/**
- * @brief Get field liftoff_ts from rocket_stats_tm message
- *
- * @return [us] System clock at liftoff
- */
-static inline uint64_t mavlink_msg_rocket_stats_tm_get_liftoff_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field liftoff_max_acc_ts from rocket_stats_tm message
- *
- * @return [us] System clock at the maximum liftoff acceleration
- */
-static inline uint64_t mavlink_msg_rocket_stats_tm_get_liftoff_max_acc_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 8);
-}
-
-/**
- * @brief Get field liftoff_max_acc from rocket_stats_tm message
- *
- * @return [m/s2] Maximum liftoff acceleration
- */
-static inline float mavlink_msg_rocket_stats_tm_get_liftoff_max_acc(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field dpl_ts from rocket_stats_tm message
- *
- * @return [us] System clock at drouge deployment
- */
-static inline uint64_t mavlink_msg_rocket_stats_tm_get_dpl_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 16);
-}
-
-/**
- * @brief Get field dpl_max_acc from rocket_stats_tm message
- *
- * @return [m/s2] Max acceleration during drouge deployment
- */
-static inline float mavlink_msg_rocket_stats_tm_get_dpl_max_acc(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field max_z_speed_ts from rocket_stats_tm message
- *
- * @return [us] System clock at ADA max vertical speed
- */
-static inline uint64_t mavlink_msg_rocket_stats_tm_get_max_z_speed_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 24);
-}
-
-/**
- * @brief Get field max_z_speed from rocket_stats_tm message
- *
- * @return [m/s] Max measured vertical speed - ADA
- */
-static inline float mavlink_msg_rocket_stats_tm_get_max_z_speed(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field max_airspeed_pitot from rocket_stats_tm message
- *
- * @return [m/s] Max speed read by the pitot tube
- */
-static inline float mavlink_msg_rocket_stats_tm_get_max_airspeed_pitot(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field max_speed_altitude from rocket_stats_tm message
- *
- * @return [m] Altitude at max speed
- */
-static inline float mavlink_msg_rocket_stats_tm_get_max_speed_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field apogee_ts from rocket_stats_tm message
- *
- * @return [us] System clock at apogee
- */
-static inline uint64_t mavlink_msg_rocket_stats_tm_get_apogee_ts(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 32);
-}
-
-/**
- * @brief Get field apogee_lat from rocket_stats_tm message
- *
- * @return [deg] Apogee latitude
- */
-static inline float mavlink_msg_rocket_stats_tm_get_apogee_lat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field apogee_lon from rocket_stats_tm message
- *
- * @return [deg] Apogee longitude
- */
-static inline float mavlink_msg_rocket_stats_tm_get_apogee_lon(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field apogee_alt from rocket_stats_tm message
- *
- * @return [m] Apogee altitude
- */
-static inline float mavlink_msg_rocket_stats_tm_get_apogee_alt(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field min_pressure from rocket_stats_tm message
- *
- * @return [Pa] Apogee pressure - Digital barometer
- */
-static inline float mavlink_msg_rocket_stats_tm_get_min_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 72);
-}
-
-/**
- * @brief Get field ada_min_pressure from rocket_stats_tm message
- *
- * @return [Pa] Apogee pressure - ADA filtered
- */
-static inline float mavlink_msg_rocket_stats_tm_get_ada_min_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 76);
-}
-
-/**
- * @brief Get field dpl_vane_max_pressure from rocket_stats_tm message
- *
- * @return [Pa] Max pressure in the deployment bay during drogue deployment
- */
-static inline float mavlink_msg_rocket_stats_tm_get_dpl_vane_max_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 80);
-}
-
-/**
- * @brief Get field cpu_load from rocket_stats_tm message
- *
- * @return CPU load in percentage
- */
-static inline float mavlink_msg_rocket_stats_tm_get_cpu_load(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 84);
-}
-
-/**
- * @brief Get field free_heap from rocket_stats_tm message
- *
- * @return Amount of available heap in memory
- */
-static inline uint32_t mavlink_msg_rocket_stats_tm_get_free_heap(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 88);
-}
-
-/**
- * @brief Decode a rocket_stats_tm message into a struct
- *
- * @param msg The message to decode
- * @param rocket_stats_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_rocket_stats_tm_decode(const mavlink_message_t* msg, mavlink_rocket_stats_tm_t* rocket_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- rocket_stats_tm->liftoff_ts = mavlink_msg_rocket_stats_tm_get_liftoff_ts(msg);
- rocket_stats_tm->liftoff_max_acc_ts = mavlink_msg_rocket_stats_tm_get_liftoff_max_acc_ts(msg);
- rocket_stats_tm->dpl_ts = mavlink_msg_rocket_stats_tm_get_dpl_ts(msg);
- rocket_stats_tm->max_z_speed_ts = mavlink_msg_rocket_stats_tm_get_max_z_speed_ts(msg);
- rocket_stats_tm->apogee_ts = mavlink_msg_rocket_stats_tm_get_apogee_ts(msg);
- rocket_stats_tm->liftoff_max_acc = mavlink_msg_rocket_stats_tm_get_liftoff_max_acc(msg);
- rocket_stats_tm->dpl_max_acc = mavlink_msg_rocket_stats_tm_get_dpl_max_acc(msg);
- rocket_stats_tm->max_z_speed = mavlink_msg_rocket_stats_tm_get_max_z_speed(msg);
- rocket_stats_tm->max_airspeed_pitot = mavlink_msg_rocket_stats_tm_get_max_airspeed_pitot(msg);
- rocket_stats_tm->max_speed_altitude = mavlink_msg_rocket_stats_tm_get_max_speed_altitude(msg);
- rocket_stats_tm->apogee_lat = mavlink_msg_rocket_stats_tm_get_apogee_lat(msg);
- rocket_stats_tm->apogee_lon = mavlink_msg_rocket_stats_tm_get_apogee_lon(msg);
- rocket_stats_tm->apogee_alt = mavlink_msg_rocket_stats_tm_get_apogee_alt(msg);
- rocket_stats_tm->min_pressure = mavlink_msg_rocket_stats_tm_get_min_pressure(msg);
- rocket_stats_tm->ada_min_pressure = mavlink_msg_rocket_stats_tm_get_ada_min_pressure(msg);
- rocket_stats_tm->dpl_vane_max_pressure = mavlink_msg_rocket_stats_tm_get_dpl_vane_max_pressure(msg);
- rocket_stats_tm->cpu_load = mavlink_msg_rocket_stats_tm_get_cpu_load(msg);
- rocket_stats_tm->free_heap = mavlink_msg_rocket_stats_tm_get_free_heap(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN? msg->len : MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN;
- memset(rocket_stats_tm, 0, MAVLINK_MSG_ID_ROCKET_STATS_TM_LEN);
- memcpy(rocket_stats_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_sensor_state_tm.h b/mavlink_lib/pyxis/mavlink_msg_sensor_state_tm.h
deleted file mode 100644
index fed43a8843a506233f2863b32ea7b5fbf8afb80d..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_sensor_state_tm.h
+++ /dev/null
@@ -1,230 +0,0 @@
-#pragma once
-// MESSAGE SENSOR_STATE_TM PACKING
-
-#define MAVLINK_MSG_ID_SENSOR_STATE_TM 111
-
-
-typedef struct __mavlink_sensor_state_tm_t {
- char sensor_id[20]; /*< Sensor name*/
- uint8_t state; /*< Boolean that represents the init state*/
-} mavlink_sensor_state_tm_t;
-
-#define MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN 21
-#define MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN 21
-#define MAVLINK_MSG_ID_111_LEN 21
-#define MAVLINK_MSG_ID_111_MIN_LEN 21
-
-#define MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC 42
-#define MAVLINK_MSG_ID_111_CRC 42
-
-#define MAVLINK_MSG_SENSOR_STATE_TM_FIELD_SENSOR_ID_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM { \
- 111, \
- "SENSOR_STATE_TM", \
- 2, \
- { { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 0, offsetof(mavlink_sensor_state_tm_t, sensor_id) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_sensor_state_tm_t, state) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM { \
- "SENSOR_STATE_TM", \
- 2, \
- { { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 0, offsetof(mavlink_sensor_state_tm_t, sensor_id) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_sensor_state_tm_t, state) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a sensor_state_tm 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 sensor_id Sensor name
- * @param state Boolean that represents the init state
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sensor_state_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- const char *sensor_id, uint8_t state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN];
- _mav_put_uint8_t(buf, 20, state);
- _mav_put_char_array(buf, 0, sensor_id, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
-#else
- mavlink_sensor_state_tm_t packet;
- packet.state = state;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SENSOR_STATE_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-}
-
-/**
- * @brief Pack a sensor_state_tm 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 sensor_id Sensor name
- * @param state Boolean that represents the init state
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sensor_state_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- const char *sensor_id,uint8_t state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN];
- _mav_put_uint8_t(buf, 20, state);
- _mav_put_char_array(buf, 0, sensor_id, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
-#else
- mavlink_sensor_state_tm_t packet;
- packet.state = state;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SENSOR_STATE_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-}
-
-/**
- * @brief Encode a sensor_state_tm 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 sensor_state_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sensor_state_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_state_tm_t* sensor_state_tm)
-{
- return mavlink_msg_sensor_state_tm_pack(system_id, component_id, msg, sensor_state_tm->sensor_id, sensor_state_tm->state);
-}
-
-/**
- * @brief Encode a sensor_state_tm 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 sensor_state_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sensor_state_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sensor_state_tm_t* sensor_state_tm)
-{
- return mavlink_msg_sensor_state_tm_pack_chan(system_id, component_id, chan, msg, sensor_state_tm->sensor_id, sensor_state_tm->state);
-}
-
-/**
- * @brief Send a sensor_state_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param sensor_id Sensor name
- * @param state Boolean that represents the init state
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_sensor_state_tm_send(mavlink_channel_t chan, const char *sensor_id, uint8_t state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN];
- _mav_put_uint8_t(buf, 20, state);
- _mav_put_char_array(buf, 0, sensor_id, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_STATE_TM, buf, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-#else
- mavlink_sensor_state_tm_t packet;
- packet.state = state;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_STATE_TM, (const char *)&packet, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a sensor_state_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_sensor_state_tm_send_struct(mavlink_channel_t chan, const mavlink_sensor_state_tm_t* sensor_state_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_sensor_state_tm_send(chan, sensor_state_tm->sensor_id, sensor_state_tm->state);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_STATE_TM, (const char *)sensor_state_tm, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SENSOR_STATE_TM_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_sensor_state_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *sensor_id, uint8_t state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 20, state);
- _mav_put_char_array(buf, 0, sensor_id, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_STATE_TM, buf, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-#else
- mavlink_sensor_state_tm_t *packet = (mavlink_sensor_state_tm_t *)msgbuf;
- packet->state = state;
- mav_array_memcpy(packet->sensor_id, sensor_id, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_STATE_TM, (const char *)packet, MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN, MAVLINK_MSG_ID_SENSOR_STATE_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SENSOR_STATE_TM UNPACKING
-
-
-/**
- * @brief Get field sensor_id from sensor_state_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_sensor_state_tm_get_sensor_id(const mavlink_message_t* msg, char *sensor_id)
-{
- return _MAV_RETURN_char_array(msg, sensor_id, 20, 0);
-}
-
-/**
- * @brief Get field state from sensor_state_tm message
- *
- * @return Boolean that represents the init state
- */
-static inline uint8_t mavlink_msg_sensor_state_tm_get_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 20);
-}
-
-/**
- * @brief Decode a sensor_state_tm message into a struct
- *
- * @param msg The message to decode
- * @param sensor_state_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_sensor_state_tm_decode(const mavlink_message_t* msg, mavlink_sensor_state_tm_t* sensor_state_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_sensor_state_tm_get_sensor_id(msg, sensor_state_tm->sensor_id);
- sensor_state_tm->state = mavlink_msg_sensor_state_tm_get_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN? msg->len : MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN;
- memset(sensor_state_tm, 0, MAVLINK_MSG_ID_SENSOR_STATE_TM_LEN);
- memcpy(sensor_state_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_sensor_tm_request_tc.h b/mavlink_lib/pyxis/mavlink_msg_sensor_tm_request_tc.h
deleted file mode 100644
index 0deb0024310dcc80b876c1a4013c98891341c034..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_sensor_tm_request_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SENSOR_TM_REQUEST_TC PACKING
-
-#define MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC 4
-
-
-typedef struct __mavlink_sensor_tm_request_tc_t {
- uint8_t sensor_id; /*< A member of the SensorTMList enum*/
-} mavlink_sensor_tm_request_tc_t;
-
-#define MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN 1
-#define MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_4_LEN 1
-#define MAVLINK_MSG_ID_4_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC 103
-#define MAVLINK_MSG_ID_4_CRC 103
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC { \
- 4, \
- "SENSOR_TM_REQUEST_TC", \
- 1, \
- { { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_sensor_tm_request_tc_t, sensor_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC { \
- "SENSOR_TM_REQUEST_TC", \
- 1, \
- { { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_sensor_tm_request_tc_t, sensor_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a sensor_tm_request_tc 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 sensor_id A member of the SensorTMList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sensor_tm_request_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t sensor_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, sensor_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN);
-#else
- mavlink_sensor_tm_request_tc_t packet;
- packet.sensor_id = sensor_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Pack a sensor_tm_request_tc 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 sensor_id A member of the SensorTMList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sensor_tm_request_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t sensor_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, sensor_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN);
-#else
- mavlink_sensor_tm_request_tc_t packet;
- packet.sensor_id = sensor_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Encode a sensor_tm_request_tc 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 sensor_tm_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sensor_tm_request_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_tm_request_tc_t* sensor_tm_request_tc)
-{
- return mavlink_msg_sensor_tm_request_tc_pack(system_id, component_id, msg, sensor_tm_request_tc->sensor_id);
-}
-
-/**
- * @brief Encode a sensor_tm_request_tc 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 sensor_tm_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sensor_tm_request_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sensor_tm_request_tc_t* sensor_tm_request_tc)
-{
- return mavlink_msg_sensor_tm_request_tc_pack_chan(system_id, component_id, chan, msg, sensor_tm_request_tc->sensor_id);
-}
-
-/**
- * @brief Send a sensor_tm_request_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param sensor_id A member of the SensorTMList enum
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_sensor_tm_request_tc_send(mavlink_channel_t chan, uint8_t sensor_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, sensor_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC, buf, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-#else
- mavlink_sensor_tm_request_tc_t packet;
- packet.sensor_id = sensor_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC, (const char *)&packet, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a sensor_tm_request_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_sensor_tm_request_tc_send_struct(mavlink_channel_t chan, const mavlink_sensor_tm_request_tc_t* sensor_tm_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_sensor_tm_request_tc_send(chan, sensor_tm_request_tc->sensor_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC, (const char *)sensor_tm_request_tc, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_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_sensor_tm_request_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t sensor_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, sensor_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC, buf, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-#else
- mavlink_sensor_tm_request_tc_t *packet = (mavlink_sensor_tm_request_tc_t *)msgbuf;
- packet->sensor_id = sensor_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC, (const char *)packet, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SENSOR_TM_REQUEST_TC UNPACKING
-
-
-/**
- * @brief Get field sensor_id from sensor_tm_request_tc message
- *
- * @return A member of the SensorTMList enum
- */
-static inline uint8_t mavlink_msg_sensor_tm_request_tc_get_sensor_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a sensor_tm_request_tc message into a struct
- *
- * @param msg The message to decode
- * @param sensor_tm_request_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_sensor_tm_request_tc_decode(const mavlink_message_t* msg, mavlink_sensor_tm_request_tc_t* sensor_tm_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- sensor_tm_request_tc->sensor_id = mavlink_msg_sensor_tm_request_tc_get_sensor_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN? msg->len : MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN;
- memset(sensor_tm_request_tc, 0, MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_LEN);
- memcpy(sensor_tm_request_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_servo_tm.h b/mavlink_lib/pyxis/mavlink_msg_servo_tm.h
deleted file mode 100644
index 0ffe705d7c4094e1d82b537e2c7977a64b12c86a..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_servo_tm.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SERVO_TM PACKING
-
-#define MAVLINK_MSG_ID_SERVO_TM 112
-
-
-typedef struct __mavlink_servo_tm_t {
- float servo_position; /*< Position of the servo [0-1]*/
- uint8_t servo_id; /*< A member of the ServosList enum*/
-} mavlink_servo_tm_t;
-
-#define MAVLINK_MSG_ID_SERVO_TM_LEN 5
-#define MAVLINK_MSG_ID_SERVO_TM_MIN_LEN 5
-#define MAVLINK_MSG_ID_112_LEN 5
-#define MAVLINK_MSG_ID_112_MIN_LEN 5
-
-#define MAVLINK_MSG_ID_SERVO_TM_CRC 87
-#define MAVLINK_MSG_ID_112_CRC 87
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SERVO_TM { \
- 112, \
- "SERVO_TM", \
- 2, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_servo_tm_t, servo_id) }, \
- { "servo_position", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_servo_tm_t, servo_position) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SERVO_TM { \
- "SERVO_TM", \
- 2, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_servo_tm_t, servo_id) }, \
- { "servo_position", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_servo_tm_t, servo_position) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a servo_tm 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 servo_id A member of the ServosList enum
- * @param servo_position Position of the servo [0-1]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_servo_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t servo_id, float servo_position)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SERVO_TM_LEN];
- _mav_put_float(buf, 0, servo_position);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_TM_LEN);
-#else
- mavlink_servo_tm_t packet;
- packet.servo_position = servo_position;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SERVO_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-}
-
-/**
- * @brief Pack a servo_tm 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 servo_id A member of the ServosList enum
- * @param servo_position Position of the servo [0-1]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_servo_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t servo_id,float servo_position)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SERVO_TM_LEN];
- _mav_put_float(buf, 0, servo_position);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_TM_LEN);
-#else
- mavlink_servo_tm_t packet;
- packet.servo_position = servo_position;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SERVO_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-}
-
-/**
- * @brief Encode a servo_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_servo_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_servo_tm_t* servo_tm)
-{
- return mavlink_msg_servo_tm_pack(system_id, component_id, msg, servo_tm->servo_id, servo_tm->servo_position);
-}
-
-/**
- * @brief Encode a servo_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_servo_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_servo_tm_t* servo_tm)
-{
- return mavlink_msg_servo_tm_pack_chan(system_id, component_id, chan, msg, servo_tm->servo_id, servo_tm->servo_position);
-}
-
-/**
- * @brief Send a servo_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param servo_id A member of the ServosList enum
- * @param servo_position Position of the servo [0-1]
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_servo_tm_send(mavlink_channel_t chan, uint8_t servo_id, float servo_position)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SERVO_TM_LEN];
- _mav_put_float(buf, 0, servo_position);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM, buf, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-#else
- mavlink_servo_tm_t packet;
- packet.servo_position = servo_position;
- packet.servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM, (const char *)&packet, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a servo_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_servo_tm_send_struct(mavlink_channel_t chan, const mavlink_servo_tm_t* servo_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_servo_tm_send(chan, servo_tm->servo_id, servo_tm->servo_position);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM, (const char *)servo_tm, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SERVO_TM_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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t servo_id, float servo_position)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, servo_position);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM, buf, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-#else
- mavlink_servo_tm_t *packet = (mavlink_servo_tm_t *)msgbuf;
- packet->servo_position = servo_position;
- packet->servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM, (const char *)packet, MAVLINK_MSG_ID_SERVO_TM_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_LEN, MAVLINK_MSG_ID_SERVO_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SERVO_TM UNPACKING
-
-
-/**
- * @brief Get field servo_id from servo_tm message
- *
- * @return A member of the ServosList enum
- */
-static inline uint8_t mavlink_msg_servo_tm_get_servo_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 4);
-}
-
-/**
- * @brief Get field servo_position from servo_tm message
- *
- * @return Position of the servo [0-1]
- */
-static inline float mavlink_msg_servo_tm_get_servo_position(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a servo_tm message into a struct
- *
- * @param msg The message to decode
- * @param servo_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_servo_tm_decode(const mavlink_message_t* msg, mavlink_servo_tm_t* servo_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- servo_tm->servo_position = mavlink_msg_servo_tm_get_servo_position(msg);
- servo_tm->servo_id = mavlink_msg_servo_tm_get_servo_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SERVO_TM_LEN? msg->len : MAVLINK_MSG_ID_SERVO_TM_LEN;
- memset(servo_tm, 0, MAVLINK_MSG_ID_SERVO_TM_LEN);
- memcpy(servo_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_servo_tm_request_tc.h b/mavlink_lib/pyxis/mavlink_msg_servo_tm_request_tc.h
deleted file mode 100644
index 6ac27824c3a9ac7df9d8bf0a0983c552f689cb71..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_servo_tm_request_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SERVO_TM_REQUEST_TC PACKING
-
-#define MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC 5
-
-
-typedef struct __mavlink_servo_tm_request_tc_t {
- uint8_t servo_id; /*< A member of the ServosList enum*/
-} mavlink_servo_tm_request_tc_t;
-
-#define MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN 1
-#define MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_5_LEN 1
-#define MAVLINK_MSG_ID_5_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC 184
-#define MAVLINK_MSG_ID_5_CRC 184
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC { \
- 5, \
- "SERVO_TM_REQUEST_TC", \
- 1, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_servo_tm_request_tc_t, servo_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC { \
- "SERVO_TM_REQUEST_TC", \
- 1, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_servo_tm_request_tc_t, servo_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a servo_tm_request_tc 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 servo_id A member of the ServosList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_servo_tm_request_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN);
-#else
- mavlink_servo_tm_request_tc_t packet;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Pack a servo_tm_request_tc 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 servo_id A member of the ServosList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_servo_tm_request_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN);
-#else
- mavlink_servo_tm_request_tc_t packet;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Encode a servo_tm_request_tc 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_tm_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_servo_tm_request_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_servo_tm_request_tc_t* servo_tm_request_tc)
-{
- return mavlink_msg_servo_tm_request_tc_pack(system_id, component_id, msg, servo_tm_request_tc->servo_id);
-}
-
-/**
- * @brief Encode a servo_tm_request_tc 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_tm_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_servo_tm_request_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_servo_tm_request_tc_t* servo_tm_request_tc)
-{
- return mavlink_msg_servo_tm_request_tc_pack_chan(system_id, component_id, chan, msg, servo_tm_request_tc->servo_id);
-}
-
-/**
- * @brief Send a servo_tm_request_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param servo_id A member of the ServosList enum
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_servo_tm_request_tc_send(mavlink_channel_t chan, uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC, buf, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-#else
- mavlink_servo_tm_request_tc_t packet;
- packet.servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC, (const char *)&packet, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a servo_tm_request_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_servo_tm_request_tc_send_struct(mavlink_channel_t chan, const mavlink_servo_tm_request_tc_t* servo_tm_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_servo_tm_request_tc_send(chan, servo_tm_request_tc->servo_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC, (const char *)servo_tm_request_tc, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_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_tm_request_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC, buf, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-#else
- mavlink_servo_tm_request_tc_t *packet = (mavlink_servo_tm_request_tc_t *)msgbuf;
- packet->servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC, (const char *)packet, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SERVO_TM_REQUEST_TC UNPACKING
-
-
-/**
- * @brief Get field servo_id from servo_tm_request_tc message
- *
- * @return A member of the ServosList enum
- */
-static inline uint8_t mavlink_msg_servo_tm_request_tc_get_servo_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a servo_tm_request_tc message into a struct
- *
- * @param msg The message to decode
- * @param servo_tm_request_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_servo_tm_request_tc_decode(const mavlink_message_t* msg, mavlink_servo_tm_request_tc_t* servo_tm_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- servo_tm_request_tc->servo_id = mavlink_msg_servo_tm_request_tc_get_servo_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN? msg->len : MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN;
- memset(servo_tm_request_tc, 0, MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_LEN);
- memcpy(servo_tm_request_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_set_algorithm_tc.h b/mavlink_lib/pyxis/mavlink_msg_set_algorithm_tc.h
deleted file mode 100644
index 68de47900b54c4ba2dd2d8243250d5a1474d57e2..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_set_algorithm_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SET_ALGORITHM_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_ALGORITHM_TC 16
-
-
-typedef struct __mavlink_set_algorithm_tc_t {
- uint8_t algorithm_number; /*< Algorithm number*/
-} mavlink_set_algorithm_tc_t;
-
-#define MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN 1
-#define MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_16_LEN 1
-#define MAVLINK_MSG_ID_16_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC 181
-#define MAVLINK_MSG_ID_16_CRC 181
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC { \
- 16, \
- "SET_ALGORITHM_TC", \
- 1, \
- { { "algorithm_number", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_algorithm_tc_t, algorithm_number) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC { \
- "SET_ALGORITHM_TC", \
- 1, \
- { { "algorithm_number", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_algorithm_tc_t, algorithm_number) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_algorithm_tc 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 algorithm_number Algorithm number
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_algorithm_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t algorithm_number)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN];
- _mav_put_uint8_t(buf, 0, algorithm_number);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN);
-#else
- mavlink_set_algorithm_tc_t packet;
- packet.algorithm_number = algorithm_number;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_ALGORITHM_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-}
-
-/**
- * @brief Pack a set_algorithm_tc 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 algorithm_number Algorithm number
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_algorithm_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t algorithm_number)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN];
- _mav_put_uint8_t(buf, 0, algorithm_number);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN);
-#else
- mavlink_set_algorithm_tc_t packet;
- packet.algorithm_number = algorithm_number;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_ALGORITHM_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-}
-
-/**
- * @brief Encode a set_algorithm_tc 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_algorithm_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_algorithm_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_algorithm_tc_t* set_algorithm_tc)
-{
- return mavlink_msg_set_algorithm_tc_pack(system_id, component_id, msg, set_algorithm_tc->algorithm_number);
-}
-
-/**
- * @brief Encode a set_algorithm_tc 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_algorithm_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_algorithm_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_algorithm_tc_t* set_algorithm_tc)
-{
- return mavlink_msg_set_algorithm_tc_pack_chan(system_id, component_id, chan, msg, set_algorithm_tc->algorithm_number);
-}
-
-/**
- * @brief Send a set_algorithm_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param algorithm_number Algorithm number
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_algorithm_tc_send(mavlink_channel_t chan, uint8_t algorithm_number)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN];
- _mav_put_uint8_t(buf, 0, algorithm_number);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ALGORITHM_TC, buf, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-#else
- mavlink_set_algorithm_tc_t packet;
- packet.algorithm_number = algorithm_number;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ALGORITHM_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_algorithm_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_algorithm_tc_send_struct(mavlink_channel_t chan, const mavlink_set_algorithm_tc_t* set_algorithm_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_algorithm_tc_send(chan, set_algorithm_tc->algorithm_number);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ALGORITHM_TC, (const char *)set_algorithm_tc, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_ALGORITHM_TC_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_algorithm_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t algorithm_number)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, algorithm_number);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ALGORITHM_TC, buf, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-#else
- mavlink_set_algorithm_tc_t *packet = (mavlink_set_algorithm_tc_t *)msgbuf;
- packet->algorithm_number = algorithm_number;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ALGORITHM_TC, (const char *)packet, MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN, MAVLINK_MSG_ID_SET_ALGORITHM_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_ALGORITHM_TC UNPACKING
-
-
-/**
- * @brief Get field algorithm_number from set_algorithm_tc message
- *
- * @return Algorithm number
- */
-static inline uint8_t mavlink_msg_set_algorithm_tc_get_algorithm_number(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a set_algorithm_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_algorithm_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_algorithm_tc_decode(const mavlink_message_t* msg, mavlink_set_algorithm_tc_t* set_algorithm_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_algorithm_tc->algorithm_number = mavlink_msg_set_algorithm_tc_get_algorithm_number(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN;
- memset(set_algorithm_tc, 0, MAVLINK_MSG_ID_SET_ALGORITHM_TC_LEN);
- memcpy(set_algorithm_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_set_coordinates_tc.h b/mavlink_lib/pyxis/mavlink_msg_set_coordinates_tc.h
deleted file mode 100644
index 827f0ec42e8f8ca2cc283732f06ebc1f9a966af0..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_set_coordinates_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SET_COORDINATES_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_COORDINATES_TC 12
-
-
-typedef struct __mavlink_set_coordinates_tc_t {
- float latitude; /*< [deg] Latitude*/
- float longitude; /*< [deg] Longitude*/
-} mavlink_set_coordinates_tc_t;
-
-#define MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN 8
-#define MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_12_LEN 8
-#define MAVLINK_MSG_ID_12_MIN_LEN 8
-
-#define MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC 67
-#define MAVLINK_MSG_ID_12_CRC 67
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC { \
- 12, \
- "SET_COORDINATES_TC", \
- 2, \
- { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_coordinates_tc_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_coordinates_tc_t, longitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC { \
- "SET_COORDINATES_TC", \
- 2, \
- { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_coordinates_tc_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_coordinates_tc_t, longitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_coordinates_tc 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 [deg] Latitude
- * @param longitude [deg] Longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_coordinates_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN);
-#else
- mavlink_set_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_COORDINATES_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-}
-
-/**
- * @brief Pack a set_coordinates_tc 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 [deg] Latitude
- * @param longitude [deg] Longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_coordinates_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float latitude,float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN);
-#else
- mavlink_set_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_COORDINATES_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-}
-
-/**
- * @brief Encode a set_coordinates_tc 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_coordinates_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_coordinates_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_coordinates_tc_t* set_coordinates_tc)
-{
- return mavlink_msg_set_coordinates_tc_pack(system_id, component_id, msg, set_coordinates_tc->latitude, set_coordinates_tc->longitude);
-}
-
-/**
- * @brief Encode a set_coordinates_tc 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_coordinates_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_coordinates_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_coordinates_tc_t* set_coordinates_tc)
-{
- return mavlink_msg_set_coordinates_tc_pack_chan(system_id, component_id, chan, msg, set_coordinates_tc->latitude, set_coordinates_tc->longitude);
-}
-
-/**
- * @brief Send a set_coordinates_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param latitude [deg] Latitude
- * @param longitude [deg] Longitude
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_coordinates_tc_send(mavlink_channel_t chan, float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_COORDINATES_TC, buf, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-#else
- mavlink_set_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_COORDINATES_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_coordinates_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_coordinates_tc_send_struct(mavlink_channel_t chan, const mavlink_set_coordinates_tc_t* set_coordinates_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_coordinates_tc_send(chan, set_coordinates_tc->latitude, set_coordinates_tc->longitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_COORDINATES_TC, (const char *)set_coordinates_tc, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_COORDINATES_TC_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_coordinates_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_COORDINATES_TC, buf, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-#else
- mavlink_set_coordinates_tc_t *packet = (mavlink_set_coordinates_tc_t *)msgbuf;
- packet->latitude = latitude;
- packet->longitude = longitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_COORDINATES_TC, (const char *)packet, MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_COORDINATES_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_COORDINATES_TC UNPACKING
-
-
-/**
- * @brief Get field latitude from set_coordinates_tc message
- *
- * @return [deg] Latitude
- */
-static inline float mavlink_msg_set_coordinates_tc_get_latitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Get field longitude from set_coordinates_tc message
- *
- * @return [deg] Longitude
- */
-static inline float mavlink_msg_set_coordinates_tc_get_longitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 4);
-}
-
-/**
- * @brief Decode a set_coordinates_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_coordinates_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_coordinates_tc_decode(const mavlink_message_t* msg, mavlink_set_coordinates_tc_t* set_coordinates_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_coordinates_tc->latitude = mavlink_msg_set_coordinates_tc_get_latitude(msg);
- set_coordinates_tc->longitude = mavlink_msg_set_coordinates_tc_get_longitude(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN;
- memset(set_coordinates_tc, 0, MAVLINK_MSG_ID_SET_COORDINATES_TC_LEN);
- memcpy(set_coordinates_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_set_deployment_altitude_tc.h b/mavlink_lib/pyxis/mavlink_msg_set_deployment_altitude_tc.h
deleted file mode 100644
index 38c61267d4498fb5f1924eaf8a83b701d0d37677..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_set_deployment_altitude_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SET_DEPLOYMENT_ALTITUDE_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC 14
-
-
-typedef struct __mavlink_set_deployment_altitude_tc_t {
- float dpl_altitude; /*< [m] Deployment altitude*/
-} mavlink_set_deployment_altitude_tc_t;
-
-#define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN 4
-#define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN 4
-#define MAVLINK_MSG_ID_14_LEN 4
-#define MAVLINK_MSG_ID_14_MIN_LEN 4
-
-#define MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC 44
-#define MAVLINK_MSG_ID_14_CRC 44
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC { \
- 14, \
- "SET_DEPLOYMENT_ALTITUDE_TC", \
- 1, \
- { { "dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_deployment_altitude_tc_t, dpl_altitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC { \
- "SET_DEPLOYMENT_ALTITUDE_TC", \
- 1, \
- { { "dpl_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_deployment_altitude_tc_t, dpl_altitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_deployment_altitude_tc 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 dpl_altitude [m] Deployment altitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_deployment_altitude_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, dpl_altitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
-#else
- mavlink_set_deployment_altitude_tc_t packet;
- packet.dpl_altitude = dpl_altitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-}
-
-/**
- * @brief Pack a set_deployment_altitude_tc 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 dpl_altitude [m] Deployment altitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_deployment_altitude_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, dpl_altitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
-#else
- mavlink_set_deployment_altitude_tc_t packet;
- packet.dpl_altitude = dpl_altitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-}
-
-/**
- * @brief Encode a set_deployment_altitude_tc 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_deployment_altitude_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_deployment_altitude_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_deployment_altitude_tc_t* set_deployment_altitude_tc)
-{
- return mavlink_msg_set_deployment_altitude_tc_pack(system_id, component_id, msg, set_deployment_altitude_tc->dpl_altitude);
-}
-
-/**
- * @brief Encode a set_deployment_altitude_tc 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_deployment_altitude_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_deployment_altitude_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_deployment_altitude_tc_t* set_deployment_altitude_tc)
-{
- return mavlink_msg_set_deployment_altitude_tc_pack_chan(system_id, component_id, chan, msg, set_deployment_altitude_tc->dpl_altitude);
-}
-
-/**
- * @brief Send a set_deployment_altitude_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param dpl_altitude [m] Deployment altitude
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_deployment_altitude_tc_send(mavlink_channel_t chan, float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, dpl_altitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC, buf, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-#else
- mavlink_set_deployment_altitude_tc_t packet;
- packet.dpl_altitude = dpl_altitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_deployment_altitude_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_deployment_altitude_tc_send_struct(mavlink_channel_t chan, const mavlink_set_deployment_altitude_tc_t* set_deployment_altitude_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_deployment_altitude_tc_send(chan, set_deployment_altitude_tc->dpl_altitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC, (const char *)set_deployment_altitude_tc, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_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_deployment_altitude_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float dpl_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, dpl_altitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC, buf, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-#else
- mavlink_set_deployment_altitude_tc_t *packet = (mavlink_set_deployment_altitude_tc_t *)msgbuf;
- packet->dpl_altitude = dpl_altitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC, (const char *)packet, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_DEPLOYMENT_ALTITUDE_TC UNPACKING
-
-
-/**
- * @brief Get field dpl_altitude from set_deployment_altitude_tc message
- *
- * @return [m] Deployment altitude
- */
-static inline float mavlink_msg_set_deployment_altitude_tc_get_dpl_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a set_deployment_altitude_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_deployment_altitude_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_deployment_altitude_tc_decode(const mavlink_message_t* msg, mavlink_set_deployment_altitude_tc_t* set_deployment_altitude_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_deployment_altitude_tc->dpl_altitude = mavlink_msg_set_deployment_altitude_tc_get_dpl_altitude(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN;
- memset(set_deployment_altitude_tc, 0, MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_LEN);
- memcpy(set_deployment_altitude_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_set_orientation_tc.h b/mavlink_lib/pyxis/mavlink_msg_set_orientation_tc.h
deleted file mode 100644
index 5169814cd4c7a7afbe6e204bf82fb2d049078fc7..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_set_orientation_tc.h
+++ /dev/null
@@ -1,263 +0,0 @@
-#pragma once
-// MESSAGE SET_ORIENTATION_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_ORIENTATION_TC 11
-
-
-typedef struct __mavlink_set_orientation_tc_t {
- float yaw; /*< [deg] Yaw angle*/
- float pitch; /*< [deg] Pitch angle*/
- float roll; /*< [deg] Roll angle*/
-} mavlink_set_orientation_tc_t;
-
-#define MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN 12
-#define MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN 12
-#define MAVLINK_MSG_ID_11_LEN 12
-#define MAVLINK_MSG_ID_11_MIN_LEN 12
-
-#define MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC 71
-#define MAVLINK_MSG_ID_11_CRC 71
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC { \
- 11, \
- "SET_ORIENTATION_TC", \
- 3, \
- { { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_orientation_tc_t, yaw) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_orientation_tc_t, pitch) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_orientation_tc_t, roll) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC { \
- "SET_ORIENTATION_TC", \
- 3, \
- { { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_orientation_tc_t, yaw) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_orientation_tc_t, pitch) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_orientation_tc_t, roll) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_orientation_tc 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 yaw [deg] Yaw angle
- * @param pitch [deg] Pitch angle
- * @param roll [deg] Roll angle
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_orientation_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float yaw, float pitch, float roll)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN];
- _mav_put_float(buf, 0, yaw);
- _mav_put_float(buf, 4, pitch);
- _mav_put_float(buf, 8, roll);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN);
-#else
- mavlink_set_orientation_tc_t packet;
- packet.yaw = yaw;
- packet.pitch = pitch;
- packet.roll = roll;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_ORIENTATION_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-}
-
-/**
- * @brief Pack a set_orientation_tc 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 yaw [deg] Yaw angle
- * @param pitch [deg] Pitch angle
- * @param roll [deg] Roll angle
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_orientation_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float yaw,float pitch,float roll)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN];
- _mav_put_float(buf, 0, yaw);
- _mav_put_float(buf, 4, pitch);
- _mav_put_float(buf, 8, roll);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN);
-#else
- mavlink_set_orientation_tc_t packet;
- packet.yaw = yaw;
- packet.pitch = pitch;
- packet.roll = roll;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_ORIENTATION_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-}
-
-/**
- * @brief Encode a set_orientation_tc 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_orientation_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_orientation_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_orientation_tc_t* set_orientation_tc)
-{
- return mavlink_msg_set_orientation_tc_pack(system_id, component_id, msg, set_orientation_tc->yaw, set_orientation_tc->pitch, set_orientation_tc->roll);
-}
-
-/**
- * @brief Encode a set_orientation_tc 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_orientation_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_orientation_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_orientation_tc_t* set_orientation_tc)
-{
- return mavlink_msg_set_orientation_tc_pack_chan(system_id, component_id, chan, msg, set_orientation_tc->yaw, set_orientation_tc->pitch, set_orientation_tc->roll);
-}
-
-/**
- * @brief Send a set_orientation_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param yaw [deg] Yaw angle
- * @param pitch [deg] Pitch angle
- * @param roll [deg] Roll angle
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_orientation_tc_send(mavlink_channel_t chan, float yaw, float pitch, float roll)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN];
- _mav_put_float(buf, 0, yaw);
- _mav_put_float(buf, 4, pitch);
- _mav_put_float(buf, 8, roll);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ORIENTATION_TC, buf, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-#else
- mavlink_set_orientation_tc_t packet;
- packet.yaw = yaw;
- packet.pitch = pitch;
- packet.roll = roll;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ORIENTATION_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_orientation_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_orientation_tc_send_struct(mavlink_channel_t chan, const mavlink_set_orientation_tc_t* set_orientation_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_orientation_tc_send(chan, set_orientation_tc->yaw, set_orientation_tc->pitch, set_orientation_tc->roll);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ORIENTATION_TC, (const char *)set_orientation_tc, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_ORIENTATION_TC_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_orientation_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float yaw, float pitch, float roll)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, yaw);
- _mav_put_float(buf, 4, pitch);
- _mav_put_float(buf, 8, roll);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ORIENTATION_TC, buf, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-#else
- mavlink_set_orientation_tc_t *packet = (mavlink_set_orientation_tc_t *)msgbuf;
- packet->yaw = yaw;
- packet->pitch = pitch;
- packet->roll = roll;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ORIENTATION_TC, (const char *)packet, MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN, MAVLINK_MSG_ID_SET_ORIENTATION_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_ORIENTATION_TC UNPACKING
-
-
-/**
- * @brief Get field yaw from set_orientation_tc message
- *
- * @return [deg] Yaw angle
- */
-static inline float mavlink_msg_set_orientation_tc_get_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Get field pitch from set_orientation_tc message
- *
- * @return [deg] Pitch angle
- */
-static inline float mavlink_msg_set_orientation_tc_get_pitch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 4);
-}
-
-/**
- * @brief Get field roll from set_orientation_tc message
- *
- * @return [deg] Roll angle
- */
-static inline float mavlink_msg_set_orientation_tc_get_roll(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Decode a set_orientation_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_orientation_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_orientation_tc_decode(const mavlink_message_t* msg, mavlink_set_orientation_tc_t* set_orientation_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_orientation_tc->yaw = mavlink_msg_set_orientation_tc_get_yaw(msg);
- set_orientation_tc->pitch = mavlink_msg_set_orientation_tc_get_pitch(msg);
- set_orientation_tc->roll = mavlink_msg_set_orientation_tc_get_roll(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN;
- memset(set_orientation_tc, 0, MAVLINK_MSG_ID_SET_ORIENTATION_TC_LEN);
- memcpy(set_orientation_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_set_reference_altitude_tc.h b/mavlink_lib/pyxis/mavlink_msg_set_reference_altitude_tc.h
deleted file mode 100644
index a291b0b8da0d1d60e7e30767ade22abc5f35402a..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_set_reference_altitude_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SET_REFERENCE_ALTITUDE_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC 9
-
-
-typedef struct __mavlink_set_reference_altitude_tc_t {
- float ref_altitude; /*< [m] Reference altitude*/
-} mavlink_set_reference_altitude_tc_t;
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN 4
-#define MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN 4
-#define MAVLINK_MSG_ID_9_LEN 4
-#define MAVLINK_MSG_ID_9_MIN_LEN 4
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC 113
-#define MAVLINK_MSG_ID_9_CRC 113
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC { \
- 9, \
- "SET_REFERENCE_ALTITUDE_TC", \
- 1, \
- { { "ref_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_reference_altitude_tc_t, ref_altitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC { \
- "SET_REFERENCE_ALTITUDE_TC", \
- 1, \
- { { "ref_altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_reference_altitude_tc_t, ref_altitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_reference_altitude_tc 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 ref_altitude [m] Reference altitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_reference_altitude_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float ref_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, ref_altitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN);
-#else
- mavlink_set_reference_altitude_tc_t packet;
- packet.ref_altitude = ref_altitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-}
-
-/**
- * @brief Pack a set_reference_altitude_tc 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 ref_altitude [m] Reference altitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_reference_altitude_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float ref_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, ref_altitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN);
-#else
- mavlink_set_reference_altitude_tc_t packet;
- packet.ref_altitude = ref_altitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-}
-
-/**
- * @brief Encode a set_reference_altitude_tc 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_reference_altitude_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_reference_altitude_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_reference_altitude_tc_t* set_reference_altitude_tc)
-{
- return mavlink_msg_set_reference_altitude_tc_pack(system_id, component_id, msg, set_reference_altitude_tc->ref_altitude);
-}
-
-/**
- * @brief Encode a set_reference_altitude_tc 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_reference_altitude_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_reference_altitude_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_reference_altitude_tc_t* set_reference_altitude_tc)
-{
- return mavlink_msg_set_reference_altitude_tc_pack_chan(system_id, component_id, chan, msg, set_reference_altitude_tc->ref_altitude);
-}
-
-/**
- * @brief Send a set_reference_altitude_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param ref_altitude [m] Reference altitude
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_reference_altitude_tc_send(mavlink_channel_t chan, float ref_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN];
- _mav_put_float(buf, 0, ref_altitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC, buf, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-#else
- mavlink_set_reference_altitude_tc_t packet;
- packet.ref_altitude = ref_altitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_reference_altitude_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_reference_altitude_tc_send_struct(mavlink_channel_t chan, const mavlink_set_reference_altitude_tc_t* set_reference_altitude_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_reference_altitude_tc_send(chan, set_reference_altitude_tc->ref_altitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC, (const char *)set_reference_altitude_tc, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_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_reference_altitude_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float ref_altitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, ref_altitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC, buf, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-#else
- mavlink_set_reference_altitude_tc_t *packet = (mavlink_set_reference_altitude_tc_t *)msgbuf;
- packet->ref_altitude = ref_altitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC, (const char *)packet, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_REFERENCE_ALTITUDE_TC UNPACKING
-
-
-/**
- * @brief Get field ref_altitude from set_reference_altitude_tc message
- *
- * @return [m] Reference altitude
- */
-static inline float mavlink_msg_set_reference_altitude_tc_get_ref_altitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a set_reference_altitude_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_reference_altitude_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_reference_altitude_tc_decode(const mavlink_message_t* msg, mavlink_set_reference_altitude_tc_t* set_reference_altitude_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_reference_altitude_tc->ref_altitude = mavlink_msg_set_reference_altitude_tc_get_ref_altitude(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN;
- memset(set_reference_altitude_tc, 0, MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_LEN);
- memcpy(set_reference_altitude_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_set_reference_temperature_tc.h b/mavlink_lib/pyxis/mavlink_msg_set_reference_temperature_tc.h
deleted file mode 100644
index 5bb1c529477606617b93eca65726e9580259f832..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_set_reference_temperature_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SET_REFERENCE_TEMPERATURE_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC 10
-
-
-typedef struct __mavlink_set_reference_temperature_tc_t {
- float ref_temp; /*< [degC] Reference temperature*/
-} mavlink_set_reference_temperature_tc_t;
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN 4
-#define MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN 4
-#define MAVLINK_MSG_ID_10_LEN 4
-#define MAVLINK_MSG_ID_10_MIN_LEN 4
-
-#define MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC 38
-#define MAVLINK_MSG_ID_10_CRC 38
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC { \
- 10, \
- "SET_REFERENCE_TEMPERATURE_TC", \
- 1, \
- { { "ref_temp", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_reference_temperature_tc_t, ref_temp) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC { \
- "SET_REFERENCE_TEMPERATURE_TC", \
- 1, \
- { { "ref_temp", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_reference_temperature_tc_t, ref_temp) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_reference_temperature_tc 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 ref_temp [degC] Reference temperature
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_reference_temperature_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float ref_temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN];
- _mav_put_float(buf, 0, ref_temp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
-#else
- mavlink_set_reference_temperature_tc_t packet;
- packet.ref_temp = ref_temp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-}
-
-/**
- * @brief Pack a set_reference_temperature_tc 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 ref_temp [degC] Reference temperature
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_reference_temperature_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float ref_temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN];
- _mav_put_float(buf, 0, ref_temp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
-#else
- mavlink_set_reference_temperature_tc_t packet;
- packet.ref_temp = ref_temp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-}
-
-/**
- * @brief Encode a set_reference_temperature_tc 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_reference_temperature_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_reference_temperature_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_reference_temperature_tc_t* set_reference_temperature_tc)
-{
- return mavlink_msg_set_reference_temperature_tc_pack(system_id, component_id, msg, set_reference_temperature_tc->ref_temp);
-}
-
-/**
- * @brief Encode a set_reference_temperature_tc 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_reference_temperature_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_reference_temperature_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_reference_temperature_tc_t* set_reference_temperature_tc)
-{
- return mavlink_msg_set_reference_temperature_tc_pack_chan(system_id, component_id, chan, msg, set_reference_temperature_tc->ref_temp);
-}
-
-/**
- * @brief Send a set_reference_temperature_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param ref_temp [degC] Reference temperature
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_reference_temperature_tc_send(mavlink_channel_t chan, float ref_temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN];
- _mav_put_float(buf, 0, ref_temp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC, buf, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-#else
- mavlink_set_reference_temperature_tc_t packet;
- packet.ref_temp = ref_temp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_reference_temperature_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_reference_temperature_tc_send_struct(mavlink_channel_t chan, const mavlink_set_reference_temperature_tc_t* set_reference_temperature_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_reference_temperature_tc_send(chan, set_reference_temperature_tc->ref_temp);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC, (const char *)set_reference_temperature_tc, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_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_reference_temperature_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float ref_temp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, ref_temp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC, buf, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-#else
- mavlink_set_reference_temperature_tc_t *packet = (mavlink_set_reference_temperature_tc_t *)msgbuf;
- packet->ref_temp = ref_temp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC, (const char *)packet, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_REFERENCE_TEMPERATURE_TC UNPACKING
-
-
-/**
- * @brief Get field ref_temp from set_reference_temperature_tc message
- *
- * @return [degC] Reference temperature
- */
-static inline float mavlink_msg_set_reference_temperature_tc_get_ref_temp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a set_reference_temperature_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_reference_temperature_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_reference_temperature_tc_decode(const mavlink_message_t* msg, mavlink_set_reference_temperature_tc_t* set_reference_temperature_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_reference_temperature_tc->ref_temp = mavlink_msg_set_reference_temperature_tc_get_ref_temp(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN;
- memset(set_reference_temperature_tc, 0, MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_LEN);
- memcpy(set_reference_temperature_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_set_servo_angle_tc.h b/mavlink_lib/pyxis/mavlink_msg_set_servo_angle_tc.h
deleted file mode 100644
index a9e3fa6e354c97e420ba4a778f8e11dc9c9c0848..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_set_servo_angle_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SET_SERVO_ANGLE_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC 6
-
-
-typedef struct __mavlink_set_servo_angle_tc_t {
- float angle; /*< [deg] Servo angle*/
- uint8_t servo_id; /*< A member of the ServosList enum*/
-} mavlink_set_servo_angle_tc_t;
-
-#define MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN 5
-#define MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN 5
-#define MAVLINK_MSG_ID_6_LEN 5
-#define MAVLINK_MSG_ID_6_MIN_LEN 5
-
-#define MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC 215
-#define MAVLINK_MSG_ID_6_CRC 215
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC { \
- 6, \
- "SET_SERVO_ANGLE_TC", \
- 2, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_servo_angle_tc_t, servo_id) }, \
- { "angle", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_servo_angle_tc_t, angle) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC { \
- "SET_SERVO_ANGLE_TC", \
- 2, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_servo_angle_tc_t, servo_id) }, \
- { "angle", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_servo_angle_tc_t, angle) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_servo_angle_tc 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 servo_id A member of the ServosList enum
- * @param angle [deg] Servo angle
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_servo_angle_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t servo_id, float angle)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN];
- _mav_put_float(buf, 0, angle);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN);
-#else
- mavlink_set_servo_angle_tc_t packet;
- packet.angle = angle;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-}
-
-/**
- * @brief Pack a set_servo_angle_tc 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 servo_id A member of the ServosList enum
- * @param angle [deg] Servo angle
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_servo_angle_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t servo_id,float angle)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN];
- _mav_put_float(buf, 0, angle);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN);
-#else
- mavlink_set_servo_angle_tc_t packet;
- packet.angle = angle;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-}
-
-/**
- * @brief Encode a set_servo_angle_tc 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_servo_angle_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_servo_angle_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_servo_angle_tc_t* set_servo_angle_tc)
-{
- return mavlink_msg_set_servo_angle_tc_pack(system_id, component_id, msg, set_servo_angle_tc->servo_id, set_servo_angle_tc->angle);
-}
-
-/**
- * @brief Encode a set_servo_angle_tc 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_servo_angle_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_servo_angle_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_servo_angle_tc_t* set_servo_angle_tc)
-{
- return mavlink_msg_set_servo_angle_tc_pack_chan(system_id, component_id, chan, msg, set_servo_angle_tc->servo_id, set_servo_angle_tc->angle);
-}
-
-/**
- * @brief Send a set_servo_angle_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param servo_id A member of the ServosList enum
- * @param angle [deg] Servo angle
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_servo_angle_tc_send(mavlink_channel_t chan, uint8_t servo_id, float angle)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN];
- _mav_put_float(buf, 0, angle);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC, buf, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-#else
- mavlink_set_servo_angle_tc_t packet;
- packet.angle = angle;
- packet.servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_servo_angle_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_servo_angle_tc_send_struct(mavlink_channel_t chan, const mavlink_set_servo_angle_tc_t* set_servo_angle_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_servo_angle_tc_send(chan, set_servo_angle_tc->servo_id, set_servo_angle_tc->angle);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC, (const char *)set_servo_angle_tc, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_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_servo_angle_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t servo_id, float angle)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, angle);
- _mav_put_uint8_t(buf, 4, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC, buf, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-#else
- mavlink_set_servo_angle_tc_t *packet = (mavlink_set_servo_angle_tc_t *)msgbuf;
- packet->angle = angle;
- packet->servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC, (const char *)packet, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_SERVO_ANGLE_TC UNPACKING
-
-
-/**
- * @brief Get field servo_id from set_servo_angle_tc message
- *
- * @return A member of the ServosList enum
- */
-static inline uint8_t mavlink_msg_set_servo_angle_tc_get_servo_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 4);
-}
-
-/**
- * @brief Get field angle from set_servo_angle_tc message
- *
- * @return [deg] Servo angle
- */
-static inline float mavlink_msg_set_servo_angle_tc_get_angle(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Decode a set_servo_angle_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_servo_angle_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_servo_angle_tc_decode(const mavlink_message_t* msg, mavlink_set_servo_angle_tc_t* set_servo_angle_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_servo_angle_tc->angle = mavlink_msg_set_servo_angle_tc_get_angle(msg);
- set_servo_angle_tc->servo_id = mavlink_msg_set_servo_angle_tc_get_servo_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN;
- memset(set_servo_angle_tc, 0, MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_LEN);
- memcpy(set_servo_angle_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_set_target_coordinates_tc.h b/mavlink_lib/pyxis/mavlink_msg_set_target_coordinates_tc.h
deleted file mode 100644
index 40394b728f76ebb99dfb689a467c28474a457fee..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_set_target_coordinates_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE SET_TARGET_COORDINATES_TC PACKING
-
-#define MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC 15
-
-
-typedef struct __mavlink_set_target_coordinates_tc_t {
- float latitude; /*< [deg] Latitude*/
- float longitude; /*< [deg] Longitude*/
-} mavlink_set_target_coordinates_tc_t;
-
-#define MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN 8
-#define MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_15_LEN 8
-#define MAVLINK_MSG_ID_15_MIN_LEN 8
-
-#define MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC 81
-#define MAVLINK_MSG_ID_15_CRC 81
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC { \
- 15, \
- "SET_TARGET_COORDINATES_TC", \
- 2, \
- { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_target_coordinates_tc_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_target_coordinates_tc_t, longitude) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC { \
- "SET_TARGET_COORDINATES_TC", \
- 2, \
- { { "latitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_target_coordinates_tc_t, latitude) }, \
- { "longitude", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_target_coordinates_tc_t, longitude) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a set_target_coordinates_tc 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 [deg] Latitude
- * @param longitude [deg] Longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_target_coordinates_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN);
-#else
- mavlink_set_target_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-}
-
-/**
- * @brief Pack a set_target_coordinates_tc 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 [deg] Latitude
- * @param longitude [deg] Longitude
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_target_coordinates_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float latitude,float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN);
-#else
- mavlink_set_target_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-}
-
-/**
- * @brief Encode a set_target_coordinates_tc 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_target_coordinates_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_target_coordinates_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_target_coordinates_tc_t* set_target_coordinates_tc)
-{
- return mavlink_msg_set_target_coordinates_tc_pack(system_id, component_id, msg, set_target_coordinates_tc->latitude, set_target_coordinates_tc->longitude);
-}
-
-/**
- * @brief Encode a set_target_coordinates_tc 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_target_coordinates_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_target_coordinates_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_target_coordinates_tc_t* set_target_coordinates_tc)
-{
- return mavlink_msg_set_target_coordinates_tc_pack_chan(system_id, component_id, chan, msg, set_target_coordinates_tc->latitude, set_target_coordinates_tc->longitude);
-}
-
-/**
- * @brief Send a set_target_coordinates_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param latitude [deg] Latitude
- * @param longitude [deg] Longitude
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_target_coordinates_tc_send(mavlink_channel_t chan, float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN];
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC, buf, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-#else
- mavlink_set_target_coordinates_tc_t packet;
- packet.latitude = latitude;
- packet.longitude = longitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a set_target_coordinates_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_set_target_coordinates_tc_send_struct(mavlink_channel_t chan, const mavlink_set_target_coordinates_tc_t* set_target_coordinates_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_target_coordinates_tc_send(chan, set_target_coordinates_tc->latitude, set_target_coordinates_tc->longitude);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC, (const char *)set_target_coordinates_tc, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_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_target_coordinates_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float latitude, float longitude)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_float(buf, 0, latitude);
- _mav_put_float(buf, 4, longitude);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC, buf, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-#else
- mavlink_set_target_coordinates_tc_t *packet = (mavlink_set_target_coordinates_tc_t *)msgbuf;
- packet->latitude = latitude;
- packet->longitude = longitude;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC, (const char *)packet, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SET_TARGET_COORDINATES_TC UNPACKING
-
-
-/**
- * @brief Get field latitude from set_target_coordinates_tc message
- *
- * @return [deg] Latitude
- */
-static inline float mavlink_msg_set_target_coordinates_tc_get_latitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Get field longitude from set_target_coordinates_tc message
- *
- * @return [deg] Longitude
- */
-static inline float mavlink_msg_set_target_coordinates_tc_get_longitude(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 4);
-}
-
-/**
- * @brief Decode a set_target_coordinates_tc message into a struct
- *
- * @param msg The message to decode
- * @param set_target_coordinates_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_target_coordinates_tc_decode(const mavlink_message_t* msg, mavlink_set_target_coordinates_tc_t* set_target_coordinates_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_target_coordinates_tc->latitude = mavlink_msg_set_target_coordinates_tc_get_latitude(msg);
- set_target_coordinates_tc->longitude = mavlink_msg_set_target_coordinates_tc_get_longitude(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN;
- memset(set_target_coordinates_tc, 0, MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_LEN);
- memcpy(set_target_coordinates_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_sys_tm.h b/mavlink_lib/pyxis/mavlink_msg_sys_tm.h
deleted file mode 100644
index 460e076f05dcf8b83836d80a887f0c77b074c517..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_sys_tm.h
+++ /dev/null
@@ -1,363 +0,0 @@
-#pragma once
-// MESSAGE SYS_TM PACKING
-
-#define MAVLINK_MSG_ID_SYS_TM 200
-
-
-typedef struct __mavlink_sys_tm_t {
- uint64_t timestamp; /*< [us] Timestamp*/
- uint8_t logger; /*< True if the logger started correctly*/
- uint8_t event_broker; /*< True if the event broker started correctly*/
- uint8_t radio; /*< True if the radio started correctly*/
- uint8_t pin_observer; /*< True if the pin observer started correctly*/
- uint8_t sensors; /*< True if the sensors started correctly*/
- uint8_t board_scheduler; /*< True if the board scheduler is running*/
-} mavlink_sys_tm_t;
-
-#define MAVLINK_MSG_ID_SYS_TM_LEN 14
-#define MAVLINK_MSG_ID_SYS_TM_MIN_LEN 14
-#define MAVLINK_MSG_ID_200_LEN 14
-#define MAVLINK_MSG_ID_200_MIN_LEN 14
-
-#define MAVLINK_MSG_ID_SYS_TM_CRC 183
-#define MAVLINK_MSG_ID_200_CRC 183
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SYS_TM { \
- 200, \
- "SYS_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_sys_tm_t, timestamp) }, \
- { "logger", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_sys_tm_t, logger) }, \
- { "event_broker", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_sys_tm_t, event_broker) }, \
- { "radio", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_sys_tm_t, radio) }, \
- { "pin_observer", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_sys_tm_t, pin_observer) }, \
- { "sensors", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_sys_tm_t, sensors) }, \
- { "board_scheduler", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_sys_tm_t, board_scheduler) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SYS_TM { \
- "SYS_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_sys_tm_t, timestamp) }, \
- { "logger", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_sys_tm_t, logger) }, \
- { "event_broker", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_sys_tm_t, event_broker) }, \
- { "radio", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_sys_tm_t, radio) }, \
- { "pin_observer", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_sys_tm_t, pin_observer) }, \
- { "sensors", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_sys_tm_t, sensors) }, \
- { "board_scheduler", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_sys_tm_t, board_scheduler) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a sys_tm 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
- * @param logger True if the logger started correctly
- * @param event_broker True if the event broker started correctly
- * @param radio True if the radio started correctly
- * @param pin_observer True if the pin observer started correctly
- * @param sensors True if the sensors started correctly
- * @param board_scheduler True if the board scheduler is running
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sys_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t logger, uint8_t event_broker, uint8_t radio, uint8_t pin_observer, uint8_t sensors, uint8_t board_scheduler)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, logger);
- _mav_put_uint8_t(buf, 9, event_broker);
- _mav_put_uint8_t(buf, 10, radio);
- _mav_put_uint8_t(buf, 11, pin_observer);
- _mav_put_uint8_t(buf, 12, sensors);
- _mav_put_uint8_t(buf, 13, board_scheduler);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_TM_LEN);
-#else
- mavlink_sys_tm_t packet;
- packet.timestamp = timestamp;
- packet.logger = logger;
- packet.event_broker = event_broker;
- packet.radio = radio;
- packet.pin_observer = pin_observer;
- packet.sensors = sensors;
- packet.board_scheduler = board_scheduler;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SYS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-}
-
-/**
- * @brief Pack a sys_tm 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
- * @param logger True if the logger started correctly
- * @param event_broker True if the event broker started correctly
- * @param radio True if the radio started correctly
- * @param pin_observer True if the pin observer started correctly
- * @param sensors True if the sensors started correctly
- * @param board_scheduler True if the board scheduler is running
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_sys_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t logger,uint8_t event_broker,uint8_t radio,uint8_t pin_observer,uint8_t sensors,uint8_t board_scheduler)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, logger);
- _mav_put_uint8_t(buf, 9, event_broker);
- _mav_put_uint8_t(buf, 10, radio);
- _mav_put_uint8_t(buf, 11, pin_observer);
- _mav_put_uint8_t(buf, 12, sensors);
- _mav_put_uint8_t(buf, 13, board_scheduler);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_TM_LEN);
-#else
- mavlink_sys_tm_t packet;
- packet.timestamp = timestamp;
- packet.logger = logger;
- packet.event_broker = event_broker;
- packet.radio = radio;
- packet.pin_observer = pin_observer;
- packet.sensors = sensors;
- packet.board_scheduler = board_scheduler;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SYS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-}
-
-/**
- * @brief Encode a sys_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sys_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_tm_t* sys_tm)
-{
- return mavlink_msg_sys_tm_pack(system_id, component_id, msg, sys_tm->timestamp, sys_tm->logger, sys_tm->event_broker, sys_tm->radio, sys_tm->pin_observer, sys_tm->sensors, sys_tm->board_scheduler);
-}
-
-/**
- * @brief Encode a sys_tm 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_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_sys_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sys_tm_t* sys_tm)
-{
- return mavlink_msg_sys_tm_pack_chan(system_id, component_id, chan, msg, sys_tm->timestamp, sys_tm->logger, sys_tm->event_broker, sys_tm->radio, sys_tm->pin_observer, sys_tm->sensors, sys_tm->board_scheduler);
-}
-
-/**
- * @brief Send a sys_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] Timestamp
- * @param logger True if the logger started correctly
- * @param event_broker True if the event broker started correctly
- * @param radio True if the radio started correctly
- * @param pin_observer True if the pin observer started correctly
- * @param sensors True if the sensors started correctly
- * @param board_scheduler True if the board scheduler is running
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_sys_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t logger, uint8_t event_broker, uint8_t radio, uint8_t pin_observer, uint8_t sensors, uint8_t board_scheduler)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, logger);
- _mav_put_uint8_t(buf, 9, event_broker);
- _mav_put_uint8_t(buf, 10, radio);
- _mav_put_uint8_t(buf, 11, pin_observer);
- _mav_put_uint8_t(buf, 12, sensors);
- _mav_put_uint8_t(buf, 13, board_scheduler);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, buf, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#else
- mavlink_sys_tm_t packet;
- packet.timestamp = timestamp;
- packet.logger = logger;
- packet.event_broker = event_broker;
- packet.radio = radio;
- packet.pin_observer = pin_observer;
- packet.sensors = sensors;
- packet.board_scheduler = board_scheduler;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, (const char *)&packet, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a sys_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_sys_tm_send_struct(mavlink_channel_t chan, const mavlink_sys_tm_t* sys_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_sys_tm_send(chan, sys_tm->timestamp, sys_tm->logger, sys_tm->event_broker, sys_tm->radio, sys_tm->pin_observer, sys_tm->sensors, sys_tm->board_scheduler);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, (const char *)sys_tm, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SYS_TM_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_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t logger, uint8_t event_broker, uint8_t radio, uint8_t pin_observer, uint8_t sensors, uint8_t board_scheduler)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint8_t(buf, 8, logger);
- _mav_put_uint8_t(buf, 9, event_broker);
- _mav_put_uint8_t(buf, 10, radio);
- _mav_put_uint8_t(buf, 11, pin_observer);
- _mav_put_uint8_t(buf, 12, sensors);
- _mav_put_uint8_t(buf, 13, board_scheduler);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, buf, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#else
- mavlink_sys_tm_t *packet = (mavlink_sys_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->logger = logger;
- packet->event_broker = event_broker;
- packet->radio = radio;
- packet->pin_observer = pin_observer;
- packet->sensors = sensors;
- packet->board_scheduler = board_scheduler;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_TM, (const char *)packet, MAVLINK_MSG_ID_SYS_TM_MIN_LEN, MAVLINK_MSG_ID_SYS_TM_LEN, MAVLINK_MSG_ID_SYS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SYS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from sys_tm message
- *
- * @return [us] Timestamp
- */
-static inline uint64_t mavlink_msg_sys_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field logger from sys_tm message
- *
- * @return True if the logger started correctly
- */
-static inline uint8_t mavlink_msg_sys_tm_get_logger(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 8);
-}
-
-/**
- * @brief Get field event_broker from sys_tm message
- *
- * @return True if the event broker started correctly
- */
-static inline uint8_t mavlink_msg_sys_tm_get_event_broker(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 9);
-}
-
-/**
- * @brief Get field radio from sys_tm message
- *
- * @return True if the radio started correctly
- */
-static inline uint8_t mavlink_msg_sys_tm_get_radio(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 10);
-}
-
-/**
- * @brief Get field pin_observer from sys_tm message
- *
- * @return True if the pin observer started correctly
- */
-static inline uint8_t mavlink_msg_sys_tm_get_pin_observer(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 11);
-}
-
-/**
- * @brief Get field sensors from sys_tm message
- *
- * @return True if the sensors started correctly
- */
-static inline uint8_t mavlink_msg_sys_tm_get_sensors(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 12);
-}
-
-/**
- * @brief Get field board_scheduler from sys_tm message
- *
- * @return True if the board scheduler is running
- */
-static inline uint8_t mavlink_msg_sys_tm_get_board_scheduler(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 13);
-}
-
-/**
- * @brief Decode a sys_tm message into a struct
- *
- * @param msg The message to decode
- * @param sys_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_sys_tm_decode(const mavlink_message_t* msg, mavlink_sys_tm_t* sys_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- sys_tm->timestamp = mavlink_msg_sys_tm_get_timestamp(msg);
- sys_tm->logger = mavlink_msg_sys_tm_get_logger(msg);
- sys_tm->event_broker = mavlink_msg_sys_tm_get_event_broker(msg);
- sys_tm->radio = mavlink_msg_sys_tm_get_radio(msg);
- sys_tm->pin_observer = mavlink_msg_sys_tm_get_pin_observer(msg);
- sys_tm->sensors = mavlink_msg_sys_tm_get_sensors(msg);
- sys_tm->board_scheduler = mavlink_msg_sys_tm_get_board_scheduler(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SYS_TM_LEN? msg->len : MAVLINK_MSG_ID_SYS_TM_LEN;
- memset(sys_tm, 0, MAVLINK_MSG_ID_SYS_TM_LEN);
- memcpy(sys_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_system_tm_request_tc.h b/mavlink_lib/pyxis/mavlink_msg_system_tm_request_tc.h
deleted file mode 100644
index de5a083eed2404c27df5ad34524fcac401fe3b6f..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_system_tm_request_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE SYSTEM_TM_REQUEST_TC PACKING
-
-#define MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC 3
-
-
-typedef struct __mavlink_system_tm_request_tc_t {
- uint8_t tm_id; /*< A member of the SystemTMList enum*/
-} mavlink_system_tm_request_tc_t;
-
-#define MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN 1
-#define MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_3_LEN 1
-#define MAVLINK_MSG_ID_3_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC 165
-#define MAVLINK_MSG_ID_3_CRC 165
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC { \
- 3, \
- "SYSTEM_TM_REQUEST_TC", \
- 1, \
- { { "tm_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_system_tm_request_tc_t, tm_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC { \
- "SYSTEM_TM_REQUEST_TC", \
- 1, \
- { { "tm_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_system_tm_request_tc_t, tm_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a system_tm_request_tc 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 tm_id A member of the SystemTMList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_system_tm_request_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t tm_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, tm_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN);
-#else
- mavlink_system_tm_request_tc_t packet;
- packet.tm_id = tm_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Pack a system_tm_request_tc 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 tm_id A member of the SystemTMList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_system_tm_request_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t tm_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, tm_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN);
-#else
- mavlink_system_tm_request_tc_t packet;
- packet.tm_id = tm_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Encode a system_tm_request_tc 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_tm_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_system_tm_request_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_tm_request_tc_t* system_tm_request_tc)
-{
- return mavlink_msg_system_tm_request_tc_pack(system_id, component_id, msg, system_tm_request_tc->tm_id);
-}
-
-/**
- * @brief Encode a system_tm_request_tc 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_tm_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_system_tm_request_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_system_tm_request_tc_t* system_tm_request_tc)
-{
- return mavlink_msg_system_tm_request_tc_pack_chan(system_id, component_id, chan, msg, system_tm_request_tc->tm_id);
-}
-
-/**
- * @brief Send a system_tm_request_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param tm_id A member of the SystemTMList enum
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_system_tm_request_tc_send(mavlink_channel_t chan, uint8_t tm_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, tm_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC, buf, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-#else
- mavlink_system_tm_request_tc_t packet;
- packet.tm_id = tm_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC, (const char *)&packet, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a system_tm_request_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_system_tm_request_tc_send_struct(mavlink_channel_t chan, const mavlink_system_tm_request_tc_t* system_tm_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_system_tm_request_tc_send(chan, system_tm_request_tc->tm_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC, (const char *)system_tm_request_tc, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_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_tm_request_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t tm_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, tm_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC, buf, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-#else
- mavlink_system_tm_request_tc_t *packet = (mavlink_system_tm_request_tc_t *)msgbuf;
- packet->tm_id = tm_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC, (const char *)packet, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE SYSTEM_TM_REQUEST_TC UNPACKING
-
-
-/**
- * @brief Get field tm_id from system_tm_request_tc message
- *
- * @return A member of the SystemTMList enum
- */
-static inline uint8_t mavlink_msg_system_tm_request_tc_get_tm_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a system_tm_request_tc message into a struct
- *
- * @param msg The message to decode
- * @param system_tm_request_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_system_tm_request_tc_decode(const mavlink_message_t* msg, mavlink_system_tm_request_tc_t* system_tm_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- system_tm_request_tc->tm_id = mavlink_msg_system_tm_request_tc_get_tm_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN? msg->len : MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN;
- memset(system_tm_request_tc, 0, MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_LEN);
- memcpy(system_tm_request_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_task_stats_tm.h b/mavlink_lib/pyxis/mavlink_msg_task_stats_tm.h
deleted file mode 100644
index 81727059a4f8f5ed68fc83870afb0b99ab064bba..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_task_stats_tm.h
+++ /dev/null
@@ -1,363 +0,0 @@
-#pragma once
-// MESSAGE TASK_STATS_TM PACKING
-
-#define MAVLINK_MSG_ID_TASK_STATS_TM 204
-
-
-typedef struct __mavlink_task_stats_tm_t {
- uint64_t timestamp; /*< [us] When was this logged */
- float task_min; /*< Task min period*/
- float task_max; /*< Task max period*/
- float task_mean; /*< Task mean period*/
- float task_stddev; /*< Task period std deviation*/
- uint16_t task_period; /*< [ms] Period of the task*/
- uint8_t task_id; /*< Task ID*/
-} mavlink_task_stats_tm_t;
-
-#define MAVLINK_MSG_ID_TASK_STATS_TM_LEN 27
-#define MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN 27
-#define MAVLINK_MSG_ID_204_LEN 27
-#define MAVLINK_MSG_ID_204_MIN_LEN 27
-
-#define MAVLINK_MSG_ID_TASK_STATS_TM_CRC 133
-#define MAVLINK_MSG_ID_204_CRC 133
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_TASK_STATS_TM { \
- 204, \
- "TASK_STATS_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_task_stats_tm_t, timestamp) }, \
- { "task_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_task_stats_tm_t, task_id) }, \
- { "task_period", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_task_stats_tm_t, task_period) }, \
- { "task_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_task_stats_tm_t, task_min) }, \
- { "task_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_task_stats_tm_t, task_max) }, \
- { "task_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_task_stats_tm_t, task_mean) }, \
- { "task_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_task_stats_tm_t, task_stddev) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_TASK_STATS_TM { \
- "TASK_STATS_TM", \
- 7, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_task_stats_tm_t, timestamp) }, \
- { "task_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_task_stats_tm_t, task_id) }, \
- { "task_period", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_task_stats_tm_t, task_period) }, \
- { "task_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_task_stats_tm_t, task_min) }, \
- { "task_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_task_stats_tm_t, task_max) }, \
- { "task_mean", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_task_stats_tm_t, task_mean) }, \
- { "task_stddev", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_task_stats_tm_t, task_stddev) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a task_stats_tm 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] When was this logged
- * @param task_id Task ID
- * @param task_period [ms] Period of the task
- * @param task_min Task min period
- * @param task_max Task max period
- * @param task_mean Task mean period
- * @param task_stddev Task period std deviation
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_task_stats_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint8_t task_id, uint16_t task_period, float task_min, float task_max, float task_mean, float task_stddev)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TASK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, task_min);
- _mav_put_float(buf, 12, task_max);
- _mav_put_float(buf, 16, task_mean);
- _mav_put_float(buf, 20, task_stddev);
- _mav_put_uint16_t(buf, 24, task_period);
- _mav_put_uint8_t(buf, 26, task_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
-#else
- mavlink_task_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.task_min = task_min;
- packet.task_max = task_max;
- packet.task_mean = task_mean;
- packet.task_stddev = task_stddev;
- packet.task_period = task_period;
- packet.task_id = task_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TASK_STATS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-}
-
-/**
- * @brief Pack a task_stats_tm 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] When was this logged
- * @param task_id Task ID
- * @param task_period [ms] Period of the task
- * @param task_min Task min period
- * @param task_max Task max period
- * @param task_mean Task mean period
- * @param task_stddev Task period std deviation
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_task_stats_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint8_t task_id,uint16_t task_period,float task_min,float task_max,float task_mean,float task_stddev)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TASK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, task_min);
- _mav_put_float(buf, 12, task_max);
- _mav_put_float(buf, 16, task_mean);
- _mav_put_float(buf, 20, task_stddev);
- _mav_put_uint16_t(buf, 24, task_period);
- _mav_put_uint8_t(buf, 26, task_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
-#else
- mavlink_task_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.task_min = task_min;
- packet.task_max = task_max;
- packet.task_mean = task_mean;
- packet.task_stddev = task_stddev;
- packet.task_period = task_period;
- packet.task_id = task_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TASK_STATS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-}
-
-/**
- * @brief Encode a task_stats_tm 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 task_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_task_stats_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_task_stats_tm_t* task_stats_tm)
-{
- return mavlink_msg_task_stats_tm_pack(system_id, component_id, msg, task_stats_tm->timestamp, task_stats_tm->task_id, task_stats_tm->task_period, task_stats_tm->task_min, task_stats_tm->task_max, task_stats_tm->task_mean, task_stats_tm->task_stddev);
-}
-
-/**
- * @brief Encode a task_stats_tm 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 task_stats_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_task_stats_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_task_stats_tm_t* task_stats_tm)
-{
- return mavlink_msg_task_stats_tm_pack_chan(system_id, component_id, chan, msg, task_stats_tm->timestamp, task_stats_tm->task_id, task_stats_tm->task_period, task_stats_tm->task_min, task_stats_tm->task_max, task_stats_tm->task_mean, task_stats_tm->task_stddev);
-}
-
-/**
- * @brief Send a task_stats_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param task_id Task ID
- * @param task_period [ms] Period of the task
- * @param task_min Task min period
- * @param task_max Task max period
- * @param task_mean Task mean period
- * @param task_stddev Task period std deviation
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_task_stats_tm_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t task_id, uint16_t task_period, float task_min, float task_max, float task_mean, float task_stddev)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TASK_STATS_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, task_min);
- _mav_put_float(buf, 12, task_max);
- _mav_put_float(buf, 16, task_mean);
- _mav_put_float(buf, 20, task_stddev);
- _mav_put_uint16_t(buf, 24, task_period);
- _mav_put_uint8_t(buf, 26, task_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, buf, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-#else
- mavlink_task_stats_tm_t packet;
- packet.timestamp = timestamp;
- packet.task_min = task_min;
- packet.task_max = task_max;
- packet.task_mean = task_mean;
- packet.task_stddev = task_stddev;
- packet.task_period = task_period;
- packet.task_id = task_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, (const char *)&packet, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a task_stats_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_task_stats_tm_send_struct(mavlink_channel_t chan, const mavlink_task_stats_tm_t* task_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_task_stats_tm_send(chan, task_stats_tm->timestamp, task_stats_tm->task_id, task_stats_tm->task_period, task_stats_tm->task_min, task_stats_tm->task_max, task_stats_tm->task_mean, task_stats_tm->task_stddev);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, (const char *)task_stats_tm, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_TASK_STATS_TM_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_task_stats_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t task_id, uint16_t task_period, float task_min, float task_max, float task_mean, float task_stddev)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, task_min);
- _mav_put_float(buf, 12, task_max);
- _mav_put_float(buf, 16, task_mean);
- _mav_put_float(buf, 20, task_stddev);
- _mav_put_uint16_t(buf, 24, task_period);
- _mav_put_uint8_t(buf, 26, task_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, buf, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-#else
- mavlink_task_stats_tm_t *packet = (mavlink_task_stats_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->task_min = task_min;
- packet->task_max = task_max;
- packet->task_mean = task_mean;
- packet->task_stddev = task_stddev;
- packet->task_period = task_period;
- packet->task_id = task_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TASK_STATS_TM, (const char *)packet, MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_LEN, MAVLINK_MSG_ID_TASK_STATS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE TASK_STATS_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from task_stats_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_task_stats_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field task_id from task_stats_tm message
- *
- * @return Task ID
- */
-static inline uint8_t mavlink_msg_task_stats_tm_get_task_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 26);
-}
-
-/**
- * @brief Get field task_period from task_stats_tm message
- *
- * @return [ms] Period of the task
- */
-static inline uint16_t mavlink_msg_task_stats_tm_get_task_period(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 24);
-}
-
-/**
- * @brief Get field task_min from task_stats_tm message
- *
- * @return Task min period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_min(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field task_max from task_stats_tm message
- *
- * @return Task max period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_max(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field task_mean from task_stats_tm message
- *
- * @return Task mean period
- */
-static inline float mavlink_msg_task_stats_tm_get_task_mean(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field task_stddev from task_stats_tm message
- *
- * @return Task period std deviation
- */
-static inline float mavlink_msg_task_stats_tm_get_task_stddev(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Decode a task_stats_tm message into a struct
- *
- * @param msg The message to decode
- * @param task_stats_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_task_stats_tm_decode(const mavlink_message_t* msg, mavlink_task_stats_tm_t* task_stats_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- task_stats_tm->timestamp = mavlink_msg_task_stats_tm_get_timestamp(msg);
- task_stats_tm->task_min = mavlink_msg_task_stats_tm_get_task_min(msg);
- task_stats_tm->task_max = mavlink_msg_task_stats_tm_get_task_max(msg);
- task_stats_tm->task_mean = mavlink_msg_task_stats_tm_get_task_mean(msg);
- task_stats_tm->task_stddev = mavlink_msg_task_stats_tm_get_task_stddev(msg);
- task_stats_tm->task_period = mavlink_msg_task_stats_tm_get_task_period(msg);
- task_stats_tm->task_id = mavlink_msg_task_stats_tm_get_task_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_TASK_STATS_TM_LEN? msg->len : MAVLINK_MSG_ID_TASK_STATS_TM_LEN;
- memset(task_stats_tm, 0, MAVLINK_MSG_ID_TASK_STATS_TM_LEN);
- memcpy(task_stats_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_temp_tm.h b/mavlink_lib/pyxis/mavlink_msg_temp_tm.h
deleted file mode 100644
index dc450285560c2685a96f542860ca99ed6a76480b..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_temp_tm.h
+++ /dev/null
@@ -1,255 +0,0 @@
-#pragma once
-// MESSAGE TEMP_TM PACKING
-
-#define MAVLINK_MSG_ID_TEMP_TM 108
-
-
-typedef struct __mavlink_temp_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float temperature; /*< [deg] Temperature*/
- char sensor_id[20]; /*< Sensor name*/
-} mavlink_temp_tm_t;
-
-#define MAVLINK_MSG_ID_TEMP_TM_LEN 32
-#define MAVLINK_MSG_ID_TEMP_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_108_LEN 32
-#define MAVLINK_MSG_ID_108_MIN_LEN 32
-
-#define MAVLINK_MSG_ID_TEMP_TM_CRC 128
-#define MAVLINK_MSG_ID_108_CRC 128
-
-#define MAVLINK_MSG_TEMP_TM_FIELD_SENSOR_ID_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_TEMP_TM { \
- 108, \
- "TEMP_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_temp_tm_t, timestamp) }, \
- { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_temp_tm_t, sensor_id) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_temp_tm_t, temperature) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_TEMP_TM { \
- "TEMP_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_temp_tm_t, timestamp) }, \
- { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_temp_tm_t, sensor_id) }, \
- { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_temp_tm_t, temperature) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a temp_tm 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] When was this logged
- * @param sensor_id Sensor name
- * @param temperature [deg] Temperature
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_temp_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_id, float temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TEMP_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, temperature);
- _mav_put_char_array(buf, 12, sensor_id, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TEMP_TM_LEN);
-#else
- mavlink_temp_tm_t packet;
- packet.timestamp = timestamp;
- packet.temperature = temperature;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TEMP_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TEMP_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-}
-
-/**
- * @brief Pack a temp_tm 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] When was this logged
- * @param sensor_id Sensor name
- * @param temperature [deg] Temperature
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_temp_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_id,float temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TEMP_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, temperature);
- _mav_put_char_array(buf, 12, sensor_id, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TEMP_TM_LEN);
-#else
- mavlink_temp_tm_t packet;
- packet.timestamp = timestamp;
- packet.temperature = temperature;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TEMP_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TEMP_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-}
-
-/**
- * @brief Encode a temp_tm 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 temp_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_temp_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_temp_tm_t* temp_tm)
-{
- return mavlink_msg_temp_tm_pack(system_id, component_id, msg, temp_tm->timestamp, temp_tm->sensor_id, temp_tm->temperature);
-}
-
-/**
- * @brief Encode a temp_tm 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 temp_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_temp_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_temp_tm_t* temp_tm)
-{
- return mavlink_msg_temp_tm_pack_chan(system_id, component_id, chan, msg, temp_tm->timestamp, temp_tm->sensor_id, temp_tm->temperature);
-}
-
-/**
- * @brief Send a temp_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_id Sensor name
- * @param temperature [deg] Temperature
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_temp_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_id, float temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TEMP_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, temperature);
- _mav_put_char_array(buf, 12, sensor_id, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEMP_TM, buf, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-#else
- mavlink_temp_tm_t packet;
- packet.timestamp = timestamp;
- packet.temperature = temperature;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEMP_TM, (const char *)&packet, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a temp_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_temp_tm_send_struct(mavlink_channel_t chan, const mavlink_temp_tm_t* temp_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_temp_tm_send(chan, temp_tm->timestamp, temp_tm->sensor_id, temp_tm->temperature);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEMP_TM, (const char *)temp_tm, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_TEMP_TM_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_temp_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_id, float temperature)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, temperature);
- _mav_put_char_array(buf, 12, sensor_id, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEMP_TM, buf, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-#else
- mavlink_temp_tm_t *packet = (mavlink_temp_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->temperature = temperature;
- mav_array_memcpy(packet->sensor_id, sensor_id, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEMP_TM, (const char *)packet, MAVLINK_MSG_ID_TEMP_TM_MIN_LEN, MAVLINK_MSG_ID_TEMP_TM_LEN, MAVLINK_MSG_ID_TEMP_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE TEMP_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from temp_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_temp_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_id from temp_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_temp_tm_get_sensor_id(const mavlink_message_t* msg, char *sensor_id)
-{
- return _MAV_RETURN_char_array(msg, sensor_id, 20, 12);
-}
-
-/**
- * @brief Get field temperature from temp_tm message
- *
- * @return [deg] Temperature
- */
-static inline float mavlink_msg_temp_tm_get_temperature(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Decode a temp_tm message into a struct
- *
- * @param msg The message to decode
- * @param temp_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_temp_tm_decode(const mavlink_message_t* msg, mavlink_temp_tm_t* temp_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- temp_tm->timestamp = mavlink_msg_temp_tm_get_timestamp(msg);
- temp_tm->temperature = mavlink_msg_temp_tm_get_temperature(msg);
- mavlink_msg_temp_tm_get_sensor_id(msg, temp_tm->sensor_id);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_TEMP_TM_LEN? msg->len : MAVLINK_MSG_ID_TEMP_TM_LEN;
- memset(temp_tm, 0, MAVLINK_MSG_ID_TEMP_TM_LEN);
- memcpy(temp_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_voltage_tm.h b/mavlink_lib/pyxis/mavlink_msg_voltage_tm.h
deleted file mode 100644
index 3bb29bbd930b48890bf741a4670e767e5f9eb9f3..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_voltage_tm.h
+++ /dev/null
@@ -1,255 +0,0 @@
-#pragma once
-// MESSAGE VOLTAGE_TM PACKING
-
-#define MAVLINK_MSG_ID_VOLTAGE_TM 106
-
-
-typedef struct __mavlink_voltage_tm_t {
- uint64_t timestamp; /*< [us] When was this logged*/
- float voltage; /*< [V] Voltage*/
- char sensor_id[20]; /*< Sensor name*/
-} mavlink_voltage_tm_t;
-
-#define MAVLINK_MSG_ID_VOLTAGE_TM_LEN 32
-#define MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN 32
-#define MAVLINK_MSG_ID_106_LEN 32
-#define MAVLINK_MSG_ID_106_MIN_LEN 32
-
-#define MAVLINK_MSG_ID_VOLTAGE_TM_CRC 175
-#define MAVLINK_MSG_ID_106_CRC 175
-
-#define MAVLINK_MSG_VOLTAGE_TM_FIELD_SENSOR_ID_LEN 20
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_VOLTAGE_TM { \
- 106, \
- "VOLTAGE_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_voltage_tm_t, timestamp) }, \
- { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_voltage_tm_t, sensor_id) }, \
- { "voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_voltage_tm_t, voltage) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_VOLTAGE_TM { \
- "VOLTAGE_TM", \
- 3, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_voltage_tm_t, timestamp) }, \
- { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 12, offsetof(mavlink_voltage_tm_t, sensor_id) }, \
- { "voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_voltage_tm_t, voltage) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a voltage_tm 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] When was this logged
- * @param sensor_id Sensor name
- * @param voltage [V] Voltage
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_voltage_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, const char *sensor_id, float voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_VOLTAGE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, voltage);
- _mav_put_char_array(buf, 12, sensor_id, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VOLTAGE_TM_LEN);
-#else
- mavlink_voltage_tm_t packet;
- packet.timestamp = timestamp;
- packet.voltage = voltage;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VOLTAGE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_VOLTAGE_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-}
-
-/**
- * @brief Pack a voltage_tm 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] When was this logged
- * @param sensor_id Sensor name
- * @param voltage [V] Voltage
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_voltage_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,const char *sensor_id,float voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_VOLTAGE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, voltage);
- _mav_put_char_array(buf, 12, sensor_id, 20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VOLTAGE_TM_LEN);
-#else
- mavlink_voltage_tm_t packet;
- packet.timestamp = timestamp;
- packet.voltage = voltage;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VOLTAGE_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_VOLTAGE_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-}
-
-/**
- * @brief Encode a voltage_tm 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 voltage_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_voltage_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_voltage_tm_t* voltage_tm)
-{
- return mavlink_msg_voltage_tm_pack(system_id, component_id, msg, voltage_tm->timestamp, voltage_tm->sensor_id, voltage_tm->voltage);
-}
-
-/**
- * @brief Encode a voltage_tm 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 voltage_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_voltage_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_voltage_tm_t* voltage_tm)
-{
- return mavlink_msg_voltage_tm_pack_chan(system_id, component_id, chan, msg, voltage_tm->timestamp, voltage_tm->sensor_id, voltage_tm->voltage);
-}
-
-/**
- * @brief Send a voltage_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp [us] When was this logged
- * @param sensor_id Sensor name
- * @param voltage [V] Voltage
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_voltage_tm_send(mavlink_channel_t chan, uint64_t timestamp, const char *sensor_id, float voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_VOLTAGE_TM_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, voltage);
- _mav_put_char_array(buf, 12, sensor_id, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLTAGE_TM, buf, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-#else
- mavlink_voltage_tm_t packet;
- packet.timestamp = timestamp;
- packet.voltage = voltage;
- mav_array_memcpy(packet.sensor_id, sensor_id, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLTAGE_TM, (const char *)&packet, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a voltage_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_voltage_tm_send_struct(mavlink_channel_t chan, const mavlink_voltage_tm_t* voltage_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_voltage_tm_send(chan, voltage_tm->timestamp, voltage_tm->sensor_id, voltage_tm->voltage);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLTAGE_TM, (const char *)voltage_tm, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_VOLTAGE_TM_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_voltage_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, const char *sensor_id, float voltage)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_float(buf, 8, voltage);
- _mav_put_char_array(buf, 12, sensor_id, 20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLTAGE_TM, buf, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-#else
- mavlink_voltage_tm_t *packet = (mavlink_voltage_tm_t *)msgbuf;
- packet->timestamp = timestamp;
- packet->voltage = voltage;
- mav_array_memcpy(packet->sensor_id, sensor_id, sizeof(char)*20);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLTAGE_TM, (const char *)packet, MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_LEN, MAVLINK_MSG_ID_VOLTAGE_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE VOLTAGE_TM UNPACKING
-
-
-/**
- * @brief Get field timestamp from voltage_tm message
- *
- * @return [us] When was this logged
- */
-static inline uint64_t mavlink_msg_voltage_tm_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field sensor_id from voltage_tm message
- *
- * @return Sensor name
- */
-static inline uint16_t mavlink_msg_voltage_tm_get_sensor_id(const mavlink_message_t* msg, char *sensor_id)
-{
- return _MAV_RETURN_char_array(msg, sensor_id, 20, 12);
-}
-
-/**
- * @brief Get field voltage from voltage_tm message
- *
- * @return [V] Voltage
- */
-static inline float mavlink_msg_voltage_tm_get_voltage(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Decode a voltage_tm message into a struct
- *
- * @param msg The message to decode
- * @param voltage_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_voltage_tm_decode(const mavlink_message_t* msg, mavlink_voltage_tm_t* voltage_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- voltage_tm->timestamp = mavlink_msg_voltage_tm_get_timestamp(msg);
- voltage_tm->voltage = mavlink_msg_voltage_tm_get_voltage(msg);
- mavlink_msg_voltage_tm_get_sensor_id(msg, voltage_tm->sensor_id);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_VOLTAGE_TM_LEN? msg->len : MAVLINK_MSG_ID_VOLTAGE_TM_LEN;
- memset(voltage_tm, 0, MAVLINK_MSG_ID_VOLTAGE_TM_LEN);
- memcpy(voltage_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/mavlink_msg_wiggle_servo_tc.h b/mavlink_lib/pyxis/mavlink_msg_wiggle_servo_tc.h
deleted file mode 100644
index b9e333c4ed5bde71c947b204fee64987ed98b2ad..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/mavlink_msg_wiggle_servo_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE WIGGLE_SERVO_TC PACKING
-
-#define MAVLINK_MSG_ID_WIGGLE_SERVO_TC 7
-
-
-typedef struct __mavlink_wiggle_servo_tc_t {
- uint8_t servo_id; /*< A member of the ServosList enum*/
-} mavlink_wiggle_servo_tc_t;
-
-#define MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN 1
-#define MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_7_LEN 1
-#define MAVLINK_MSG_ID_7_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC 160
-#define MAVLINK_MSG_ID_7_CRC 160
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC { \
- 7, \
- "WIGGLE_SERVO_TC", \
- 1, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_wiggle_servo_tc_t, servo_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC { \
- "WIGGLE_SERVO_TC", \
- 1, \
- { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_wiggle_servo_tc_t, servo_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a wiggle_servo_tc 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 servo_id A member of the ServosList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_wiggle_servo_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN);
-#else
- mavlink_wiggle_servo_tc_t packet;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_WIGGLE_SERVO_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-}
-
-/**
- * @brief Pack a wiggle_servo_tc 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 servo_id A member of the ServosList enum
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_wiggle_servo_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN);
-#else
- mavlink_wiggle_servo_tc_t packet;
- packet.servo_id = servo_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_WIGGLE_SERVO_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-}
-
-/**
- * @brief Encode a wiggle_servo_tc 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 wiggle_servo_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_wiggle_servo_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_wiggle_servo_tc_t* wiggle_servo_tc)
-{
- return mavlink_msg_wiggle_servo_tc_pack(system_id, component_id, msg, wiggle_servo_tc->servo_id);
-}
-
-/**
- * @brief Encode a wiggle_servo_tc 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 wiggle_servo_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_wiggle_servo_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_wiggle_servo_tc_t* wiggle_servo_tc)
-{
- return mavlink_msg_wiggle_servo_tc_pack_chan(system_id, component_id, chan, msg, wiggle_servo_tc->servo_id);
-}
-
-/**
- * @brief Send a wiggle_servo_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param servo_id A member of the ServosList enum
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_wiggle_servo_tc_send(mavlink_channel_t chan, uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN];
- _mav_put_uint8_t(buf, 0, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIGGLE_SERVO_TC, buf, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-#else
- mavlink_wiggle_servo_tc_t packet;
- packet.servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIGGLE_SERVO_TC, (const char *)&packet, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a wiggle_servo_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_wiggle_servo_tc_send_struct(mavlink_channel_t chan, const mavlink_wiggle_servo_tc_t* wiggle_servo_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_wiggle_servo_tc_send(chan, wiggle_servo_tc->servo_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIGGLE_SERVO_TC, (const char *)wiggle_servo_tc, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_WIGGLE_SERVO_TC_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_wiggle_servo_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t servo_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, servo_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIGGLE_SERVO_TC, buf, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-#else
- mavlink_wiggle_servo_tc_t *packet = (mavlink_wiggle_servo_tc_t *)msgbuf;
- packet->servo_id = servo_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIGGLE_SERVO_TC, (const char *)packet, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE WIGGLE_SERVO_TC UNPACKING
-
-
-/**
- * @brief Get field servo_id from wiggle_servo_tc message
- *
- * @return A member of the ServosList enum
- */
-static inline uint8_t mavlink_msg_wiggle_servo_tc_get_servo_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a wiggle_servo_tc message into a struct
- *
- * @param msg The message to decode
- * @param wiggle_servo_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_wiggle_servo_tc_decode(const mavlink_message_t* msg, mavlink_wiggle_servo_tc_t* wiggle_servo_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- wiggle_servo_tc->servo_id = mavlink_msg_wiggle_servo_tc_get_servo_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN? msg->len : MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN;
- memset(wiggle_servo_tc, 0, MAVLINK_MSG_ID_WIGGLE_SERVO_TC_LEN);
- memcpy(wiggle_servo_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/pyxis/pyxis.h b/mavlink_lib/pyxis/pyxis.h
deleted file mode 100644
index ddbbb7d592da8efebe8417d70e3756a58bc5a04e..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/pyxis.h
+++ /dev/null
@@ -1,203 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol generated from pyxis.xml
- * @see http://mavlink.org
- */
-#pragma once
-#ifndef MAVLINK_PYXIS_H
-#define MAVLINK_PYXIS_H
-
-#ifndef MAVLINK_H
- #error Wrong include order: MAVLINK_PYXIS.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
-
-#undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH 7764457067459173741
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-// MESSAGE LENGTHS AND CRCS
-
-#ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 8, 2, 4, 8, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 74, 64, 32, 44, 32, 32, 32, 32, 56, 21, 5, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 14, 13, 46, 28, 27, 53, 77, 167, 158, 92, 76, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
-#endif
-
-#ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 103, 184, 215, 160, 226, 113, 38, 71, 67, 218, 44, 81, 181, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 146, 39, 178, 239, 104, 175, 222, 128, 233, 170, 42, 87, 255, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 109, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 253, 142, 108, 133, 234, 66, 184, 193, 245, 115, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
-#endif
-
-#include "../protocol.h"
-
-#define MAVLINK_ENABLED_PYXIS
-
-// ENUM DEFINITIONS
-
-
-/** @brief Enum list for all the telemetries that can be requested */
-#ifndef HAVE_ENUM_SystemTMList
-#define HAVE_ENUM_SystemTMList
-typedef enum SystemTMList
-{
- MAV_SYS_ID=1, /* State of init results about system hardware/software components | */
- MAV_FSM_ID=2, /* States of all On-Board FSMs | */
- MAV_PIN_OBS_ID=3, /* Pin observer data | */
- MAV_LOGGER_ID=4, /* SD Logger stats | */
- MAV_MAVLINK_STATS=5, /* Mavlink driver stats | */
- MAV_TASK_STATS_ID=6, /* Task scheduler statistics answer: n mavlink messages where n is the number of tasks | */
- MAV_ADA_ID=8, /* ADA Status | */
- MAV_NAS_ID=9, /* NavigationSystem data | */
- MAV_CAN_ID=10, /* Canbus stats | */
- MAV_FLIGHT_ID=11, /* Flight telemetry | */
- MAV_STATS_ID=12, /* Satistics telemetry | */
- MAV_SENSORS_STATE_ID=13, /* Sensors init state telemetry | */
- SystemTMList_ENUM_END=14, /* | */
-} SystemTMList;
-#endif
-
-/** @brief Enum list of all sensors telemetries that can be requested */
-#ifndef HAVE_ENUM_SensorsTMList
-#define HAVE_ENUM_SensorsTMList
-typedef enum SensorsTMList
-{
- MAV_GPS_ID=1, /* GPS data | */
- MAV_BMX160_ID=2, /* BM180 IMU data | */
- MAV_VN100_ID=3, /* VN100 IMU data | */
- MAV_MPU9250_ID=4, /* MPU9250 IMU data | */
- MAV_ADS_ID=5, /* ADS 4 channel ADC data | */
- MAV_MS5803_ID=6, /* MS5803 barometer data | */
- MAV_BME280_ID=7, /* BME280 barometer data | */
- MAV_CURRENT_SENSE_ID=8, /* Electrical current sensors data | */
- MAV_LIS3MDL_ID=9, /* LIS3MDL compass data | */
- MAV_DPL_PRESS_ID=10, /* Deployment pressure data | */
- MAV_STATIC_PRESS_ID=11, /* Static pressure data | */
- MAV_PITOT_PRESS_ID=12, /* Pitot pressure data | */
- MAV_BATTERY_VOLTAGE_ID=13, /* Battery voltage data | */
- MAV_LOAD_CELL_ID=14, /* Load cell data | */
- SensorsTMList_ENUM_END=15, /* | */
-} SensorsTMList;
-#endif
-
-/** @brief Enum of the commands */
-#ifndef HAVE_ENUM_MavCommandList
-#define HAVE_ENUM_MavCommandList
-typedef enum MavCommandList
-{
- MAV_CMD_ARM=1, /* Command to arm the rocket | */
- MAV_CMD_DISARM=2, /* Command to disarm the rocket | */
- MAV_CMD_CALIBRATE=3, /* Command to trigger the calibration | */
- MAV_CMD_FORCE_INIT=4, /* Command to init the rocket | */
- MAV_CMD_FORCE_LAUNCH=5, /* Command to launch the rocket | */
- MAV_CMD_FORCE_LANDING=6, /* Command to communicate the end of the mission and close the file descriptors in the SD card | */
- MAV_CMD_FORCE_APOGEE=7, /* Command to trigger the apogee event | */
- MAV_CMD_FORCE_EXPULSION=8, /* Command to open the nosecone | */
- MAV_CMD_FORCE_MAIN=9, /* Command to activate the thermal cutters and cut the drogue, activating both thermal cutters sequentially | */
- MAV_CMD_START_LOGGING=10, /* Command to enable sensor logging | */
- MAV_CMD_STOP_LOGGING=11, /* Command to permanently close the log file | */
- MAV_CMD_FORCE_REBOOT=12, /* Command to reset the board from test status | */
- MAV_CMD_ENTER_TEST_MODE=13, /* Command to enter the test mode | */
- MAV_CMD_EXIT_TEST_MODE=14, /* Command to exit the test mode | */
- MAV_CMD_START_RECORDING=15, /* Command to start the internal cameras recordings | */
- MAV_CMD_STOP_RECORDING=16, /* Command to stop the internal cameras recordings | */
- MavCommandList_ENUM_END=17, /* | */
-} MavCommandList;
-#endif
-
-/** @brief Enum of all the servos used on Pyxis */
-#ifndef HAVE_ENUM_ServosList
-#define HAVE_ENUM_ServosList
-typedef enum ServosList
-{
- AIR_BRAKES_SERVO=1, /* | */
- EXPULSION_SERVO=2, /* | */
- PARAFOIL_LEFT_SERVO=3, /* | */
- PARAFOIL_RIGHT_SERVO=4, /* | */
- ServosList_ENUM_END=5, /* | */
-} ServosList;
-#endif
-
-/** @brief Enum of all the pins used on Pyxis */
-#ifndef HAVE_ENUM_PinsList
-#define HAVE_ENUM_PinsList
-typedef enum PinsList
-{
- LAUNCH_PIN=1, /* | */
- NOSECONE_PIN=2, /* | */
- DEPLOYMENT_PIN=3, /* | */
- PinsList_ENUM_END=4, /* | */
-} PinsList;
-#endif
-
-// MAVLINK VERSION
-
-#ifndef MAVLINK_VERSION
-#define MAVLINK_VERSION 1
-#endif
-
-#if (MAVLINK_VERSION == 0)
-#undef MAVLINK_VERSION
-#define MAVLINK_VERSION 1
-#endif
-
-// MESSAGE DEFINITIONS
-#include "./mavlink_msg_ping_tc.h"
-#include "./mavlink_msg_command_tc.h"
-#include "./mavlink_msg_system_tm_request_tc.h"
-#include "./mavlink_msg_sensor_tm_request_tc.h"
-#include "./mavlink_msg_servo_tm_request_tc.h"
-#include "./mavlink_msg_set_servo_angle_tc.h"
-#include "./mavlink_msg_wiggle_servo_tc.h"
-#include "./mavlink_msg_reset_servo_tc.h"
-#include "./mavlink_msg_set_reference_altitude_tc.h"
-#include "./mavlink_msg_set_reference_temperature_tc.h"
-#include "./mavlink_msg_set_orientation_tc.h"
-#include "./mavlink_msg_set_coordinates_tc.h"
-#include "./mavlink_msg_raw_event_tc.h"
-#include "./mavlink_msg_set_deployment_altitude_tc.h"
-#include "./mavlink_msg_set_target_coordinates_tc.h"
-#include "./mavlink_msg_set_algorithm_tc.h"
-#include "./mavlink_msg_ack_tm.h"
-#include "./mavlink_msg_nack_tm.h"
-#include "./mavlink_msg_gps_tm.h"
-#include "./mavlink_msg_imu_tm.h"
-#include "./mavlink_msg_pressure_tm.h"
-#include "./mavlink_msg_adc_tm.h"
-#include "./mavlink_msg_voltage_tm.h"
-#include "./mavlink_msg_current_tm.h"
-#include "./mavlink_msg_temp_tm.h"
-#include "./mavlink_msg_load_tm.h"
-#include "./mavlink_msg_attitude_tm.h"
-#include "./mavlink_msg_sensor_state_tm.h"
-#include "./mavlink_msg_servo_tm.h"
-#include "./mavlink_msg_pin_tm.h"
-#include "./mavlink_msg_receiver_tm.h"
-#include "./mavlink_msg_sys_tm.h"
-#include "./mavlink_msg_fsm_tm.h"
-#include "./mavlink_msg_logger_tm.h"
-#include "./mavlink_msg_mavlink_stats_tm.h"
-#include "./mavlink_msg_task_stats_tm.h"
-#include "./mavlink_msg_ada_tm.h"
-#include "./mavlink_msg_nas_tm.h"
-#include "./mavlink_msg_rocket_flight_tm.h"
-#include "./mavlink_msg_payload_flight_tm.h"
-#include "./mavlink_msg_rocket_stats_tm.h"
-#include "./mavlink_msg_payload_stats_tm.h"
-
-// base include
-
-
-#undef MAVLINK_THIS_XML_HASH
-#define MAVLINK_THIS_XML_HASH 7764457067459173741
-
-#if MAVLINK_THIS_XML_HASH == MAVLINK_PRIMARY_XML_HASH
-# define MAVLINK_MESSAGE_INFO {{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING_TC, MAVLINK_MESSAGE_INFO_COMMAND_TC, MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC, MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC, MAVLINK_MESSAGE_INFO_RESET_SERVO_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC, MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_RAW_EVENT_TC, MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACK_TM, MAVLINK_MESSAGE_INFO_NACK_TM, MAVLINK_MESSAGE_INFO_GPS_TM, MAVLINK_MESSAGE_INFO_IMU_TM, MAVLINK_MESSAGE_INFO_PRESSURE_TM, MAVLINK_MESSAGE_INFO_ADC_TM, MAVLINK_MESSAGE_INFO_VOLTAGE_TM, MAVLINK_MESSAGE_INFO_CURRENT_TM, MAVLINK_MESSAGE_INFO_TEMP_TM, MAVLINK_MESSAGE_INFO_LOAD_TM, MAVLINK_MESSAGE_INFO_ATTITUDE_TM, MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM, MAVLINK_MESSAGE_INFO_SERVO_TM, MAVLINK_MESSAGE_INFO_PIN_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_RECEIVER_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_TM, MAVLINK_MESSAGE_INFO_FSM_TM, MAVLINK_MESSAGE_INFO_LOGGER_TM, MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM, MAVLINK_MESSAGE_INFO_TASK_STATS_TM, MAVLINK_MESSAGE_INFO_ADA_TM, MAVLINK_MESSAGE_INFO_NAS_TM, MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM, MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
-# define MAVLINK_MESSAGE_NAMES {{ "ACK_TM", 100 }, { "ADA_TM", 205 }, { "ADC_TM", 105 }, { "ATTITUDE_TM", 110 }, { "COMMAND_TC", 2 }, { "CURRENT_TM", 107 }, { "FSM_TM", 201 }, { "GPS_TM", 102 }, { "IMU_TM", 103 }, { "LOAD_TM", 109 }, { "LOGGER_TM", 202 }, { "MAVLINK_STATS_TM", 203 }, { "NACK_TM", 101 }, { "NAS_TM", 206 }, { "PAYLOAD_FLIGHT_TM", 208 }, { "PAYLOAD_STATS_TM", 210 }, { "PING_TC", 1 }, { "PIN_TM", 113 }, { "PRESSURE_TM", 104 }, { "RAW_EVENT_TC", 13 }, { "RECEIVER_TM", 150 }, { "RESET_SERVO_TC", 8 }, { "ROCKET_FLIGHT_TM", 207 }, { "ROCKET_STATS_TM", 209 }, { "SENSOR_STATE_TM", 111 }, { "SENSOR_TM_REQUEST_TC", 4 }, { "SERVO_TM", 112 }, { "SERVO_TM_REQUEST_TC", 5 }, { "SET_ALGORITHM_TC", 16 }, { "SET_COORDINATES_TC", 12 }, { "SET_DEPLOYMENT_ALTITUDE_TC", 14 }, { "SET_ORIENTATION_TC", 11 }, { "SET_REFERENCE_ALTITUDE_TC", 9 }, { "SET_REFERENCE_TEMPERATURE_TC", 10 }, { "SET_SERVO_ANGLE_TC", 6 }, { "SET_TARGET_COORDINATES_TC", 15 }, { "SYSTEM_TM_REQUEST_TC", 3 }, { "SYS_TM", 200 }, { "TASK_STATS_TM", 204 }, { "TEMP_TM", 108 }, { "VOLTAGE_TM", 106 }, { "WIGGLE_SERVO_TC", 7 }}
-# if MAVLINK_COMMAND_24BIT
-# include "../mavlink_get_info.h"
-# endif
-#endif
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // MAVLINK_PYXIS_H
diff --git a/mavlink_lib/pyxis/testsuite.h b/mavlink_lib/pyxis/testsuite.h
deleted file mode 100644
index 4664203f8885efabaadca09d555e545c6ae0671d..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/testsuite.h
+++ /dev/null
@@ -1,2807 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol testsuite generated from pyxis.xml
- * @see https://mavlink.io/en/
- */
-#pragma once
-#ifndef PYXIS_TESTSUITE_H
-#define PYXIS_TESTSUITE_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#ifndef MAVLINK_TEST_ALL
-#define MAVLINK_TEST_ALL
-
-static void mavlink_test_pyxis(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_pyxis(system_id, component_id, last_msg);
-}
-#endif
-
-
-
-
-static void mavlink_test_ping_tc(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_PING_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ping_tc_t packet_in = {
- 93372036854775807ULL
- };
- mavlink_ping_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_PING_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PING_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ping_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_pack(system_id, component_id, &msg , packet1.timestamp );
- mavlink_msg_ping_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp );
- mavlink_msg_ping_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ping_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_send(MAVLINK_COMM_1 , packet1.timestamp );
- mavlink_msg_ping_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("PING_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_PING_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_command_tc(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_COMMAND_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_command_tc_t packet_in = {
- 5
- };
- mavlink_command_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.command_id = packet_in.command_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_COMMAND_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_command_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_command_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_command_tc_pack(system_id, component_id, &msg , packet1.command_id );
- mavlink_msg_command_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_command_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.command_id );
- mavlink_msg_command_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_command_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_command_tc_send(MAVLINK_COMM_1 , packet1.command_id );
- mavlink_msg_command_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("COMMAND_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_COMMAND_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_system_tm_request_tc(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_SYSTEM_TM_REQUEST_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_system_tm_request_tc_t packet_in = {
- 5
- };
- mavlink_system_tm_request_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.tm_id = packet_in.tm_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_system_tm_request_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_system_tm_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_system_tm_request_tc_pack(system_id, component_id, &msg , packet1.tm_id );
- mavlink_msg_system_tm_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_system_tm_request_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.tm_id );
- mavlink_msg_system_tm_request_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_system_tm_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_system_tm_request_tc_send(MAVLINK_COMM_1 , packet1.tm_id );
- mavlink_msg_system_tm_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SYSTEM_TM_REQUEST_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_sensor_tm_request_tc(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_SENSOR_TM_REQUEST_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_sensor_tm_request_tc_t packet_in = {
- 5
- };
- mavlink_sensor_tm_request_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.sensor_id = packet_in.sensor_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_tm_request_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_sensor_tm_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_tm_request_tc_pack(system_id, component_id, &msg , packet1.sensor_id );
- mavlink_msg_sensor_tm_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_tm_request_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.sensor_id );
- mavlink_msg_sensor_tm_request_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_sensor_tm_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_tm_request_tc_send(MAVLINK_COMM_1 , packet1.sensor_id );
- mavlink_msg_sensor_tm_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SENSOR_TM_REQUEST_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_servo_tm_request_tc(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_SERVO_TM_REQUEST_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_servo_tm_request_tc_t packet_in = {
- 5
- };
- mavlink_servo_tm_request_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.servo_id = packet_in.servo_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_request_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_servo_tm_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_request_tc_pack(system_id, component_id, &msg , packet1.servo_id );
- mavlink_msg_servo_tm_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_request_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id );
- mavlink_msg_servo_tm_request_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_servo_tm_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_request_tc_send(MAVLINK_COMM_1 , packet1.servo_id );
- mavlink_msg_servo_tm_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SERVO_TM_REQUEST_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SERVO_TM_REQUEST_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_servo_angle_tc(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_SET_SERVO_ANGLE_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_servo_angle_tc_t packet_in = {
- 17.0,17
- };
- mavlink_set_servo_angle_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.angle = packet_in.angle;
- packet1.servo_id = packet_in.servo_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_servo_angle_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_servo_angle_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_servo_angle_tc_pack(system_id, component_id, &msg , packet1.servo_id , packet1.angle );
- mavlink_msg_set_servo_angle_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_servo_angle_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id , packet1.angle );
- mavlink_msg_set_servo_angle_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_servo_angle_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_servo_angle_tc_send(MAVLINK_COMM_1 , packet1.servo_id , packet1.angle );
- mavlink_msg_set_servo_angle_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_SERVO_ANGLE_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_wiggle_servo_tc(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_WIGGLE_SERVO_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_wiggle_servo_tc_t packet_in = {
- 5
- };
- mavlink_wiggle_servo_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.servo_id = packet_in.servo_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_WIGGLE_SERVO_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_wiggle_servo_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_wiggle_servo_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_wiggle_servo_tc_pack(system_id, component_id, &msg , packet1.servo_id );
- mavlink_msg_wiggle_servo_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_wiggle_servo_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id );
- mavlink_msg_wiggle_servo_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_wiggle_servo_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_wiggle_servo_tc_send(MAVLINK_COMM_1 , packet1.servo_id );
- mavlink_msg_wiggle_servo_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("WIGGLE_SERVO_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_WIGGLE_SERVO_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_reset_servo_tc(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_RESET_SERVO_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_reset_servo_tc_t packet_in = {
- 5
- };
- mavlink_reset_servo_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.servo_id = packet_in.servo_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RESET_SERVO_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_reset_servo_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_reset_servo_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_reset_servo_tc_pack(system_id, component_id, &msg , packet1.servo_id );
- mavlink_msg_reset_servo_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_reset_servo_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id );
- mavlink_msg_reset_servo_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_reset_servo_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_reset_servo_tc_send(MAVLINK_COMM_1 , packet1.servo_id );
- mavlink_msg_reset_servo_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("RESET_SERVO_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_RESET_SERVO_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_reference_altitude_tc(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_SET_REFERENCE_ALTITUDE_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_reference_altitude_tc_t packet_in = {
- 17.0
- };
- mavlink_set_reference_altitude_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.ref_altitude = packet_in.ref_altitude;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_altitude_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_reference_altitude_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_altitude_tc_pack(system_id, component_id, &msg , packet1.ref_altitude );
- mavlink_msg_set_reference_altitude_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_altitude_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.ref_altitude );
- mavlink_msg_set_reference_altitude_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_reference_altitude_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_altitude_tc_send(MAVLINK_COMM_1 , packet1.ref_altitude );
- mavlink_msg_set_reference_altitude_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_REFERENCE_ALTITUDE_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_reference_temperature_tc(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_SET_REFERENCE_TEMPERATURE_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_reference_temperature_tc_t packet_in = {
- 17.0
- };
- mavlink_set_reference_temperature_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.ref_temp = packet_in.ref_temp;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_temperature_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_reference_temperature_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_temperature_tc_pack(system_id, component_id, &msg , packet1.ref_temp );
- mavlink_msg_set_reference_temperature_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_temperature_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.ref_temp );
- mavlink_msg_set_reference_temperature_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_reference_temperature_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_reference_temperature_tc_send(MAVLINK_COMM_1 , packet1.ref_temp );
- mavlink_msg_set_reference_temperature_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_REFERENCE_TEMPERATURE_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_orientation_tc(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_SET_ORIENTATION_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_orientation_tc_t packet_in = {
- 17.0,45.0,73.0
- };
- mavlink_set_orientation_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.yaw = packet_in.yaw;
- packet1.pitch = packet_in.pitch;
- packet1.roll = packet_in.roll;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ORIENTATION_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_orientation_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_orientation_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_orientation_tc_pack(system_id, component_id, &msg , packet1.yaw , packet1.pitch , packet1.roll );
- mavlink_msg_set_orientation_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_orientation_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.yaw , packet1.pitch , packet1.roll );
- mavlink_msg_set_orientation_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_orientation_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_orientation_tc_send(MAVLINK_COMM_1 , packet1.yaw , packet1.pitch , packet1.roll );
- mavlink_msg_set_orientation_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_ORIENTATION_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_ORIENTATION_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_coordinates_tc(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_SET_COORDINATES_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_coordinates_tc_t packet_in = {
- 17.0,45.0
- };
- mavlink_set_coordinates_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.latitude = packet_in.latitude;
- packet1.longitude = packet_in.longitude;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_COORDINATES_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_coordinates_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_coordinates_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_coordinates_tc_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude );
- mavlink_msg_set_coordinates_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_coordinates_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude );
- mavlink_msg_set_coordinates_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_coordinates_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_coordinates_tc_send(MAVLINK_COMM_1 , packet1.latitude , packet1.longitude );
- mavlink_msg_set_coordinates_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_COORDINATES_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_COORDINATES_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_raw_event_tc(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_RAW_EVENT_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_raw_event_tc_t packet_in = {
- 5,72
- };
- mavlink_raw_event_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.topic_id = packet_in.topic_id;
- packet1.event_id = packet_in.event_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_raw_event_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_pack(system_id, component_id, &msg , packet1.topic_id , packet1.event_id );
- mavlink_msg_raw_event_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.topic_id , packet1.event_id );
- mavlink_msg_raw_event_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_raw_event_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_send(MAVLINK_COMM_1 , packet1.topic_id , packet1.event_id );
- mavlink_msg_raw_event_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("RAW_EVENT_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_RAW_EVENT_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_deployment_altitude_tc(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_SET_DEPLOYMENT_ALTITUDE_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_deployment_altitude_tc_t packet_in = {
- 17.0
- };
- mavlink_set_deployment_altitude_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.dpl_altitude = packet_in.dpl_altitude;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_deployment_altitude_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_deployment_altitude_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_deployment_altitude_tc_pack(system_id, component_id, &msg , packet1.dpl_altitude );
- mavlink_msg_set_deployment_altitude_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_deployment_altitude_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.dpl_altitude );
- mavlink_msg_set_deployment_altitude_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_deployment_altitude_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_deployment_altitude_tc_send(MAVLINK_COMM_1 , packet1.dpl_altitude );
- mavlink_msg_set_deployment_altitude_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_DEPLOYMENT_ALTITUDE_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_target_coordinates_tc(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_SET_TARGET_COORDINATES_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_target_coordinates_tc_t packet_in = {
- 17.0,45.0
- };
- mavlink_set_target_coordinates_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.latitude = packet_in.latitude;
- packet1.longitude = packet_in.longitude;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_target_coordinates_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_target_coordinates_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_target_coordinates_tc_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude );
- mavlink_msg_set_target_coordinates_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_target_coordinates_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude );
- mavlink_msg_set_target_coordinates_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_target_coordinates_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_target_coordinates_tc_send(MAVLINK_COMM_1 , packet1.latitude , packet1.longitude );
- mavlink_msg_set_target_coordinates_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_TARGET_COORDINATES_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_set_algorithm_tc(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_SET_ALGORITHM_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_set_algorithm_tc_t packet_in = {
- 5
- };
- mavlink_set_algorithm_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.algorithm_number = packet_in.algorithm_number;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ALGORITHM_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_algorithm_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_algorithm_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_algorithm_tc_pack(system_id, component_id, &msg , packet1.algorithm_number );
- mavlink_msg_set_algorithm_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_algorithm_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.algorithm_number );
- mavlink_msg_set_algorithm_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_set_algorithm_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_algorithm_tc_send(MAVLINK_COMM_1 , packet1.algorithm_number );
- mavlink_msg_set_algorithm_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_ALGORITHM_TC") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_ALGORITHM_TC) != NULL);
-#endif
-}
-
-static void mavlink_test_ack_tm(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_ACK_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ack_tm_t packet_in = {
- 5,72
- };
- mavlink_ack_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.recv_msgid = packet_in.recv_msgid;
- packet1.seq_ack = packet_in.seq_ack;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_ACK_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ACK_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_pack(system_id, component_id, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_ack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_ack_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_send(MAVLINK_COMM_1 , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_ack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("ACK_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ACK_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_nack_tm(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_NACK_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_nack_tm_t packet_in = {
- 5,72
- };
- mavlink_nack_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.recv_msgid = packet_in.recv_msgid;
- packet1.seq_ack = packet_in.seq_ack;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_NACK_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NACK_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nack_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_nack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nack_tm_pack(system_id, component_id, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_nack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nack_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_nack_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_nack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nack_tm_send(MAVLINK_COMM_1 , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_nack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("NACK_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_NACK_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_gps_tm(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_GPS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_gps_tm_t packet_in = {
- 93372036854775807ULL,179.0,235.0,291.0,241.0,269.0,297.0,325.0,353.0,"ABCDEFGHIJKLMNOPQRS",221,32
- };
- mavlink_gps_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.latitude = packet_in.latitude;
- packet1.longitude = packet_in.longitude;
- packet1.height = packet_in.height;
- packet1.vel_north = packet_in.vel_north;
- packet1.vel_east = packet_in.vel_east;
- packet1.vel_down = packet_in.vel_down;
- packet1.speed = packet_in.speed;
- packet1.track = packet_in.track;
- packet1.fix = packet_in.fix;
- packet1.n_satellites = packet_in.n_satellites;
-
- mav_array_memcpy(packet1.sensor_id, packet_in.sensor_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_GPS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gps_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_gps_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gps_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_id , packet1.fix , packet1.latitude , packet1.longitude , packet1.height , packet1.vel_north , packet1.vel_east , packet1.vel_down , packet1.speed , packet1.track , packet1.n_satellites );
- mavlink_msg_gps_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gps_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_id , packet1.fix , packet1.latitude , packet1.longitude , packet1.height , packet1.vel_north , packet1.vel_east , packet1.vel_down , packet1.speed , packet1.track , packet1.n_satellites );
- mavlink_msg_gps_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_gps_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_gps_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_id , packet1.fix , packet1.latitude , packet1.longitude , packet1.height , packet1.vel_north , packet1.vel_east , packet1.vel_down , packet1.speed , packet1.track , packet1.n_satellites );
- mavlink_msg_gps_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("GPS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_GPS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_imu_tm(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_IMU_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_imu_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,"STUVWXYZABCDEFGHIJK"
- };
- mavlink_imu_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.acc_x = packet_in.acc_x;
- packet1.acc_y = packet_in.acc_y;
- packet1.acc_z = packet_in.acc_z;
- packet1.gyro_x = packet_in.gyro_x;
- packet1.gyro_y = packet_in.gyro_y;
- packet1.gyro_z = packet_in.gyro_z;
- packet1.mag_x = packet_in.mag_x;
- packet1.mag_y = packet_in.mag_y;
- packet1.mag_z = packet_in.mag_z;
-
- mav_array_memcpy(packet1.sensor_id, packet_in.sensor_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_IMU_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_IMU_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_imu_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_imu_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_imu_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_id , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z );
- mavlink_msg_imu_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_imu_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_id , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z );
- mavlink_msg_imu_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_imu_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_imu_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_id , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z );
- mavlink_msg_imu_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("IMU_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_IMU_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_pressure_tm(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_PRESSURE_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_pressure_tm_t packet_in = {
- 93372036854775807ULL,73.0,"MNOPQRSTUVWXYZABCDE"
- };
- mavlink_pressure_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.pressure = packet_in.pressure;
-
- mav_array_memcpy(packet1.sensor_id, packet_in.sensor_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_PRESSURE_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PRESSURE_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pressure_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_pressure_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pressure_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_id , packet1.pressure );
- mavlink_msg_pressure_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pressure_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_id , packet1.pressure );
- mavlink_msg_pressure_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_pressure_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pressure_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_id , packet1.pressure );
- mavlink_msg_pressure_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("PRESSURE_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_PRESSURE_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_adc_tm(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_ADC_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_adc_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,"YZABCDEFGHIJKLMNOPQ"
- };
- mavlink_adc_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.channel_0 = packet_in.channel_0;
- packet1.channel_1 = packet_in.channel_1;
- packet1.channel_2 = packet_in.channel_2;
- packet1.channel_3 = packet_in.channel_3;
-
- mav_array_memcpy(packet1.sensor_id, packet_in.sensor_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_ADC_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ADC_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adc_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_adc_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adc_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_id , packet1.channel_0 , packet1.channel_1 , packet1.channel_2 , packet1.channel_3 );
- mavlink_msg_adc_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adc_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_id , packet1.channel_0 , packet1.channel_1 , packet1.channel_2 , packet1.channel_3 );
- mavlink_msg_adc_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_adc_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_adc_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_id , packet1.channel_0 , packet1.channel_1 , packet1.channel_2 , packet1.channel_3 );
- mavlink_msg_adc_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("ADC_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ADC_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_voltage_tm(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_VOLTAGE_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_voltage_tm_t packet_in = {
- 93372036854775807ULL,73.0,"MNOPQRSTUVWXYZABCDE"
- };
- mavlink_voltage_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.voltage = packet_in.voltage;
-
- mav_array_memcpy(packet1.sensor_id, packet_in.sensor_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_VOLTAGE_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VOLTAGE_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_voltage_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_voltage_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_voltage_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_id , packet1.voltage );
- mavlink_msg_voltage_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_voltage_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_id , packet1.voltage );
- mavlink_msg_voltage_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_voltage_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_voltage_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_id , packet1.voltage );
- mavlink_msg_voltage_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("VOLTAGE_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_VOLTAGE_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_current_tm(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_CURRENT_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_current_tm_t packet_in = {
- 93372036854775807ULL,73.0,"MNOPQRSTUVWXYZABCDE"
- };
- mavlink_current_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.current = packet_in.current;
-
- mav_array_memcpy(packet1.sensor_id, packet_in.sensor_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_CURRENT_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CURRENT_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_current_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_current_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_current_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_id , packet1.current );
- mavlink_msg_current_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_current_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_id , packet1.current );
- mavlink_msg_current_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_current_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_current_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_id , packet1.current );
- mavlink_msg_current_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("CURRENT_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_CURRENT_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_temp_tm(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_TEMP_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_temp_tm_t packet_in = {
- 93372036854775807ULL,73.0,"MNOPQRSTUVWXYZABCDE"
- };
- mavlink_temp_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.temperature = packet_in.temperature;
-
- mav_array_memcpy(packet1.sensor_id, packet_in.sensor_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_TEMP_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TEMP_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_temp_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_temp_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_temp_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_id , packet1.temperature );
- mavlink_msg_temp_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_temp_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_id , packet1.temperature );
- mavlink_msg_temp_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_temp_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_temp_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_id , packet1.temperature );
- mavlink_msg_temp_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("TEMP_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_TEMP_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_load_tm(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_LOAD_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_load_tm_t packet_in = {
- 93372036854775807ULL,73.0,"MNOPQRSTUVWXYZABCDE"
- };
- mavlink_load_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.load = packet_in.load;
-
- mav_array_memcpy(packet1.sensor_id, packet_in.sensor_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_LOAD_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOAD_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_load_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_load_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_load_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_id , packet1.load );
- mavlink_msg_load_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_load_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_id , packet1.load );
- mavlink_msg_load_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_load_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_load_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_id , packet1.load );
- mavlink_msg_load_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("LOAD_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_LOAD_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_attitude_tm(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_ATTITUDE_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_attitude_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,"KLMNOPQRSTUVWXYZABC"
- };
- mavlink_attitude_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.roll = packet_in.roll;
- packet1.pitch = packet_in.pitch;
- packet1.yaw = packet_in.yaw;
- packet1.quat_x = packet_in.quat_x;
- packet1.quat_y = packet_in.quat_y;
- packet1.quat_z = packet_in.quat_z;
- packet1.quat_w = packet_in.quat_w;
-
- mav_array_memcpy(packet1.sensor_id, packet_in.sensor_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_ATTITUDE_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ATTITUDE_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_attitude_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_attitude_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_attitude_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.sensor_id , packet1.roll , packet1.pitch , packet1.yaw , packet1.quat_x , packet1.quat_y , packet1.quat_z , packet1.quat_w );
- mavlink_msg_attitude_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_attitude_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.sensor_id , packet1.roll , packet1.pitch , packet1.yaw , packet1.quat_x , packet1.quat_y , packet1.quat_z , packet1.quat_w );
- mavlink_msg_attitude_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_attitude_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_attitude_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.sensor_id , packet1.roll , packet1.pitch , packet1.yaw , packet1.quat_x , packet1.quat_y , packet1.quat_z , packet1.quat_w );
- mavlink_msg_attitude_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("ATTITUDE_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ATTITUDE_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_sensor_state_tm(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_SENSOR_STATE_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_sensor_state_tm_t packet_in = {
- "ABCDEFGHIJKLMNOPQRS",65
- };
- mavlink_sensor_state_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.state = packet_in.state;
-
- mav_array_memcpy(packet1.sensor_id, packet_in.sensor_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_SENSOR_STATE_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SENSOR_STATE_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_state_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_sensor_state_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_state_tm_pack(system_id, component_id, &msg , packet1.sensor_id , packet1.state );
- mavlink_msg_sensor_state_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_state_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.sensor_id , packet1.state );
- mavlink_msg_sensor_state_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_sensor_state_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sensor_state_tm_send(MAVLINK_COMM_1 , packet1.sensor_id , packet1.state );
- mavlink_msg_sensor_state_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SENSOR_STATE_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SENSOR_STATE_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_servo_tm(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_SERVO_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_servo_tm_t packet_in = {
- 17.0,17
- };
- mavlink_servo_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.servo_position = packet_in.servo_position;
- packet1.servo_id = packet_in.servo_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SERVO_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SERVO_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_servo_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_pack(system_id, component_id, &msg , packet1.servo_id , packet1.servo_position );
- mavlink_msg_servo_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo_id , packet1.servo_position );
- mavlink_msg_servo_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_servo_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_servo_tm_send(MAVLINK_COMM_1 , packet1.servo_id , packet1.servo_position );
- mavlink_msg_servo_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SERVO_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SERVO_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_pin_tm(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_PIN_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_pin_tm_t packet_in = {
- 93372036854775807ULL,93372036854776311ULL,53,120,187
- };
- mavlink_pin_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.last_change_timestamp = packet_in.last_change_timestamp;
- packet1.pin_id = packet_in.pin_id;
- packet1.changes_counter = packet_in.changes_counter;
- packet1.current_state = packet_in.current_state;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_PIN_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PIN_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pin_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_pin_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pin_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.pin_id , packet1.last_change_timestamp , packet1.changes_counter , packet1.current_state );
- mavlink_msg_pin_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pin_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.pin_id , packet1.last_change_timestamp , packet1.changes_counter , packet1.current_state );
- mavlink_msg_pin_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_pin_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pin_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.pin_id , packet1.last_change_timestamp , packet1.changes_counter , packet1.current_state );
- mavlink_msg_pin_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("PIN_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_PIN_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_receiver_tm(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_RECEIVER_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_receiver_tm_t packet_in = {
- 93372036854775807ULL,93372036854776311ULL,93372036854776815ULL,185.0,213.0
- };
- mavlink_receiver_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.rx_bitrate = packet_in.rx_bitrate;
- packet1.tx_bitrate = packet_in.tx_bitrate;
- packet1.rssi = packet_in.rssi;
- packet1.fei = packet_in.fei;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RECEIVER_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_receiver_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_receiver_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_receiver_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.rssi , packet1.fei , packet1.rx_bitrate , packet1.tx_bitrate );
- mavlink_msg_receiver_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_receiver_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.rssi , packet1.fei , packet1.rx_bitrate , packet1.tx_bitrate );
- mavlink_msg_receiver_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_receiver_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_receiver_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.rssi , packet1.fei , packet1.rx_bitrate , packet1.tx_bitrate );
- mavlink_msg_receiver_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("RECEIVER_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_RECEIVER_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_sys_tm(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_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_sys_tm_t packet_in = {
- 93372036854775807ULL,29,96,163,230,41,108
- };
- mavlink_sys_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.logger = packet_in.logger;
- packet1.event_broker = packet_in.event_broker;
- packet1.radio = packet_in.radio;
- packet1.pin_observer = packet_in.pin_observer;
- packet1.sensors = packet_in.sensors;
- packet1.board_scheduler = packet_in.board_scheduler;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_SYS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SYS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sys_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_sys_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sys_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.logger , packet1.event_broker , packet1.radio , packet1.pin_observer , packet1.sensors , packet1.board_scheduler );
- mavlink_msg_sys_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sys_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.logger , packet1.event_broker , packet1.radio , packet1.pin_observer , packet1.sensors , packet1.board_scheduler );
- mavlink_msg_sys_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_sys_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_sys_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.logger , packet1.event_broker , packet1.radio , packet1.pin_observer , packet1.sensors , packet1.board_scheduler );
- mavlink_msg_sys_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("SYS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SYS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_fsm_tm(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_FSM_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_fsm_tm_t packet_in = {
- 93372036854775807ULL,29,96,163,230,41
- };
- mavlink_fsm_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.ada_state = packet_in.ada_state;
- packet1.abk_state = packet_in.abk_state;
- packet1.dpl_state = packet_in.dpl_state;
- packet1.fmm_state = packet_in.fmm_state;
- packet1.nas_state = packet_in.nas_state;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_FSM_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FSM_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_fsm_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_fsm_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_fsm_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.ada_state , packet1.abk_state , packet1.dpl_state , packet1.fmm_state , packet1.nas_state );
- mavlink_msg_fsm_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_fsm_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.ada_state , packet1.abk_state , packet1.dpl_state , packet1.fmm_state , packet1.nas_state );
- mavlink_msg_fsm_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_fsm_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_fsm_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.ada_state , packet1.abk_state , packet1.dpl_state , packet1.fmm_state , packet1.nas_state );
- mavlink_msg_fsm_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("FSM_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_FSM_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_logger_tm(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_LOGGER_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_logger_tm_t packet_in = {
- 93372036854775807ULL,963497880,963498088,963498296,963498504,963498712,963498920,963499128,963499336,963499544,19523
- };
- mavlink_logger_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.too_large_samples = packet_in.too_large_samples;
- packet1.dropped_samples = packet_in.dropped_samples;
- packet1.queued_samples = packet_in.queued_samples;
- packet1.buffers_filled = packet_in.buffers_filled;
- packet1.buffers_written = packet_in.buffers_written;
- packet1.writes_failed = packet_in.writes_failed;
- packet1.last_write_error = packet_in.last_write_error;
- packet1.average_write_time = packet_in.average_write_time;
- packet1.max_write_time = packet_in.max_write_time;
- packet1.log_number = packet_in.log_number;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOGGER_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_logger_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_logger_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_logger_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.log_number , packet1.too_large_samples , packet1.dropped_samples , packet1.queued_samples , packet1.buffers_filled , packet1.buffers_written , packet1.writes_failed , packet1.last_write_error , packet1.average_write_time , packet1.max_write_time );
- mavlink_msg_logger_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_logger_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.log_number , packet1.too_large_samples , packet1.dropped_samples , packet1.queued_samples , packet1.buffers_filled , packet1.buffers_written , packet1.writes_failed , packet1.last_write_error , packet1.average_write_time , packet1.max_write_time );
- mavlink_msg_logger_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_logger_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_logger_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.log_number , packet1.too_large_samples , packet1.dropped_samples , packet1.queued_samples , packet1.buffers_filled , packet1.buffers_written , packet1.writes_failed , packet1.last_write_error , packet1.average_write_time , packet1.max_write_time );
- mavlink_msg_logger_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("LOGGER_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_LOGGER_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_mavlink_stats_tm(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_MAVLINK_STATS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_mavlink_stats_tm_t packet_in = {
- 93372036854775807ULL,963497880,17859,17963,18067,18171,18275,199,10,77,144,211,22
- };
- mavlink_mavlink_stats_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.parse_state = packet_in.parse_state;
- packet1.n_send_queue = packet_in.n_send_queue;
- packet1.max_send_queue = packet_in.max_send_queue;
- packet1.n_send_errors = packet_in.n_send_errors;
- packet1.packet_rx_success_count = packet_in.packet_rx_success_count;
- packet1.packet_rx_drop_count = packet_in.packet_rx_drop_count;
- packet1.msg_received = packet_in.msg_received;
- packet1.buffer_overrun = packet_in.buffer_overrun;
- packet1.parse_error = packet_in.parse_error;
- packet1.packet_idx = packet_in.packet_idx;
- packet1.current_rx_seq = packet_in.current_rx_seq;
- packet1.current_tx_seq = packet_in.current_tx_seq;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MAVLINK_STATS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mavlink_stats_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_mavlink_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mavlink_stats_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.n_send_queue , packet1.max_send_queue , packet1.n_send_errors , packet1.msg_received , packet1.buffer_overrun , packet1.parse_error , packet1.parse_state , packet1.packet_idx , packet1.current_rx_seq , packet1.current_tx_seq , packet1.packet_rx_success_count , packet1.packet_rx_drop_count );
- mavlink_msg_mavlink_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mavlink_stats_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.n_send_queue , packet1.max_send_queue , packet1.n_send_errors , packet1.msg_received , packet1.buffer_overrun , packet1.parse_error , packet1.parse_state , packet1.packet_idx , packet1.current_rx_seq , packet1.current_tx_seq , packet1.packet_rx_success_count , packet1.packet_rx_drop_count );
- mavlink_msg_mavlink_stats_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_mavlink_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_mavlink_stats_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.n_send_queue , packet1.max_send_queue , packet1.n_send_errors , packet1.msg_received , packet1.buffer_overrun , packet1.parse_error , packet1.parse_state , packet1.packet_idx , packet1.current_rx_seq , packet1.current_tx_seq , packet1.packet_rx_success_count , packet1.packet_rx_drop_count );
- mavlink_msg_mavlink_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("MAVLINK_STATS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_MAVLINK_STATS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_task_stats_tm(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_TASK_STATS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_task_stats_tm_t packet_in = {
- 93372036854775807ULL,73.0,101.0,129.0,157.0,18483,211
- };
- mavlink_task_stats_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.task_min = packet_in.task_min;
- packet1.task_max = packet_in.task_max;
- packet1.task_mean = packet_in.task_mean;
- packet1.task_stddev = packet_in.task_stddev;
- packet1.task_period = packet_in.task_period;
- packet1.task_id = packet_in.task_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TASK_STATS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_task_stats_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_task_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_task_stats_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.task_id , packet1.task_period , packet1.task_min , packet1.task_max , packet1.task_mean , packet1.task_stddev );
- mavlink_msg_task_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_task_stats_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.task_id , packet1.task_period , packet1.task_min , packet1.task_max , packet1.task_mean , packet1.task_stddev );
- mavlink_msg_task_stats_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_task_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_task_stats_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.task_id , packet1.task_period , packet1.task_min , packet1.task_max , packet1.task_mean , packet1.task_stddev );
- mavlink_msg_task_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("TASK_STATS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_TASK_STATS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_ada_tm(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_ADA_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ada_tm_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,161
- };
- mavlink_ada_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.kalman_x0 = packet_in.kalman_x0;
- packet1.kalman_x1 = packet_in.kalman_x1;
- packet1.kalman_x2 = packet_in.kalman_x2;
- packet1.vertical_speed = packet_in.vertical_speed;
- packet1.msl_altitude = packet_in.msl_altitude;
- packet1.ref_pressure = packet_in.ref_pressure;
- packet1.ref_altitude = packet_in.ref_altitude;
- packet1.ref_temperature = packet_in.ref_temperature;
- packet1.msl_pressure = packet_in.msl_pressure;
- packet1.msl_temperature = packet_in.msl_temperature;
- packet1.dpl_altitude = packet_in.dpl_altitude;
- 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_ADA_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ADA_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ada_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ada_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ada_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.vertical_speed , packet1.msl_altitude , packet1.ref_pressure , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_pressure , packet1.msl_temperature , packet1.dpl_altitude );
- mavlink_msg_ada_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ada_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.vertical_speed , packet1.msl_altitude , packet1.ref_pressure , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_pressure , packet1.msl_temperature , packet1.dpl_altitude );
- mavlink_msg_ada_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ada_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ada_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state , packet1.kalman_x0 , packet1.kalman_x1 , packet1.kalman_x2 , packet1.vertical_speed , packet1.msl_altitude , packet1.ref_pressure , packet1.ref_altitude , packet1.ref_temperature , packet1.msl_pressure , packet1.msl_temperature , packet1.dpl_altitude );
- mavlink_msg_ada_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("ADA_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ADA_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_nas_tm(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_NAS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_nas_tm_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,437.0,465.0,493.0,521.0,233
- };
- mavlink_nas_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.nas_n = packet_in.nas_n;
- packet1.nas_e = packet_in.nas_e;
- packet1.nas_d = packet_in.nas_d;
- packet1.nas_vn = packet_in.nas_vn;
- packet1.nas_ve = packet_in.nas_ve;
- packet1.nas_vd = packet_in.nas_vd;
- packet1.nas_qx = packet_in.nas_qx;
- packet1.nas_qy = packet_in.nas_qy;
- packet1.nas_qz = packet_in.nas_qz;
- packet1.nas_qw = packet_in.nas_qw;
- packet1.nas_bias_x = packet_in.nas_bias_x;
- packet1.nas_bias_y = packet_in.nas_bias_y;
- packet1.nas_bias_z = packet_in.nas_bias_z;
- packet1.ref_pressure = packet_in.ref_pressure;
- packet1.ref_temperature = packet_in.ref_temperature;
- packet1.ref_latitude = packet_in.ref_latitude;
- packet1.ref_longitude = packet_in.ref_longitude;
- 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_NAS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NAS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nas_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_nas_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nas_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.ref_pressure , packet1.ref_temperature , packet1.ref_latitude , packet1.ref_longitude );
- mavlink_msg_nas_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nas_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.ref_pressure , packet1.ref_temperature , packet1.ref_latitude , packet1.ref_longitude );
- mavlink_msg_nas_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_nas_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nas_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.ref_pressure , packet1.ref_temperature , packet1.ref_latitude , packet1.ref_longitude );
- mavlink_msg_nas_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("NAS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_NAS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_rocket_flight_tm(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_ROCKET_FLIGHT_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_rocket_flight_tm_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,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,1081.0,217,28,95,162,229,40,107,174,241,52,119
- };
- mavlink_rocket_flight_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.pressure_ada = packet_in.pressure_ada;
- packet1.pressure_digi = packet_in.pressure_digi;
- packet1.pressure_static = packet_in.pressure_static;
- packet1.pressure_dpl = packet_in.pressure_dpl;
- packet1.airspeed_pitot = packet_in.airspeed_pitot;
- packet1.altitude_agl = packet_in.altitude_agl;
- packet1.ada_vert_speed = packet_in.ada_vert_speed;
- packet1.acc_x = packet_in.acc_x;
- packet1.acc_y = packet_in.acc_y;
- packet1.acc_z = packet_in.acc_z;
- packet1.gyro_x = packet_in.gyro_x;
- packet1.gyro_y = packet_in.gyro_y;
- packet1.gyro_z = packet_in.gyro_z;
- packet1.mag_x = packet_in.mag_x;
- packet1.mag_y = packet_in.mag_y;
- packet1.mag_z = packet_in.mag_z;
- packet1.gps_lat = packet_in.gps_lat;
- packet1.gps_lon = packet_in.gps_lon;
- packet1.gps_alt = packet_in.gps_alt;
- packet1.abk_angle = packet_in.abk_angle;
- packet1.abk_estimated_cd = packet_in.abk_estimated_cd;
- packet1.parachute_load = packet_in.parachute_load;
- packet1.nas_n = packet_in.nas_n;
- packet1.nas_e = packet_in.nas_e;
- packet1.nas_d = packet_in.nas_d;
- packet1.nas_vn = packet_in.nas_vn;
- packet1.nas_ve = packet_in.nas_ve;
- packet1.nas_vd = packet_in.nas_vd;
- packet1.nas_qx = packet_in.nas_qx;
- packet1.nas_qy = packet_in.nas_qy;
- packet1.nas_qz = packet_in.nas_qz;
- packet1.nas_qw = packet_in.nas_qw;
- packet1.nas_bias_x = packet_in.nas_bias_x;
- packet1.nas_bias_y = packet_in.nas_bias_y;
- packet1.nas_bias_z = packet_in.nas_bias_z;
- packet1.vbat = packet_in.vbat;
- packet1.temperature = packet_in.temperature;
- packet1.ada_state = packet_in.ada_state;
- packet1.fmm_state = packet_in.fmm_state;
- packet1.dpl_state = packet_in.dpl_state;
- packet1.abk_state = packet_in.abk_state;
- packet1.nas_state = packet_in.nas_state;
- packet1.gps_fix = packet_in.gps_fix;
- packet1.pin_launch = packet_in.pin_launch;
- packet1.pin_nosecone = packet_in.pin_nosecone;
- packet1.pin_expulsion = packet_in.pin_expulsion;
- packet1.cutter_presence = packet_in.cutter_presence;
- packet1.logger_error = packet_in.logger_error;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ROCKET_FLIGHT_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_flight_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_rocket_flight_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.abk_estimated_cd , packet1.parachute_load , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.vbat , packet1.temperature , packet1.logger_error );
- mavlink_msg_rocket_flight_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.abk_estimated_cd , packet1.parachute_load , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.vbat , packet1.temperature , packet1.logger_error );
- mavlink_msg_rocket_flight_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_rocket_flight_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.dpl_state , packet1.abk_state , packet1.nas_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.ada_vert_speed , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.abk_angle , packet1.abk_estimated_cd , packet1.parachute_load , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_launch , packet1.pin_nosecone , packet1.pin_expulsion , packet1.cutter_presence , packet1.vbat , packet1.temperature , packet1.logger_error );
- mavlink_msg_rocket_flight_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("ROCKET_FLIGHT_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ROCKET_FLIGHT_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_payload_flight_tm(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_PAYLOAD_FLIGHT_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_payload_flight_tm_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,437.0,465.0,493.0,521.0,549.0,577.0,605.0,633.0,661.0,689.0,717.0,745.0,773.0,801.0,829.0,857.0,885.0,913.0,941.0,969.0,997.0,1025.0,1053.0,205,16,83,150,217,28
- };
- mavlink_payload_flight_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.pressure_ada = packet_in.pressure_ada;
- packet1.pressure_digi = packet_in.pressure_digi;
- packet1.pressure_static = packet_in.pressure_static;
- packet1.pressure_dpl = packet_in.pressure_dpl;
- packet1.airspeed_pitot = packet_in.airspeed_pitot;
- packet1.altitude_agl = packet_in.altitude_agl;
- packet1.acc_x = packet_in.acc_x;
- packet1.acc_y = packet_in.acc_y;
- packet1.acc_z = packet_in.acc_z;
- packet1.gyro_x = packet_in.gyro_x;
- packet1.gyro_y = packet_in.gyro_y;
- packet1.gyro_z = packet_in.gyro_z;
- packet1.mag_x = packet_in.mag_x;
- packet1.mag_y = packet_in.mag_y;
- packet1.mag_z = packet_in.mag_z;
- packet1.gps_lat = packet_in.gps_lat;
- packet1.gps_lon = packet_in.gps_lon;
- packet1.gps_alt = packet_in.gps_alt;
- packet1.left_servo_angle = packet_in.left_servo_angle;
- packet1.right_servo_angle = packet_in.right_servo_angle;
- packet1.nas_n = packet_in.nas_n;
- packet1.nas_e = packet_in.nas_e;
- packet1.nas_d = packet_in.nas_d;
- packet1.nas_vn = packet_in.nas_vn;
- packet1.nas_ve = packet_in.nas_ve;
- packet1.nas_vd = packet_in.nas_vd;
- packet1.nas_qx = packet_in.nas_qx;
- packet1.nas_qy = packet_in.nas_qy;
- packet1.nas_qz = packet_in.nas_qz;
- packet1.nas_qw = packet_in.nas_qw;
- packet1.nas_bias_x = packet_in.nas_bias_x;
- packet1.nas_bias_y = packet_in.nas_bias_y;
- packet1.nas_bias_z = packet_in.nas_bias_z;
- packet1.vbat = packet_in.vbat;
- packet1.vsupply_5v = packet_in.vsupply_5v;
- packet1.temperature = packet_in.temperature;
- packet1.ada_state = packet_in.ada_state;
- packet1.fmm_state = packet_in.fmm_state;
- packet1.nas_state = packet_in.nas_state;
- packet1.gps_fix = packet_in.gps_fix;
- packet1.pin_nosecone = packet_in.pin_nosecone;
- packet1.logger_error = packet_in.logger_error;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_flight_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_payload_flight_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_flight_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.nas_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_nosecone , packet1.vbat , packet1.vsupply_5v , packet1.temperature , packet1.logger_error );
- mavlink_msg_payload_flight_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_flight_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.nas_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_nosecone , packet1.vbat , packet1.vsupply_5v , packet1.temperature , packet1.logger_error );
- mavlink_msg_payload_flight_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_payload_flight_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_flight_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.ada_state , packet1.fmm_state , packet1.nas_state , packet1.pressure_ada , packet1.pressure_digi , packet1.pressure_static , packet1.pressure_dpl , packet1.airspeed_pitot , packet1.altitude_agl , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.gyro_x , packet1.gyro_y , packet1.gyro_z , packet1.mag_x , packet1.mag_y , packet1.mag_z , packet1.gps_fix , packet1.gps_lat , packet1.gps_lon , packet1.gps_alt , packet1.left_servo_angle , packet1.right_servo_angle , packet1.nas_n , packet1.nas_e , packet1.nas_d , packet1.nas_vn , packet1.nas_ve , packet1.nas_vd , packet1.nas_qx , packet1.nas_qy , packet1.nas_qz , packet1.nas_qw , packet1.nas_bias_x , packet1.nas_bias_y , packet1.nas_bias_z , packet1.pin_nosecone , packet1.vbat , packet1.vsupply_5v , packet1.temperature , packet1.logger_error );
- mavlink_msg_payload_flight_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("PAYLOAD_FLIGHT_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_rocket_stats_tm(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_ROCKET_STATS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_rocket_stats_tm_t packet_in = {
- 93372036854775807ULL,93372036854776311ULL,93372036854776815ULL,93372036854777319ULL,93372036854777823ULL,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,605.0,963502040
- };
- mavlink_rocket_stats_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.liftoff_ts = packet_in.liftoff_ts;
- packet1.liftoff_max_acc_ts = packet_in.liftoff_max_acc_ts;
- packet1.dpl_ts = packet_in.dpl_ts;
- packet1.max_z_speed_ts = packet_in.max_z_speed_ts;
- packet1.apogee_ts = packet_in.apogee_ts;
- packet1.liftoff_max_acc = packet_in.liftoff_max_acc;
- packet1.dpl_max_acc = packet_in.dpl_max_acc;
- packet1.max_z_speed = packet_in.max_z_speed;
- packet1.max_airspeed_pitot = packet_in.max_airspeed_pitot;
- packet1.max_speed_altitude = packet_in.max_speed_altitude;
- packet1.apogee_lat = packet_in.apogee_lat;
- packet1.apogee_lon = packet_in.apogee_lon;
- packet1.apogee_alt = packet_in.apogee_alt;
- packet1.min_pressure = packet_in.min_pressure;
- packet1.ada_min_pressure = packet_in.ada_min_pressure;
- packet1.dpl_vane_max_pressure = packet_in.dpl_vane_max_pressure;
- packet1.cpu_load = packet_in.cpu_load;
- packet1.free_heap = packet_in.free_heap;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ROCKET_STATS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_stats_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_rocket_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_stats_tm_pack(system_id, component_id, &msg , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.ada_min_pressure , packet1.dpl_vane_max_pressure , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_rocket_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_stats_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.ada_min_pressure , packet1.dpl_vane_max_pressure , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_rocket_stats_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_rocket_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_rocket_stats_tm_send(MAVLINK_COMM_1 , packet1.liftoff_ts , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.ada_min_pressure , packet1.dpl_vane_max_pressure , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_rocket_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("ROCKET_STATS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_ROCKET_STATS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_payload_stats_tm(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_PAYLOAD_STATS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_payload_stats_tm_t packet_in = {
- 93372036854775807ULL,93372036854776311ULL,93372036854776815ULL,93372036854777319ULL,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,963501208
- };
- mavlink_payload_stats_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.liftoff_max_acc_ts = packet_in.liftoff_max_acc_ts;
- packet1.dpl_ts = packet_in.dpl_ts;
- packet1.max_z_speed_ts = packet_in.max_z_speed_ts;
- packet1.apogee_ts = packet_in.apogee_ts;
- packet1.liftoff_max_acc = packet_in.liftoff_max_acc;
- packet1.dpl_max_acc = packet_in.dpl_max_acc;
- packet1.max_z_speed = packet_in.max_z_speed;
- packet1.max_airspeed_pitot = packet_in.max_airspeed_pitot;
- packet1.max_speed_altitude = packet_in.max_speed_altitude;
- packet1.apogee_lat = packet_in.apogee_lat;
- packet1.apogee_lon = packet_in.apogee_lon;
- packet1.apogee_alt = packet_in.apogee_alt;
- packet1.min_pressure = packet_in.min_pressure;
- packet1.cpu_load = packet_in.cpu_load;
- packet1.free_heap = packet_in.free_heap;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PAYLOAD_STATS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_stats_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_payload_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_stats_tm_pack(system_id, component_id, &msg , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_payload_stats_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_stats_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_payload_stats_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_payload_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_payload_stats_tm_send(MAVLINK_COMM_1 , packet1.liftoff_max_acc_ts , packet1.liftoff_max_acc , packet1.dpl_ts , packet1.dpl_max_acc , packet1.max_z_speed_ts , packet1.max_z_speed , packet1.max_airspeed_pitot , packet1.max_speed_altitude , packet1.apogee_ts , packet1.apogee_lat , packet1.apogee_lon , packet1.apogee_alt , packet1.min_pressure , packet1.cpu_load , packet1.free_heap );
- mavlink_msg_payload_stats_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
-#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
- MAVLINK_ASSERT(mavlink_get_message_info_by_name("PAYLOAD_STATS_TM") != NULL);
- MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_PAYLOAD_STATS_TM) != NULL);
-#endif
-}
-
-static void mavlink_test_pyxis(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
-{
- mavlink_test_ping_tc(system_id, component_id, last_msg);
- mavlink_test_command_tc(system_id, component_id, last_msg);
- mavlink_test_system_tm_request_tc(system_id, component_id, last_msg);
- mavlink_test_sensor_tm_request_tc(system_id, component_id, last_msg);
- mavlink_test_servo_tm_request_tc(system_id, component_id, last_msg);
- mavlink_test_set_servo_angle_tc(system_id, component_id, last_msg);
- mavlink_test_wiggle_servo_tc(system_id, component_id, last_msg);
- mavlink_test_reset_servo_tc(system_id, component_id, last_msg);
- mavlink_test_set_reference_altitude_tc(system_id, component_id, last_msg);
- mavlink_test_set_reference_temperature_tc(system_id, component_id, last_msg);
- mavlink_test_set_orientation_tc(system_id, component_id, last_msg);
- mavlink_test_set_coordinates_tc(system_id, component_id, last_msg);
- mavlink_test_raw_event_tc(system_id, component_id, last_msg);
- mavlink_test_set_deployment_altitude_tc(system_id, component_id, last_msg);
- mavlink_test_set_target_coordinates_tc(system_id, component_id, last_msg);
- mavlink_test_set_algorithm_tc(system_id, component_id, last_msg);
- mavlink_test_ack_tm(system_id, component_id, last_msg);
- mavlink_test_nack_tm(system_id, component_id, last_msg);
- mavlink_test_gps_tm(system_id, component_id, last_msg);
- mavlink_test_imu_tm(system_id, component_id, last_msg);
- mavlink_test_pressure_tm(system_id, component_id, last_msg);
- mavlink_test_adc_tm(system_id, component_id, last_msg);
- mavlink_test_voltage_tm(system_id, component_id, last_msg);
- mavlink_test_current_tm(system_id, component_id, last_msg);
- mavlink_test_temp_tm(system_id, component_id, last_msg);
- mavlink_test_load_tm(system_id, component_id, last_msg);
- mavlink_test_attitude_tm(system_id, component_id, last_msg);
- mavlink_test_sensor_state_tm(system_id, component_id, last_msg);
- mavlink_test_servo_tm(system_id, component_id, last_msg);
- mavlink_test_pin_tm(system_id, component_id, last_msg);
- mavlink_test_receiver_tm(system_id, component_id, last_msg);
- mavlink_test_sys_tm(system_id, component_id, last_msg);
- mavlink_test_fsm_tm(system_id, component_id, last_msg);
- mavlink_test_logger_tm(system_id, component_id, last_msg);
- mavlink_test_mavlink_stats_tm(system_id, component_id, last_msg);
- mavlink_test_task_stats_tm(system_id, component_id, last_msg);
- mavlink_test_ada_tm(system_id, component_id, last_msg);
- mavlink_test_nas_tm(system_id, component_id, last_msg);
- mavlink_test_rocket_flight_tm(system_id, component_id, last_msg);
- mavlink_test_payload_flight_tm(system_id, component_id, last_msg);
- mavlink_test_rocket_stats_tm(system_id, component_id, last_msg);
- mavlink_test_payload_stats_tm(system_id, component_id, last_msg);
-}
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // PYXIS_TESTSUITE_H
diff --git a/mavlink_lib/pyxis/version.h b/mavlink_lib/pyxis/version.h
deleted file mode 100644
index 6b26d44c197af1cab3f9ef10bd95b9d0f6a5b518..0000000000000000000000000000000000000000
--- a/mavlink_lib/pyxis/version.h
+++ /dev/null
@@ -1,14 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol built from pyxis.xml
- * @see http://mavlink.org
- */
-#pragma once
-
-#ifndef MAVLINK_VERSION_H
-#define MAVLINK_VERSION_H
-
-#define MAVLINK_BUILD_DATE "Sat Oct 08 2022"
-#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
-#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 167
-
-#endif // MAVLINK_VERSION_H
diff --git a/mavlink_lib/r2a/mavlink.h b/mavlink_lib/r2a/mavlink.h
deleted file mode 100644
index d95573adbfb49b2f1e41af500f9dc8fcabdcd8ab..0000000000000000000000000000000000000000
--- a/mavlink_lib/r2a/mavlink.h
+++ /dev/null
@@ -1,34 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol built from r2a.xml
- * @see http://mavlink.org
- */
-#pragma once
-#ifndef MAVLINK_H
-#define MAVLINK_H
-
-#define MAVLINK_PRIMARY_XML_IDX 0
-
-#ifndef MAVLINK_STX
-#define MAVLINK_STX 254
-#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 0
-#endif
-
-#include "version.h"
-#include "r2a.h"
-
-#endif // MAVLINK_H
diff --git a/mavlink_lib/r2a/mavlink_msg_ack_tm.h b/mavlink_lib/r2a/mavlink_msg_ack_tm.h
deleted file mode 100644
index cde26ee2c5160270c275dc1ab1c228d0890bc741..0000000000000000000000000000000000000000
--- a/mavlink_lib/r2a/mavlink_msg_ack_tm.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE ACK_TM PACKING
-
-#define MAVLINK_MSG_ID_ACK_TM 130
-
-MAVPACKED(
-typedef struct __mavlink_ack_tm_t {
- uint8_t recv_msgid; /*< Message id of the received message.*/
- uint8_t seq_ack; /*< Sequence number of the received message.*/
-}) mavlink_ack_tm_t;
-
-#define MAVLINK_MSG_ID_ACK_TM_LEN 2
-#define MAVLINK_MSG_ID_ACK_TM_MIN_LEN 2
-#define MAVLINK_MSG_ID_130_LEN 2
-#define MAVLINK_MSG_ID_130_MIN_LEN 2
-
-#define MAVLINK_MSG_ID_ACK_TM_CRC 50
-#define MAVLINK_MSG_ID_130_CRC 50
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_ACK_TM { \
- 130, \
- "ACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_ack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_ack_tm_t, seq_ack) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_ACK_TM { \
- "ACK_TM", \
- 2, \
- { { "recv_msgid", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_ack_tm_t, recv_msgid) }, \
- { "seq_ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_ack_tm_t, seq_ack) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ack_tm 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 recv_msgid Message id of the received message.
- * @param seq_ack Sequence number of the received message.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ack_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACK_TM_LEN);
-#else
- mavlink_ack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ACK_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-}
-
-/**
- * @brief Pack a ack_tm 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 recv_msgid Message id of the received message.
- * @param seq_ack Sequence number of the received message.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ack_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t recv_msgid,uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACK_TM_LEN);
-#else
- mavlink_ack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACK_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ACK_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-}
-
-/**
- * @brief Encode a ack_tm 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 ack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ack_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ack_tm_t* ack_tm)
-{
- return mavlink_msg_ack_tm_pack(system_id, component_id, msg, ack_tm->recv_msgid, ack_tm->seq_ack);
-}
-
-/**
- * @brief Encode a ack_tm 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 ack_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ack_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ack_tm_t* ack_tm)
-{
- return mavlink_msg_ack_tm_pack_chan(system_id, component_id, chan, msg, ack_tm->recv_msgid, ack_tm->seq_ack);
-}
-
-/**
- * @brief Send a ack_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param recv_msgid Message id of the received message.
- * @param seq_ack Sequence number of the received message.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ack_tm_send(mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ACK_TM_LEN];
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, buf, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#else
- mavlink_ack_tm_t packet;
- packet.recv_msgid = recv_msgid;
- packet.seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, (const char *)&packet, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a ack_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ack_tm_send_struct(mavlink_channel_t chan, const mavlink_ack_tm_t* ack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ack_tm_send(chan, ack_tm->recv_msgid, ack_tm->seq_ack);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, (const char *)ack_tm, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_ACK_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_ack_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t recv_msgid, uint8_t seq_ack)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, recv_msgid);
- _mav_put_uint8_t(buf, 1, seq_ack);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, buf, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#else
- mavlink_ack_tm_t *packet = (mavlink_ack_tm_t *)msgbuf;
- packet->recv_msgid = recv_msgid;
- packet->seq_ack = seq_ack;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACK_TM, (const char *)packet, MAVLINK_MSG_ID_ACK_TM_MIN_LEN, MAVLINK_MSG_ID_ACK_TM_LEN, MAVLINK_MSG_ID_ACK_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE ACK_TM UNPACKING
-
-
-/**
- * @brief Get field recv_msgid from ack_tm message
- *
- * @return Message id of the received message.
- */
-static inline uint8_t mavlink_msg_ack_tm_get_recv_msgid(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field seq_ack from ack_tm message
- *
- * @return Sequence number of the received message.
- */
-static inline uint8_t mavlink_msg_ack_tm_get_seq_ack(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Decode a ack_tm message into a struct
- *
- * @param msg The message to decode
- * @param ack_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ack_tm_decode(const mavlink_message_t* msg, mavlink_ack_tm_t* ack_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ack_tm->recv_msgid = mavlink_msg_ack_tm_get_recv_msgid(msg);
- ack_tm->seq_ack = mavlink_msg_ack_tm_get_seq_ack(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ACK_TM_LEN? msg->len : MAVLINK_MSG_ID_ACK_TM_LEN;
- memset(ack_tm, 0, MAVLINK_MSG_ID_ACK_TM_LEN);
- memcpy(ack_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/r2a/mavlink_msg_homeone_status_tm.h b/mavlink_lib/r2a/mavlink_msg_homeone_status_tm.h
deleted file mode 100644
index de846ea51436a7f427905afccd7e229a5f79d918..0000000000000000000000000000000000000000
--- a/mavlink_lib/r2a/mavlink_msg_homeone_status_tm.h
+++ /dev/null
@@ -1,305 +0,0 @@
-#pragma once
-// MESSAGE HOMEONE_STATUS_TM PACKING
-
-#define MAVLINK_MSG_ID_HOMEONE_STATUS_TM 140
-
-MAVPACKED(
-typedef struct __mavlink_homeone_status_tm_t {
- uint8_t sampling_status; /*< True=Sampling enabled, False=Sampling disabled.*/
- uint8_t FMM_current_state; /*< Value of FMM_STATE_ENUM.*/
- uint8_t log_status; /*< True=Log active, False=Log not active.*/
- char umbilical_connection_status; /*< True=Umbilical connected, False=Umbilical not connected,*/
- uint8_t fault_counter_array[15]; /*< Array of all the fault counters in the system. //TODO set the correct size*/
-}) mavlink_homeone_status_tm_t;
-
-#define MAVLINK_MSG_ID_HOMEONE_STATUS_TM_LEN 19
-#define MAVLINK_MSG_ID_HOMEONE_STATUS_TM_MIN_LEN 19
-#define MAVLINK_MSG_ID_140_LEN 19
-#define MAVLINK_MSG_ID_140_MIN_LEN 19
-
-#define MAVLINK_MSG_ID_HOMEONE_STATUS_TM_CRC 119
-#define MAVLINK_MSG_ID_140_CRC 119
-
-#define MAVLINK_MSG_HOMEONE_STATUS_TM_FIELD_FAULT_COUNTER_ARRAY_LEN 15
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_HOMEONE_STATUS_TM { \
- 140, \
- "HOMEONE_STATUS_TM", \
- 5, \
- { { "sampling_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_homeone_status_tm_t, sampling_status) }, \
- { "FMM_current_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_homeone_status_tm_t, FMM_current_state) }, \
- { "log_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_homeone_status_tm_t, log_status) }, \
- { "umbilical_connection_status", NULL, MAVLINK_TYPE_CHAR, 0, 3, offsetof(mavlink_homeone_status_tm_t, umbilical_connection_status) }, \
- { "fault_counter_array", NULL, MAVLINK_TYPE_UINT8_T, 15, 4, offsetof(mavlink_homeone_status_tm_t, fault_counter_array) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_HOMEONE_STATUS_TM { \
- "HOMEONE_STATUS_TM", \
- 5, \
- { { "sampling_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_homeone_status_tm_t, sampling_status) }, \
- { "FMM_current_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_homeone_status_tm_t, FMM_current_state) }, \
- { "log_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_homeone_status_tm_t, log_status) }, \
- { "umbilical_connection_status", NULL, MAVLINK_TYPE_CHAR, 0, 3, offsetof(mavlink_homeone_status_tm_t, umbilical_connection_status) }, \
- { "fault_counter_array", NULL, MAVLINK_TYPE_UINT8_T, 15, 4, offsetof(mavlink_homeone_status_tm_t, fault_counter_array) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a homeone_status_tm 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 sampling_status True=Sampling enabled, False=Sampling disabled.
- * @param FMM_current_state Value of FMM_STATE_ENUM.
- * @param log_status True=Log active, False=Log not active.
- * @param umbilical_connection_status True=Umbilical connected, False=Umbilical not connected,
- * @param fault_counter_array Array of all the fault counters in the system. //TODO set the correct size
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_homeone_status_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t sampling_status, uint8_t FMM_current_state, uint8_t log_status, char umbilical_connection_status, const uint8_t *fault_counter_array)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_HOMEONE_STATUS_TM_LEN];
- _mav_put_uint8_t(buf, 0, sampling_status);
- _mav_put_uint8_t(buf, 1, FMM_current_state);
- _mav_put_uint8_t(buf, 2, log_status);
- _mav_put_char(buf, 3, umbilical_connection_status);
- _mav_put_uint8_t_array(buf, 4, fault_counter_array, 15);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_LEN);
-#else
- mavlink_homeone_status_tm_t packet;
- packet.sampling_status = sampling_status;
- packet.FMM_current_state = FMM_current_state;
- packet.log_status = log_status;
- packet.umbilical_connection_status = umbilical_connection_status;
- mav_array_memcpy(packet.fault_counter_array, fault_counter_array, sizeof(uint8_t)*15);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_HOMEONE_STATUS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_LEN, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_CRC);
-}
-
-/**
- * @brief Pack a homeone_status_tm 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 sampling_status True=Sampling enabled, False=Sampling disabled.
- * @param FMM_current_state Value of FMM_STATE_ENUM.
- * @param log_status True=Log active, False=Log not active.
- * @param umbilical_connection_status True=Umbilical connected, False=Umbilical not connected,
- * @param fault_counter_array Array of all the fault counters in the system. //TODO set the correct size
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_homeone_status_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t sampling_status,uint8_t FMM_current_state,uint8_t log_status,char umbilical_connection_status,const uint8_t *fault_counter_array)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_HOMEONE_STATUS_TM_LEN];
- _mav_put_uint8_t(buf, 0, sampling_status);
- _mav_put_uint8_t(buf, 1, FMM_current_state);
- _mav_put_uint8_t(buf, 2, log_status);
- _mav_put_char(buf, 3, umbilical_connection_status);
- _mav_put_uint8_t_array(buf, 4, fault_counter_array, 15);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_LEN);
-#else
- mavlink_homeone_status_tm_t packet;
- packet.sampling_status = sampling_status;
- packet.FMM_current_state = FMM_current_state;
- packet.log_status = log_status;
- packet.umbilical_connection_status = umbilical_connection_status;
- mav_array_memcpy(packet.fault_counter_array, fault_counter_array, sizeof(uint8_t)*15);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_HOMEONE_STATUS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_LEN, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_CRC);
-}
-
-/**
- * @brief Encode a homeone_status_tm 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 homeone_status_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_homeone_status_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_homeone_status_tm_t* homeone_status_tm)
-{
- return mavlink_msg_homeone_status_tm_pack(system_id, component_id, msg, homeone_status_tm->sampling_status, homeone_status_tm->FMM_current_state, homeone_status_tm->log_status, homeone_status_tm->umbilical_connection_status, homeone_status_tm->fault_counter_array);
-}
-
-/**
- * @brief Encode a homeone_status_tm 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 homeone_status_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_homeone_status_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_homeone_status_tm_t* homeone_status_tm)
-{
- return mavlink_msg_homeone_status_tm_pack_chan(system_id, component_id, chan, msg, homeone_status_tm->sampling_status, homeone_status_tm->FMM_current_state, homeone_status_tm->log_status, homeone_status_tm->umbilical_connection_status, homeone_status_tm->fault_counter_array);
-}
-
-/**
- * @brief Send a homeone_status_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param sampling_status True=Sampling enabled, False=Sampling disabled.
- * @param FMM_current_state Value of FMM_STATE_ENUM.
- * @param log_status True=Log active, False=Log not active.
- * @param umbilical_connection_status True=Umbilical connected, False=Umbilical not connected,
- * @param fault_counter_array Array of all the fault counters in the system. //TODO set the correct size
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_homeone_status_tm_send(mavlink_channel_t chan, uint8_t sampling_status, uint8_t FMM_current_state, uint8_t log_status, char umbilical_connection_status, const uint8_t *fault_counter_array)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_HOMEONE_STATUS_TM_LEN];
- _mav_put_uint8_t(buf, 0, sampling_status);
- _mav_put_uint8_t(buf, 1, FMM_current_state);
- _mav_put_uint8_t(buf, 2, log_status);
- _mav_put_char(buf, 3, umbilical_connection_status);
- _mav_put_uint8_t_array(buf, 4, fault_counter_array, 15);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOMEONE_STATUS_TM, buf, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_LEN, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_CRC);
-#else
- mavlink_homeone_status_tm_t packet;
- packet.sampling_status = sampling_status;
- packet.FMM_current_state = FMM_current_state;
- packet.log_status = log_status;
- packet.umbilical_connection_status = umbilical_connection_status;
- mav_array_memcpy(packet.fault_counter_array, fault_counter_array, sizeof(uint8_t)*15);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOMEONE_STATUS_TM, (const char *)&packet, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_LEN, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a homeone_status_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_homeone_status_tm_send_struct(mavlink_channel_t chan, const mavlink_homeone_status_tm_t* homeone_status_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_homeone_status_tm_send(chan, homeone_status_tm->sampling_status, homeone_status_tm->FMM_current_state, homeone_status_tm->log_status, homeone_status_tm->umbilical_connection_status, homeone_status_tm->fault_counter_array);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOMEONE_STATUS_TM, (const char *)homeone_status_tm, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_LEN, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_HOMEONE_STATUS_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_homeone_status_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t sampling_status, uint8_t FMM_current_state, uint8_t log_status, char umbilical_connection_status, const uint8_t *fault_counter_array)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, sampling_status);
- _mav_put_uint8_t(buf, 1, FMM_current_state);
- _mav_put_uint8_t(buf, 2, log_status);
- _mav_put_char(buf, 3, umbilical_connection_status);
- _mav_put_uint8_t_array(buf, 4, fault_counter_array, 15);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOMEONE_STATUS_TM, buf, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_LEN, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_CRC);
-#else
- mavlink_homeone_status_tm_t *packet = (mavlink_homeone_status_tm_t *)msgbuf;
- packet->sampling_status = sampling_status;
- packet->FMM_current_state = FMM_current_state;
- packet->log_status = log_status;
- packet->umbilical_connection_status = umbilical_connection_status;
- mav_array_memcpy(packet->fault_counter_array, fault_counter_array, sizeof(uint8_t)*15);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOMEONE_STATUS_TM, (const char *)packet, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_LEN, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE HOMEONE_STATUS_TM UNPACKING
-
-
-/**
- * @brief Get field sampling_status from homeone_status_tm message
- *
- * @return True=Sampling enabled, False=Sampling disabled.
- */
-static inline uint8_t mavlink_msg_homeone_status_tm_get_sampling_status(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field FMM_current_state from homeone_status_tm message
- *
- * @return Value of FMM_STATE_ENUM.
- */
-static inline uint8_t mavlink_msg_homeone_status_tm_get_FMM_current_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Get field log_status from homeone_status_tm message
- *
- * @return True=Log active, False=Log not active.
- */
-static inline uint8_t mavlink_msg_homeone_status_tm_get_log_status(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 2);
-}
-
-/**
- * @brief Get field umbilical_connection_status from homeone_status_tm message
- *
- * @return True=Umbilical connected, False=Umbilical not connected,
- */
-static inline char mavlink_msg_homeone_status_tm_get_umbilical_connection_status(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_char(msg, 3);
-}
-
-/**
- * @brief Get field fault_counter_array from homeone_status_tm message
- *
- * @return Array of all the fault counters in the system. //TODO set the correct size
- */
-static inline uint16_t mavlink_msg_homeone_status_tm_get_fault_counter_array(const mavlink_message_t* msg, uint8_t *fault_counter_array)
-{
- return _MAV_RETURN_uint8_t_array(msg, fault_counter_array, 15, 4);
-}
-
-/**
- * @brief Decode a homeone_status_tm message into a struct
- *
- * @param msg The message to decode
- * @param homeone_status_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_homeone_status_tm_decode(const mavlink_message_t* msg, mavlink_homeone_status_tm_t* homeone_status_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- homeone_status_tm->sampling_status = mavlink_msg_homeone_status_tm_get_sampling_status(msg);
- homeone_status_tm->FMM_current_state = mavlink_msg_homeone_status_tm_get_FMM_current_state(msg);
- homeone_status_tm->log_status = mavlink_msg_homeone_status_tm_get_log_status(msg);
- homeone_status_tm->umbilical_connection_status = mavlink_msg_homeone_status_tm_get_umbilical_connection_status(msg);
- mavlink_msg_homeone_status_tm_get_fault_counter_array(msg, homeone_status_tm->fault_counter_array);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_HOMEONE_STATUS_TM_LEN? msg->len : MAVLINK_MSG_ID_HOMEONE_STATUS_TM_LEN;
- memset(homeone_status_tm, 0, MAVLINK_MSG_ID_HOMEONE_STATUS_TM_LEN);
- memcpy(homeone_status_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/r2a/mavlink_msg_hr_sample_data_tm.h b/mavlink_lib/r2a/mavlink_msg_hr_sample_data_tm.h
deleted file mode 100644
index 3e42dc96ec8f6d307e3a82fbd6f25383dd88a728..0000000000000000000000000000000000000000
--- a/mavlink_lib/r2a/mavlink_msg_hr_sample_data_tm.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE HR_SAMPLE_DATA_TM PACKING
-
-#define MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM 155
-
-MAVPACKED(
-typedef struct __mavlink_hr_sample_data_tm_t {
- uint16_t pressure; /*< Pressure value in raw value //TODO: add calibration curve*/
-}) mavlink_hr_sample_data_tm_t;
-
-#define MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_LEN 2
-#define MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_MIN_LEN 2
-#define MAVLINK_MSG_ID_155_LEN 2
-#define MAVLINK_MSG_ID_155_MIN_LEN 2
-
-#define MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_CRC 50
-#define MAVLINK_MSG_ID_155_CRC 50
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_HR_SAMPLE_DATA_TM { \
- 155, \
- "HR_SAMPLE_DATA_TM", \
- 1, \
- { { "pressure", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_hr_sample_data_tm_t, pressure) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_HR_SAMPLE_DATA_TM { \
- "HR_SAMPLE_DATA_TM", \
- 1, \
- { { "pressure", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_hr_sample_data_tm_t, pressure) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a hr_sample_data_tm 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 pressure Pressure value in raw value //TODO: add calibration curve
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_hr_sample_data_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint16_t pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_LEN];
- _mav_put_uint16_t(buf, 0, pressure);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_LEN);
-#else
- mavlink_hr_sample_data_tm_t packet;
- packet.pressure = pressure;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_MIN_LEN, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_LEN, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_CRC);
-}
-
-/**
- * @brief Pack a hr_sample_data_tm 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 pressure Pressure value in raw value //TODO: add calibration curve
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_hr_sample_data_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint16_t pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_LEN];
- _mav_put_uint16_t(buf, 0, pressure);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_LEN);
-#else
- mavlink_hr_sample_data_tm_t packet;
- packet.pressure = pressure;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_MIN_LEN, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_LEN, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_CRC);
-}
-
-/**
- * @brief Encode a hr_sample_data_tm 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 hr_sample_data_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_hr_sample_data_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hr_sample_data_tm_t* hr_sample_data_tm)
-{
- return mavlink_msg_hr_sample_data_tm_pack(system_id, component_id, msg, hr_sample_data_tm->pressure);
-}
-
-/**
- * @brief Encode a hr_sample_data_tm 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 hr_sample_data_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_hr_sample_data_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hr_sample_data_tm_t* hr_sample_data_tm)
-{
- return mavlink_msg_hr_sample_data_tm_pack_chan(system_id, component_id, chan, msg, hr_sample_data_tm->pressure);
-}
-
-/**
- * @brief Send a hr_sample_data_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param pressure Pressure value in raw value //TODO: add calibration curve
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_hr_sample_data_tm_send(mavlink_channel_t chan, uint16_t pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_LEN];
- _mav_put_uint16_t(buf, 0, pressure);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM, buf, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_MIN_LEN, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_LEN, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_CRC);
-#else
- mavlink_hr_sample_data_tm_t packet;
- packet.pressure = pressure;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM, (const char *)&packet, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_MIN_LEN, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_LEN, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a hr_sample_data_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_hr_sample_data_tm_send_struct(mavlink_channel_t chan, const mavlink_hr_sample_data_tm_t* hr_sample_data_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_hr_sample_data_tm_send(chan, hr_sample_data_tm->pressure);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM, (const char *)hr_sample_data_tm, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_MIN_LEN, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_LEN, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_hr_sample_data_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t pressure)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint16_t(buf, 0, pressure);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM, buf, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_MIN_LEN, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_LEN, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_CRC);
-#else
- mavlink_hr_sample_data_tm_t *packet = (mavlink_hr_sample_data_tm_t *)msgbuf;
- packet->pressure = pressure;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM, (const char *)packet, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_MIN_LEN, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_LEN, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE HR_SAMPLE_DATA_TM UNPACKING
-
-
-/**
- * @brief Get field pressure from hr_sample_data_tm message
- *
- * @return Pressure value in raw value //TODO: add calibration curve
- */
-static inline uint16_t mavlink_msg_hr_sample_data_tm_get_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 0);
-}
-
-/**
- * @brief Decode a hr_sample_data_tm message into a struct
- *
- * @param msg The message to decode
- * @param hr_sample_data_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_hr_sample_data_tm_decode(const mavlink_message_t* msg, mavlink_hr_sample_data_tm_t* hr_sample_data_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- hr_sample_data_tm->pressure = mavlink_msg_hr_sample_data_tm_get_pressure(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_LEN? msg->len : MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_LEN;
- memset(hr_sample_data_tm, 0, MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_LEN);
- memcpy(hr_sample_data_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/r2a/mavlink_msg_ignition_status_tm.h b/mavlink_lib/r2a/mavlink_msg_ignition_status_tm.h
deleted file mode 100644
index dc615dd263063a4f095226d146067560d8db3343..0000000000000000000000000000000000000000
--- a/mavlink_lib/r2a/mavlink_msg_ignition_status_tm.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE IGNITION_STATUS_TM PACKING
-
-#define MAVLINK_MSG_ID_IGNITION_STATUS_TM 142
-
-MAVPACKED(
-typedef struct __mavlink_ignition_status_tm_t {
- uint8_t connected; /*< If False the other value are not valid.*/
- uint8_t ignition_state; /*< Value of IGNITION_STATUS_ENUM.*/
-}) mavlink_ignition_status_tm_t;
-
-#define MAVLINK_MSG_ID_IGNITION_STATUS_TM_LEN 2
-#define MAVLINK_MSG_ID_IGNITION_STATUS_TM_MIN_LEN 2
-#define MAVLINK_MSG_ID_142_LEN 2
-#define MAVLINK_MSG_ID_142_MIN_LEN 2
-
-#define MAVLINK_MSG_ID_IGNITION_STATUS_TM_CRC 55
-#define MAVLINK_MSG_ID_142_CRC 55
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_IGNITION_STATUS_TM { \
- 142, \
- "IGNITION_STATUS_TM", \
- 2, \
- { { "connected", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_ignition_status_tm_t, connected) }, \
- { "ignition_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_ignition_status_tm_t, ignition_state) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_IGNITION_STATUS_TM { \
- "IGNITION_STATUS_TM", \
- 2, \
- { { "connected", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_ignition_status_tm_t, connected) }, \
- { "ignition_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_ignition_status_tm_t, ignition_state) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ignition_status_tm 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 connected If False the other value are not valid.
- * @param ignition_state Value of IGNITION_STATUS_ENUM.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ignition_status_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t connected, uint8_t ignition_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_IGNITION_STATUS_TM_LEN];
- _mav_put_uint8_t(buf, 0, connected);
- _mav_put_uint8_t(buf, 1, ignition_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IGNITION_STATUS_TM_LEN);
-#else
- mavlink_ignition_status_tm_t packet;
- packet.connected = connected;
- packet.ignition_state = ignition_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IGNITION_STATUS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_IGNITION_STATUS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_IGNITION_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_IGNITION_STATUS_TM_LEN, MAVLINK_MSG_ID_IGNITION_STATUS_TM_CRC);
-}
-
-/**
- * @brief Pack a ignition_status_tm 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 connected If False the other value are not valid.
- * @param ignition_state Value of IGNITION_STATUS_ENUM.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ignition_status_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t connected,uint8_t ignition_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_IGNITION_STATUS_TM_LEN];
- _mav_put_uint8_t(buf, 0, connected);
- _mav_put_uint8_t(buf, 1, ignition_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IGNITION_STATUS_TM_LEN);
-#else
- mavlink_ignition_status_tm_t packet;
- packet.connected = connected;
- packet.ignition_state = ignition_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IGNITION_STATUS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_IGNITION_STATUS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_IGNITION_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_IGNITION_STATUS_TM_LEN, MAVLINK_MSG_ID_IGNITION_STATUS_TM_CRC);
-}
-
-/**
- * @brief Encode a ignition_status_tm 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 ignition_status_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ignition_status_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ignition_status_tm_t* ignition_status_tm)
-{
- return mavlink_msg_ignition_status_tm_pack(system_id, component_id, msg, ignition_status_tm->connected, ignition_status_tm->ignition_state);
-}
-
-/**
- * @brief Encode a ignition_status_tm 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 ignition_status_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ignition_status_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ignition_status_tm_t* ignition_status_tm)
-{
- return mavlink_msg_ignition_status_tm_pack_chan(system_id, component_id, chan, msg, ignition_status_tm->connected, ignition_status_tm->ignition_state);
-}
-
-/**
- * @brief Send a ignition_status_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param connected If False the other value are not valid.
- * @param ignition_state Value of IGNITION_STATUS_ENUM.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ignition_status_tm_send(mavlink_channel_t chan, uint8_t connected, uint8_t ignition_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_IGNITION_STATUS_TM_LEN];
- _mav_put_uint8_t(buf, 0, connected);
- _mav_put_uint8_t(buf, 1, ignition_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IGNITION_STATUS_TM, buf, MAVLINK_MSG_ID_IGNITION_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_IGNITION_STATUS_TM_LEN, MAVLINK_MSG_ID_IGNITION_STATUS_TM_CRC);
-#else
- mavlink_ignition_status_tm_t packet;
- packet.connected = connected;
- packet.ignition_state = ignition_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IGNITION_STATUS_TM, (const char *)&packet, MAVLINK_MSG_ID_IGNITION_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_IGNITION_STATUS_TM_LEN, MAVLINK_MSG_ID_IGNITION_STATUS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a ignition_status_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ignition_status_tm_send_struct(mavlink_channel_t chan, const mavlink_ignition_status_tm_t* ignition_status_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ignition_status_tm_send(chan, ignition_status_tm->connected, ignition_status_tm->ignition_state);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IGNITION_STATUS_TM, (const char *)ignition_status_tm, MAVLINK_MSG_ID_IGNITION_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_IGNITION_STATUS_TM_LEN, MAVLINK_MSG_ID_IGNITION_STATUS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_IGNITION_STATUS_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_ignition_status_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t connected, uint8_t ignition_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, connected);
- _mav_put_uint8_t(buf, 1, ignition_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IGNITION_STATUS_TM, buf, MAVLINK_MSG_ID_IGNITION_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_IGNITION_STATUS_TM_LEN, MAVLINK_MSG_ID_IGNITION_STATUS_TM_CRC);
-#else
- mavlink_ignition_status_tm_t *packet = (mavlink_ignition_status_tm_t *)msgbuf;
- packet->connected = connected;
- packet->ignition_state = ignition_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IGNITION_STATUS_TM, (const char *)packet, MAVLINK_MSG_ID_IGNITION_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_IGNITION_STATUS_TM_LEN, MAVLINK_MSG_ID_IGNITION_STATUS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE IGNITION_STATUS_TM UNPACKING
-
-
-/**
- * @brief Get field connected from ignition_status_tm message
- *
- * @return If False the other value are not valid.
- */
-static inline uint8_t mavlink_msg_ignition_status_tm_get_connected(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field ignition_state from ignition_status_tm message
- *
- * @return Value of IGNITION_STATUS_ENUM.
- */
-static inline uint8_t mavlink_msg_ignition_status_tm_get_ignition_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Decode a ignition_status_tm message into a struct
- *
- * @param msg The message to decode
- * @param ignition_status_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ignition_status_tm_decode(const mavlink_message_t* msg, mavlink_ignition_status_tm_t* ignition_status_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ignition_status_tm->connected = mavlink_msg_ignition_status_tm_get_connected(msg);
- ignition_status_tm->ignition_state = mavlink_msg_ignition_status_tm_get_ignition_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_IGNITION_STATUS_TM_LEN? msg->len : MAVLINK_MSG_ID_IGNITION_STATUS_TM_LEN;
- memset(ignition_status_tm, 0, MAVLINK_MSG_ID_IGNITION_STATUS_TM_LEN);
- memcpy(ignition_status_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/r2a/mavlink_msg_lr_sample_data_tm.h b/mavlink_lib/r2a/mavlink_msg_lr_sample_data_tm.h
deleted file mode 100644
index 284e698c4990762b5527a080592fd03fd67b1af0..0000000000000000000000000000000000000000
--- a/mavlink_lib/r2a/mavlink_msg_lr_sample_data_tm.h
+++ /dev/null
@@ -1,363 +0,0 @@
-#pragma once
-// MESSAGE LR_SAMPLE_DATA_TM PACKING
-
-#define MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM 150
-
-MAVPACKED(
-typedef struct __mavlink_lr_sample_data_tm_t {
- uint16_t pressure; /*< Pressure value in raw value //TODO: add calibration curve*/
- uint16_t imu1_acc_x; /*< Raw acceleration value of the x axis of the ADIS imu*/
- uint16_t imu1_acc_y; /*< Raw acceleration value of the y axis of the ADIS imu*/
- uint16_t imu1_acc_z; /*< Raw acceleration value of the z axis of the ADIS imu*/
- uint16_t imu1_gyr_x; /*< Raw gyro value of the x axis of the ADIS imu*/
- uint16_t imu1_gyr_y; /*< Raw gyro value of the y axis of the ADIS imu*/
- uint16_t imu1_gyr_z; /*< Raw gyro value of the z axis of the ADIS imu*/
-}) mavlink_lr_sample_data_tm_t;
-
-#define MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_LEN 14
-#define MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_MIN_LEN 14
-#define MAVLINK_MSG_ID_150_LEN 14
-#define MAVLINK_MSG_ID_150_MIN_LEN 14
-
-#define MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_CRC 244
-#define MAVLINK_MSG_ID_150_CRC 244
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_LR_SAMPLE_DATA_TM { \
- 150, \
- "LR_SAMPLE_DATA_TM", \
- 7, \
- { { "pressure", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_lr_sample_data_tm_t, pressure) }, \
- { "imu1_acc_x", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_lr_sample_data_tm_t, imu1_acc_x) }, \
- { "imu1_acc_y", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_lr_sample_data_tm_t, imu1_acc_y) }, \
- { "imu1_acc_z", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_lr_sample_data_tm_t, imu1_acc_z) }, \
- { "imu1_gyr_x", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_lr_sample_data_tm_t, imu1_gyr_x) }, \
- { "imu1_gyr_y", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_lr_sample_data_tm_t, imu1_gyr_y) }, \
- { "imu1_gyr_z", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_lr_sample_data_tm_t, imu1_gyr_z) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_LR_SAMPLE_DATA_TM { \
- "LR_SAMPLE_DATA_TM", \
- 7, \
- { { "pressure", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_lr_sample_data_tm_t, pressure) }, \
- { "imu1_acc_x", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_lr_sample_data_tm_t, imu1_acc_x) }, \
- { "imu1_acc_y", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_lr_sample_data_tm_t, imu1_acc_y) }, \
- { "imu1_acc_z", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_lr_sample_data_tm_t, imu1_acc_z) }, \
- { "imu1_gyr_x", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_lr_sample_data_tm_t, imu1_gyr_x) }, \
- { "imu1_gyr_y", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_lr_sample_data_tm_t, imu1_gyr_y) }, \
- { "imu1_gyr_z", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_lr_sample_data_tm_t, imu1_gyr_z) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a lr_sample_data_tm 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 pressure Pressure value in raw value //TODO: add calibration curve
- * @param imu1_acc_x Raw acceleration value of the x axis of the ADIS imu
- * @param imu1_acc_y Raw acceleration value of the y axis of the ADIS imu
- * @param imu1_acc_z Raw acceleration value of the z axis of the ADIS imu
- * @param imu1_gyr_x Raw gyro value of the x axis of the ADIS imu
- * @param imu1_gyr_y Raw gyro value of the y axis of the ADIS imu
- * @param imu1_gyr_z Raw gyro value of the z axis of the ADIS imu
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_lr_sample_data_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint16_t pressure, uint16_t imu1_acc_x, uint16_t imu1_acc_y, uint16_t imu1_acc_z, uint16_t imu1_gyr_x, uint16_t imu1_gyr_y, uint16_t imu1_gyr_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_LEN];
- _mav_put_uint16_t(buf, 0, pressure);
- _mav_put_uint16_t(buf, 2, imu1_acc_x);
- _mav_put_uint16_t(buf, 4, imu1_acc_y);
- _mav_put_uint16_t(buf, 6, imu1_acc_z);
- _mav_put_uint16_t(buf, 8, imu1_gyr_x);
- _mav_put_uint16_t(buf, 10, imu1_gyr_y);
- _mav_put_uint16_t(buf, 12, imu1_gyr_z);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_LEN);
-#else
- mavlink_lr_sample_data_tm_t packet;
- packet.pressure = pressure;
- packet.imu1_acc_x = imu1_acc_x;
- packet.imu1_acc_y = imu1_acc_y;
- packet.imu1_acc_z = imu1_acc_z;
- packet.imu1_gyr_x = imu1_gyr_x;
- packet.imu1_gyr_y = imu1_gyr_y;
- packet.imu1_gyr_z = imu1_gyr_z;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_MIN_LEN, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_LEN, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_CRC);
-}
-
-/**
- * @brief Pack a lr_sample_data_tm 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 pressure Pressure value in raw value //TODO: add calibration curve
- * @param imu1_acc_x Raw acceleration value of the x axis of the ADIS imu
- * @param imu1_acc_y Raw acceleration value of the y axis of the ADIS imu
- * @param imu1_acc_z Raw acceleration value of the z axis of the ADIS imu
- * @param imu1_gyr_x Raw gyro value of the x axis of the ADIS imu
- * @param imu1_gyr_y Raw gyro value of the y axis of the ADIS imu
- * @param imu1_gyr_z Raw gyro value of the z axis of the ADIS imu
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_lr_sample_data_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint16_t pressure,uint16_t imu1_acc_x,uint16_t imu1_acc_y,uint16_t imu1_acc_z,uint16_t imu1_gyr_x,uint16_t imu1_gyr_y,uint16_t imu1_gyr_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_LEN];
- _mav_put_uint16_t(buf, 0, pressure);
- _mav_put_uint16_t(buf, 2, imu1_acc_x);
- _mav_put_uint16_t(buf, 4, imu1_acc_y);
- _mav_put_uint16_t(buf, 6, imu1_acc_z);
- _mav_put_uint16_t(buf, 8, imu1_gyr_x);
- _mav_put_uint16_t(buf, 10, imu1_gyr_y);
- _mav_put_uint16_t(buf, 12, imu1_gyr_z);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_LEN);
-#else
- mavlink_lr_sample_data_tm_t packet;
- packet.pressure = pressure;
- packet.imu1_acc_x = imu1_acc_x;
- packet.imu1_acc_y = imu1_acc_y;
- packet.imu1_acc_z = imu1_acc_z;
- packet.imu1_gyr_x = imu1_gyr_x;
- packet.imu1_gyr_y = imu1_gyr_y;
- packet.imu1_gyr_z = imu1_gyr_z;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_MIN_LEN, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_LEN, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_CRC);
-}
-
-/**
- * @brief Encode a lr_sample_data_tm 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 lr_sample_data_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_lr_sample_data_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_lr_sample_data_tm_t* lr_sample_data_tm)
-{
- return mavlink_msg_lr_sample_data_tm_pack(system_id, component_id, msg, lr_sample_data_tm->pressure, lr_sample_data_tm->imu1_acc_x, lr_sample_data_tm->imu1_acc_y, lr_sample_data_tm->imu1_acc_z, lr_sample_data_tm->imu1_gyr_x, lr_sample_data_tm->imu1_gyr_y, lr_sample_data_tm->imu1_gyr_z);
-}
-
-/**
- * @brief Encode a lr_sample_data_tm 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 lr_sample_data_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_lr_sample_data_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_lr_sample_data_tm_t* lr_sample_data_tm)
-{
- return mavlink_msg_lr_sample_data_tm_pack_chan(system_id, component_id, chan, msg, lr_sample_data_tm->pressure, lr_sample_data_tm->imu1_acc_x, lr_sample_data_tm->imu1_acc_y, lr_sample_data_tm->imu1_acc_z, lr_sample_data_tm->imu1_gyr_x, lr_sample_data_tm->imu1_gyr_y, lr_sample_data_tm->imu1_gyr_z);
-}
-
-/**
- * @brief Send a lr_sample_data_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param pressure Pressure value in raw value //TODO: add calibration curve
- * @param imu1_acc_x Raw acceleration value of the x axis of the ADIS imu
- * @param imu1_acc_y Raw acceleration value of the y axis of the ADIS imu
- * @param imu1_acc_z Raw acceleration value of the z axis of the ADIS imu
- * @param imu1_gyr_x Raw gyro value of the x axis of the ADIS imu
- * @param imu1_gyr_y Raw gyro value of the y axis of the ADIS imu
- * @param imu1_gyr_z Raw gyro value of the z axis of the ADIS imu
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_lr_sample_data_tm_send(mavlink_channel_t chan, uint16_t pressure, uint16_t imu1_acc_x, uint16_t imu1_acc_y, uint16_t imu1_acc_z, uint16_t imu1_gyr_x, uint16_t imu1_gyr_y, uint16_t imu1_gyr_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_LEN];
- _mav_put_uint16_t(buf, 0, pressure);
- _mav_put_uint16_t(buf, 2, imu1_acc_x);
- _mav_put_uint16_t(buf, 4, imu1_acc_y);
- _mav_put_uint16_t(buf, 6, imu1_acc_z);
- _mav_put_uint16_t(buf, 8, imu1_gyr_x);
- _mav_put_uint16_t(buf, 10, imu1_gyr_y);
- _mav_put_uint16_t(buf, 12, imu1_gyr_z);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM, buf, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_MIN_LEN, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_LEN, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_CRC);
-#else
- mavlink_lr_sample_data_tm_t packet;
- packet.pressure = pressure;
- packet.imu1_acc_x = imu1_acc_x;
- packet.imu1_acc_y = imu1_acc_y;
- packet.imu1_acc_z = imu1_acc_z;
- packet.imu1_gyr_x = imu1_gyr_x;
- packet.imu1_gyr_y = imu1_gyr_y;
- packet.imu1_gyr_z = imu1_gyr_z;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM, (const char *)&packet, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_MIN_LEN, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_LEN, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a lr_sample_data_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_lr_sample_data_tm_send_struct(mavlink_channel_t chan, const mavlink_lr_sample_data_tm_t* lr_sample_data_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_lr_sample_data_tm_send(chan, lr_sample_data_tm->pressure, lr_sample_data_tm->imu1_acc_x, lr_sample_data_tm->imu1_acc_y, lr_sample_data_tm->imu1_acc_z, lr_sample_data_tm->imu1_gyr_x, lr_sample_data_tm->imu1_gyr_y, lr_sample_data_tm->imu1_gyr_z);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM, (const char *)lr_sample_data_tm, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_MIN_LEN, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_LEN, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_lr_sample_data_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t pressure, uint16_t imu1_acc_x, uint16_t imu1_acc_y, uint16_t imu1_acc_z, uint16_t imu1_gyr_x, uint16_t imu1_gyr_y, uint16_t imu1_gyr_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint16_t(buf, 0, pressure);
- _mav_put_uint16_t(buf, 2, imu1_acc_x);
- _mav_put_uint16_t(buf, 4, imu1_acc_y);
- _mav_put_uint16_t(buf, 6, imu1_acc_z);
- _mav_put_uint16_t(buf, 8, imu1_gyr_x);
- _mav_put_uint16_t(buf, 10, imu1_gyr_y);
- _mav_put_uint16_t(buf, 12, imu1_gyr_z);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM, buf, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_MIN_LEN, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_LEN, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_CRC);
-#else
- mavlink_lr_sample_data_tm_t *packet = (mavlink_lr_sample_data_tm_t *)msgbuf;
- packet->pressure = pressure;
- packet->imu1_acc_x = imu1_acc_x;
- packet->imu1_acc_y = imu1_acc_y;
- packet->imu1_acc_z = imu1_acc_z;
- packet->imu1_gyr_x = imu1_gyr_x;
- packet->imu1_gyr_y = imu1_gyr_y;
- packet->imu1_gyr_z = imu1_gyr_z;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM, (const char *)packet, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_MIN_LEN, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_LEN, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE LR_SAMPLE_DATA_TM UNPACKING
-
-
-/**
- * @brief Get field pressure from lr_sample_data_tm message
- *
- * @return Pressure value in raw value //TODO: add calibration curve
- */
-static inline uint16_t mavlink_msg_lr_sample_data_tm_get_pressure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 0);
-}
-
-/**
- * @brief Get field imu1_acc_x from lr_sample_data_tm message
- *
- * @return Raw acceleration value of the x axis of the ADIS imu
- */
-static inline uint16_t mavlink_msg_lr_sample_data_tm_get_imu1_acc_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 2);
-}
-
-/**
- * @brief Get field imu1_acc_y from lr_sample_data_tm message
- *
- * @return Raw acceleration value of the y axis of the ADIS imu
- */
-static inline uint16_t mavlink_msg_lr_sample_data_tm_get_imu1_acc_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 4);
-}
-
-/**
- * @brief Get field imu1_acc_z from lr_sample_data_tm message
- *
- * @return Raw acceleration value of the z axis of the ADIS imu
- */
-static inline uint16_t mavlink_msg_lr_sample_data_tm_get_imu1_acc_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 6);
-}
-
-/**
- * @brief Get field imu1_gyr_x from lr_sample_data_tm message
- *
- * @return Raw gyro value of the x axis of the ADIS imu
- */
-static inline uint16_t mavlink_msg_lr_sample_data_tm_get_imu1_gyr_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 8);
-}
-
-/**
- * @brief Get field imu1_gyr_y from lr_sample_data_tm message
- *
- * @return Raw gyro value of the y axis of the ADIS imu
- */
-static inline uint16_t mavlink_msg_lr_sample_data_tm_get_imu1_gyr_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 10);
-}
-
-/**
- * @brief Get field imu1_gyr_z from lr_sample_data_tm message
- *
- * @return Raw gyro value of the z axis of the ADIS imu
- */
-static inline uint16_t mavlink_msg_lr_sample_data_tm_get_imu1_gyr_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 12);
-}
-
-/**
- * @brief Decode a lr_sample_data_tm message into a struct
- *
- * @param msg The message to decode
- * @param lr_sample_data_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_lr_sample_data_tm_decode(const mavlink_message_t* msg, mavlink_lr_sample_data_tm_t* lr_sample_data_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- lr_sample_data_tm->pressure = mavlink_msg_lr_sample_data_tm_get_pressure(msg);
- lr_sample_data_tm->imu1_acc_x = mavlink_msg_lr_sample_data_tm_get_imu1_acc_x(msg);
- lr_sample_data_tm->imu1_acc_y = mavlink_msg_lr_sample_data_tm_get_imu1_acc_y(msg);
- lr_sample_data_tm->imu1_acc_z = mavlink_msg_lr_sample_data_tm_get_imu1_acc_z(msg);
- lr_sample_data_tm->imu1_gyr_x = mavlink_msg_lr_sample_data_tm_get_imu1_gyr_x(msg);
- lr_sample_data_tm->imu1_gyr_y = mavlink_msg_lr_sample_data_tm_get_imu1_gyr_y(msg);
- lr_sample_data_tm->imu1_gyr_z = mavlink_msg_lr_sample_data_tm_get_imu1_gyr_z(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_LEN? msg->len : MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_LEN;
- memset(lr_sample_data_tm, 0, MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_LEN);
- memcpy(lr_sample_data_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/r2a/mavlink_msg_noarg_tc.h b/mavlink_lib/r2a/mavlink_msg_noarg_tc.h
deleted file mode 100644
index 7de53c9223ff12524224dede49dcfee4c45f38c1..0000000000000000000000000000000000000000
--- a/mavlink_lib/r2a/mavlink_msg_noarg_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE NOARG_TC PACKING
-
-#define MAVLINK_MSG_ID_NOARG_TC 10
-
-MAVPACKED(
-typedef struct __mavlink_noarg_tc_t {
- uint8_t command_id; /*< A member of the MavCommandList enum.*/
-}) mavlink_noarg_tc_t;
-
-#define MAVLINK_MSG_ID_NOARG_TC_LEN 1
-#define MAVLINK_MSG_ID_NOARG_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_10_LEN 1
-#define MAVLINK_MSG_ID_10_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_NOARG_TC_CRC 77
-#define MAVLINK_MSG_ID_10_CRC 77
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_NOARG_TC { \
- 10, \
- "NOARG_TC", \
- 1, \
- { { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_noarg_tc_t, command_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_NOARG_TC { \
- "NOARG_TC", \
- 1, \
- { { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_noarg_tc_t, command_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a noarg_tc 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_id A member of the MavCommandList enum.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_noarg_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NOARG_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NOARG_TC_LEN);
-#else
- mavlink_noarg_tc_t packet;
- packet.command_id = command_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NOARG_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NOARG_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-}
-
-/**
- * @brief Pack a noarg_tc 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_id A member of the MavCommandList enum.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_noarg_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NOARG_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NOARG_TC_LEN);
-#else
- mavlink_noarg_tc_t packet;
- packet.command_id = command_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NOARG_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NOARG_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-}
-
-/**
- * @brief Encode a noarg_tc 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 noarg_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_noarg_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_noarg_tc_t* noarg_tc)
-{
- return mavlink_msg_noarg_tc_pack(system_id, component_id, msg, noarg_tc->command_id);
-}
-
-/**
- * @brief Encode a noarg_tc 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 noarg_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_noarg_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_noarg_tc_t* noarg_tc)
-{
- return mavlink_msg_noarg_tc_pack_chan(system_id, component_id, chan, msg, noarg_tc->command_id);
-}
-
-/**
- * @brief Send a noarg_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param command_id A member of the MavCommandList enum.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_noarg_tc_send(mavlink_channel_t chan, uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NOARG_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOARG_TC, buf, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-#else
- mavlink_noarg_tc_t packet;
- packet.command_id = command_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOARG_TC, (const char *)&packet, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a noarg_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_noarg_tc_send_struct(mavlink_channel_t chan, const mavlink_noarg_tc_t* noarg_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_noarg_tc_send(chan, noarg_tc->command_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOARG_TC, (const char *)noarg_tc, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_NOARG_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_noarg_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, command_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOARG_TC, buf, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-#else
- mavlink_noarg_tc_t *packet = (mavlink_noarg_tc_t *)msgbuf;
- packet->command_id = command_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOARG_TC, (const char *)packet, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE NOARG_TC UNPACKING
-
-
-/**
- * @brief Get field command_id from noarg_tc message
- *
- * @return A member of the MavCommandList enum.
- */
-static inline uint8_t mavlink_msg_noarg_tc_get_command_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a noarg_tc message into a struct
- *
- * @param msg The message to decode
- * @param noarg_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_noarg_tc_decode(const mavlink_message_t* msg, mavlink_noarg_tc_t* noarg_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- noarg_tc->command_id = mavlink_msg_noarg_tc_get_command_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_NOARG_TC_LEN? msg->len : MAVLINK_MSG_ID_NOARG_TC_LEN;
- memset(noarg_tc, 0, MAVLINK_MSG_ID_NOARG_TC_LEN);
- memcpy(noarg_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/r2a/mavlink_msg_nosecone_status_tm.h b/mavlink_lib/r2a/mavlink_msg_nosecone_status_tm.h
deleted file mode 100644
index d637e42a2493fabbd1a812a302a178c2e2c3fb9a..0000000000000000000000000000000000000000
--- a/mavlink_lib/r2a/mavlink_msg_nosecone_status_tm.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE NOSECONE_STATUS_TM PACKING
-
-#define MAVLINK_MSG_ID_NOSECONE_STATUS_TM 141
-
-MAVPACKED(
-typedef struct __mavlink_nosecone_status_tm_t {
- uint8_t connected; /*< If False the other value are not valid.*/
- uint8_t dpl_state; /*< Value of NOSECONE_STATUS_ENUM.*/
-}) mavlink_nosecone_status_tm_t;
-
-#define MAVLINK_MSG_ID_NOSECONE_STATUS_TM_LEN 2
-#define MAVLINK_MSG_ID_NOSECONE_STATUS_TM_MIN_LEN 2
-#define MAVLINK_MSG_ID_141_LEN 2
-#define MAVLINK_MSG_ID_141_MIN_LEN 2
-
-#define MAVLINK_MSG_ID_NOSECONE_STATUS_TM_CRC 45
-#define MAVLINK_MSG_ID_141_CRC 45
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_NOSECONE_STATUS_TM { \
- 141, \
- "NOSECONE_STATUS_TM", \
- 2, \
- { { "connected", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_nosecone_status_tm_t, connected) }, \
- { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_nosecone_status_tm_t, dpl_state) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_NOSECONE_STATUS_TM { \
- "NOSECONE_STATUS_TM", \
- 2, \
- { { "connected", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_nosecone_status_tm_t, connected) }, \
- { "dpl_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_nosecone_status_tm_t, dpl_state) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a nosecone_status_tm 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 connected If False the other value are not valid.
- * @param dpl_state Value of NOSECONE_STATUS_ENUM.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_nosecone_status_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t connected, uint8_t dpl_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NOSECONE_STATUS_TM_LEN];
- _mav_put_uint8_t(buf, 0, connected);
- _mav_put_uint8_t(buf, 1, dpl_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_LEN);
-#else
- mavlink_nosecone_status_tm_t packet;
- packet.connected = connected;
- packet.dpl_state = dpl_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NOSECONE_STATUS_TM;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_LEN, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_CRC);
-}
-
-/**
- * @brief Pack a nosecone_status_tm 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 connected If False the other value are not valid.
- * @param dpl_state Value of NOSECONE_STATUS_ENUM.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_nosecone_status_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t connected,uint8_t dpl_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NOSECONE_STATUS_TM_LEN];
- _mav_put_uint8_t(buf, 0, connected);
- _mav_put_uint8_t(buf, 1, dpl_state);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_LEN);
-#else
- mavlink_nosecone_status_tm_t packet;
- packet.connected = connected;
- packet.dpl_state = dpl_state;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NOSECONE_STATUS_TM;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_LEN, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_CRC);
-}
-
-/**
- * @brief Encode a nosecone_status_tm 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 nosecone_status_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_nosecone_status_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nosecone_status_tm_t* nosecone_status_tm)
-{
- return mavlink_msg_nosecone_status_tm_pack(system_id, component_id, msg, nosecone_status_tm->connected, nosecone_status_tm->dpl_state);
-}
-
-/**
- * @brief Encode a nosecone_status_tm 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 nosecone_status_tm C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_nosecone_status_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nosecone_status_tm_t* nosecone_status_tm)
-{
- return mavlink_msg_nosecone_status_tm_pack_chan(system_id, component_id, chan, msg, nosecone_status_tm->connected, nosecone_status_tm->dpl_state);
-}
-
-/**
- * @brief Send a nosecone_status_tm message
- * @param chan MAVLink channel to send the message
- *
- * @param connected If False the other value are not valid.
- * @param dpl_state Value of NOSECONE_STATUS_ENUM.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_nosecone_status_tm_send(mavlink_channel_t chan, uint8_t connected, uint8_t dpl_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NOSECONE_STATUS_TM_LEN];
- _mav_put_uint8_t(buf, 0, connected);
- _mav_put_uint8_t(buf, 1, dpl_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOSECONE_STATUS_TM, buf, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_LEN, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_CRC);
-#else
- mavlink_nosecone_status_tm_t packet;
- packet.connected = connected;
- packet.dpl_state = dpl_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOSECONE_STATUS_TM, (const char *)&packet, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_LEN, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_CRC);
-#endif
-}
-
-/**
- * @brief Send a nosecone_status_tm message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_nosecone_status_tm_send_struct(mavlink_channel_t chan, const mavlink_nosecone_status_tm_t* nosecone_status_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_nosecone_status_tm_send(chan, nosecone_status_tm->connected, nosecone_status_tm->dpl_state);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOSECONE_STATUS_TM, (const char *)nosecone_status_tm, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_LEN, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_NOSECONE_STATUS_TM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_nosecone_status_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t connected, uint8_t dpl_state)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, connected);
- _mav_put_uint8_t(buf, 1, dpl_state);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOSECONE_STATUS_TM, buf, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_LEN, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_CRC);
-#else
- mavlink_nosecone_status_tm_t *packet = (mavlink_nosecone_status_tm_t *)msgbuf;
- packet->connected = connected;
- packet->dpl_state = dpl_state;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOSECONE_STATUS_TM, (const char *)packet, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_MIN_LEN, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_LEN, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE NOSECONE_STATUS_TM UNPACKING
-
-
-/**
- * @brief Get field connected from nosecone_status_tm message
- *
- * @return If False the other value are not valid.
- */
-static inline uint8_t mavlink_msg_nosecone_status_tm_get_connected(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field dpl_state from nosecone_status_tm message
- *
- * @return Value of NOSECONE_STATUS_ENUM.
- */
-static inline uint8_t mavlink_msg_nosecone_status_tm_get_dpl_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Decode a nosecone_status_tm message into a struct
- *
- * @param msg The message to decode
- * @param nosecone_status_tm C-struct to decode the message contents into
- */
-static inline void mavlink_msg_nosecone_status_tm_decode(const mavlink_message_t* msg, mavlink_nosecone_status_tm_t* nosecone_status_tm)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- nosecone_status_tm->connected = mavlink_msg_nosecone_status_tm_get_connected(msg);
- nosecone_status_tm->dpl_state = mavlink_msg_nosecone_status_tm_get_dpl_state(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_NOSECONE_STATUS_TM_LEN? msg->len : MAVLINK_MSG_ID_NOSECONE_STATUS_TM_LEN;
- memset(nosecone_status_tm, 0, MAVLINK_MSG_ID_NOSECONE_STATUS_TM_LEN);
- memcpy(nosecone_status_tm, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/r2a/mavlink_msg_ping_tc.h b/mavlink_lib/r2a/mavlink_msg_ping_tc.h
deleted file mode 100644
index cb1575a0f48705e36177dc8186d3ae85bbd41391..0000000000000000000000000000000000000000
--- a/mavlink_lib/r2a/mavlink_msg_ping_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE PING_TC PACKING
-
-#define MAVLINK_MSG_ID_PING_TC 1
-
-MAVPACKED(
-typedef struct __mavlink_ping_tc_t {
- uint64_t timestamp; /*< Timestamp to identify when it was sent.*/
-}) mavlink_ping_tc_t;
-
-#define MAVLINK_MSG_ID_PING_TC_LEN 8
-#define MAVLINK_MSG_ID_PING_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_1_LEN 8
-#define MAVLINK_MSG_ID_1_MIN_LEN 8
-
-#define MAVLINK_MSG_ID_PING_TC_CRC 136
-#define MAVLINK_MSG_ID_1_CRC 136
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_PING_TC { \
- 1, \
- "PING_TC", \
- 1, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_tc_t, timestamp) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_PING_TC { \
- "PING_TC", \
- 1, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_tc_t, timestamp) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ping_tc 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 Timestamp to identify when it was sent.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ping_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_TC_LEN);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PING_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-}
-
-/**
- * @brief Pack a ping_tc 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 Timestamp to identify when it was sent.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ping_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_TC_LEN);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PING_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-}
-
-/**
- * @brief Encode a ping_tc 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_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ping_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_tc_t* ping_tc)
-{
- return mavlink_msg_ping_tc_pack(system_id, component_id, msg, ping_tc->timestamp);
-}
-
-/**
- * @brief Encode a ping_tc 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_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ping_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ping_tc_t* ping_tc)
-{
- return mavlink_msg_ping_tc_pack_chan(system_id, component_id, chan, msg, ping_tc->timestamp);
-}
-
-/**
- * @brief Send a ping_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp Timestamp to identify when it was sent.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ping_tc_send(mavlink_channel_t chan, uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, buf, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)&packet, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a ping_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ping_tc_send_struct(mavlink_channel_t chan, const mavlink_ping_tc_t* ping_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ping_tc_send(chan, ping_tc->timestamp);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)ping_tc, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_PING_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, buf, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#else
- mavlink_ping_tc_t *packet = (mavlink_ping_tc_t *)msgbuf;
- packet->timestamp = timestamp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)packet, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE PING_TC UNPACKING
-
-
-/**
- * @brief Get field timestamp from ping_tc message
- *
- * @return Timestamp to identify when it was sent.
- */
-static inline uint64_t mavlink_msg_ping_tc_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Decode a ping_tc message into a struct
- *
- * @param msg The message to decode
- * @param ping_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ping_tc_decode(const mavlink_message_t* msg, mavlink_ping_tc_t* ping_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ping_tc->timestamp = mavlink_msg_ping_tc_get_timestamp(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_PING_TC_LEN? msg->len : MAVLINK_MSG_ID_PING_TC_LEN;
- memset(ping_tc, 0, MAVLINK_MSG_ID_PING_TC_LEN);
- memcpy(ping_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/r2a/mavlink_msg_raw_event_tc.h b/mavlink_lib/r2a/mavlink_msg_raw_event_tc.h
deleted file mode 100644
index 7b95415ba088d3fd4527319f3ee22c84c5754eb9..0000000000000000000000000000000000000000
--- a/mavlink_lib/r2a/mavlink_msg_raw_event_tc.h
+++ /dev/null
@@ -1,238 +0,0 @@
-#pragma once
-// MESSAGE RAW_EVENT_TC PACKING
-
-#define MAVLINK_MSG_ID_RAW_EVENT_TC 80
-
-MAVPACKED(
-typedef struct __mavlink_raw_event_tc_t {
- uint8_t Event_id; /*< Id of the event to be posted.*/
- uint8_t Topic_id; /*< Id of the topic to which the event should be posted.*/
-}) mavlink_raw_event_tc_t;
-
-#define MAVLINK_MSG_ID_RAW_EVENT_TC_LEN 2
-#define MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN 2
-#define MAVLINK_MSG_ID_80_LEN 2
-#define MAVLINK_MSG_ID_80_MIN_LEN 2
-
-#define MAVLINK_MSG_ID_RAW_EVENT_TC_CRC 134
-#define MAVLINK_MSG_ID_80_CRC 134
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_RAW_EVENT_TC { \
- 80, \
- "RAW_EVENT_TC", \
- 2, \
- { { "Event_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_raw_event_tc_t, Event_id) }, \
- { "Topic_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_raw_event_tc_t, Topic_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_RAW_EVENT_TC { \
- "RAW_EVENT_TC", \
- 2, \
- { { "Event_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_raw_event_tc_t, Event_id) }, \
- { "Topic_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_raw_event_tc_t, Topic_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a raw_event_tc 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 Event_id Id of the event to be posted.
- * @param Topic_id Id of the topic to which the event should be posted.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_raw_event_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t Event_id, uint8_t Topic_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_EVENT_TC_LEN];
- _mav_put_uint8_t(buf, 0, Event_id);
- _mav_put_uint8_t(buf, 1, Topic_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#else
- mavlink_raw_event_tc_t packet;
- packet.Event_id = Event_id;
- packet.Topic_id = Topic_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RAW_EVENT_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-}
-
-/**
- * @brief Pack a raw_event_tc 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 Event_id Id of the event to be posted.
- * @param Topic_id Id of the topic to which the event should be posted.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_raw_event_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t Event_id,uint8_t Topic_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_EVENT_TC_LEN];
- _mav_put_uint8_t(buf, 0, Event_id);
- _mav_put_uint8_t(buf, 1, Topic_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#else
- mavlink_raw_event_tc_t packet;
- packet.Event_id = Event_id;
- packet.Topic_id = Topic_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RAW_EVENT_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-}
-
-/**
- * @brief Encode a raw_event_tc 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_event_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_raw_event_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_event_tc_t* raw_event_tc)
-{
- return mavlink_msg_raw_event_tc_pack(system_id, component_id, msg, raw_event_tc->Event_id, raw_event_tc->Topic_id);
-}
-
-/**
- * @brief Encode a raw_event_tc 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_event_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_raw_event_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_event_tc_t* raw_event_tc)
-{
- return mavlink_msg_raw_event_tc_pack_chan(system_id, component_id, chan, msg, raw_event_tc->Event_id, raw_event_tc->Topic_id);
-}
-
-/**
- * @brief Send a raw_event_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param Event_id Id of the event to be posted.
- * @param Topic_id Id of the topic to which the event should be posted.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_raw_event_tc_send(mavlink_channel_t chan, uint8_t Event_id, uint8_t Topic_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_RAW_EVENT_TC_LEN];
- _mav_put_uint8_t(buf, 0, Event_id);
- _mav_put_uint8_t(buf, 1, Topic_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, buf, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#else
- mavlink_raw_event_tc_t packet;
- packet.Event_id = Event_id;
- packet.Topic_id = Topic_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, (const char *)&packet, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a raw_event_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_raw_event_tc_send_struct(mavlink_channel_t chan, const mavlink_raw_event_tc_t* raw_event_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_raw_event_tc_send(chan, raw_event_tc->Event_id, raw_event_tc->Topic_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, (const char *)raw_event_tc, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_RAW_EVENT_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_event_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t Event_id, uint8_t Topic_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, Event_id);
- _mav_put_uint8_t(buf, 1, Topic_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, buf, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#else
- mavlink_raw_event_tc_t *packet = (mavlink_raw_event_tc_t *)msgbuf;
- packet->Event_id = Event_id;
- packet->Topic_id = Topic_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_EVENT_TC, (const char *)packet, MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN, MAVLINK_MSG_ID_RAW_EVENT_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE RAW_EVENT_TC UNPACKING
-
-
-/**
- * @brief Get field Event_id from raw_event_tc message
- *
- * @return Id of the event to be posted.
- */
-static inline uint8_t mavlink_msg_raw_event_tc_get_Event_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field Topic_id from raw_event_tc message
- *
- * @return Id of the topic to which the event should be posted.
- */
-static inline uint8_t mavlink_msg_raw_event_tc_get_Topic_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Decode a raw_event_tc message into a struct
- *
- * @param msg The message to decode
- * @param raw_event_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_raw_event_tc_decode(const mavlink_message_t* msg, mavlink_raw_event_tc_t* raw_event_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- raw_event_tc->Event_id = mavlink_msg_raw_event_tc_get_Event_id(msg);
- raw_event_tc->Topic_id = mavlink_msg_raw_event_tc_get_Topic_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_RAW_EVENT_TC_LEN? msg->len : MAVLINK_MSG_ID_RAW_EVENT_TC_LEN;
- memset(raw_event_tc, 0, MAVLINK_MSG_ID_RAW_EVENT_TC_LEN);
- memcpy(raw_event_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/r2a/mavlink_msg_start_launch_tc.h b/mavlink_lib/r2a/mavlink_msg_start_launch_tc.h
deleted file mode 100644
index 34ab1599e2f08d41912e74034c260f5868631c55..0000000000000000000000000000000000000000
--- a/mavlink_lib/r2a/mavlink_msg_start_launch_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE START_LAUNCH_TC PACKING
-
-#define MAVLINK_MSG_ID_START_LAUNCH_TC 20
-
-MAVPACKED(
-typedef struct __mavlink_start_launch_tc_t {
- uint64_t launch_code; /*< 64bit launch code.*/
-}) mavlink_start_launch_tc_t;
-
-#define MAVLINK_MSG_ID_START_LAUNCH_TC_LEN 8
-#define MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_20_LEN 8
-#define MAVLINK_MSG_ID_20_MIN_LEN 8
-
-#define MAVLINK_MSG_ID_START_LAUNCH_TC_CRC 43
-#define MAVLINK_MSG_ID_20_CRC 43
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_START_LAUNCH_TC { \
- 20, \
- "START_LAUNCH_TC", \
- 1, \
- { { "launch_code", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_start_launch_tc_t, launch_code) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_START_LAUNCH_TC { \
- "START_LAUNCH_TC", \
- 1, \
- { { "launch_code", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_start_launch_tc_t, launch_code) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a start_launch_tc 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 launch_code 64bit launch code.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_start_launch_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t launch_code)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_START_LAUNCH_TC_LEN];
- _mav_put_uint64_t(buf, 0, launch_code);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN);
-#else
- mavlink_start_launch_tc_t packet;
- packet.launch_code = launch_code;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_START_LAUNCH_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-}
-
-/**
- * @brief Pack a start_launch_tc 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 launch_code 64bit launch code.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_start_launch_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t launch_code)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_START_LAUNCH_TC_LEN];
- _mav_put_uint64_t(buf, 0, launch_code);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN);
-#else
- mavlink_start_launch_tc_t packet;
- packet.launch_code = launch_code;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_START_LAUNCH_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-}
-
-/**
- * @brief Encode a start_launch_tc 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 start_launch_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_start_launch_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_start_launch_tc_t* start_launch_tc)
-{
- return mavlink_msg_start_launch_tc_pack(system_id, component_id, msg, start_launch_tc->launch_code);
-}
-
-/**
- * @brief Encode a start_launch_tc 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 start_launch_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_start_launch_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_start_launch_tc_t* start_launch_tc)
-{
- return mavlink_msg_start_launch_tc_pack_chan(system_id, component_id, chan, msg, start_launch_tc->launch_code);
-}
-
-/**
- * @brief Send a start_launch_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param launch_code 64bit launch code.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_start_launch_tc_send(mavlink_channel_t chan, uint64_t launch_code)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_START_LAUNCH_TC_LEN];
- _mav_put_uint64_t(buf, 0, launch_code);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_START_LAUNCH_TC, buf, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-#else
- mavlink_start_launch_tc_t packet;
- packet.launch_code = launch_code;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_START_LAUNCH_TC, (const char *)&packet, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a start_launch_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_start_launch_tc_send_struct(mavlink_channel_t chan, const mavlink_start_launch_tc_t* start_launch_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_start_launch_tc_send(chan, start_launch_tc->launch_code);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_START_LAUNCH_TC, (const char *)start_launch_tc, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_START_LAUNCH_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_start_launch_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t launch_code)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, launch_code);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_START_LAUNCH_TC, buf, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-#else
- mavlink_start_launch_tc_t *packet = (mavlink_start_launch_tc_t *)msgbuf;
- packet->launch_code = launch_code;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_START_LAUNCH_TC, (const char *)packet, MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN, MAVLINK_MSG_ID_START_LAUNCH_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE START_LAUNCH_TC UNPACKING
-
-
-/**
- * @brief Get field launch_code from start_launch_tc message
- *
- * @return 64bit launch code.
- */
-static inline uint64_t mavlink_msg_start_launch_tc_get_launch_code(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Decode a start_launch_tc message into a struct
- *
- * @param msg The message to decode
- * @param start_launch_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_start_launch_tc_decode(const mavlink_message_t* msg, mavlink_start_launch_tc_t* start_launch_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- start_launch_tc->launch_code = mavlink_msg_start_launch_tc_get_launch_code(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_START_LAUNCH_TC_LEN? msg->len : MAVLINK_MSG_ID_START_LAUNCH_TC_LEN;
- memset(start_launch_tc, 0, MAVLINK_MSG_ID_START_LAUNCH_TC_LEN);
- memcpy(start_launch_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/r2a/mavlink_msg_telemetry_request_tc.h b/mavlink_lib/r2a/mavlink_msg_telemetry_request_tc.h
deleted file mode 100644
index 4d5b9d5f110dcd3f2f60f581f306893be2b19cb5..0000000000000000000000000000000000000000
--- a/mavlink_lib/r2a/mavlink_msg_telemetry_request_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE TELEMETRY_REQUEST_TC PACKING
-
-#define MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC 30
-
-MAVPACKED(
-typedef struct __mavlink_telemetry_request_tc_t {
- uint8_t board_id; /*< A member of the MavTMList enum.*/
-}) mavlink_telemetry_request_tc_t;
-
-#define MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN 1
-#define MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_30_LEN 1
-#define MAVLINK_MSG_ID_30_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC 105
-#define MAVLINK_MSG_ID_30_CRC 105
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_TELEMETRY_REQUEST_TC { \
- 30, \
- "TELEMETRY_REQUEST_TC", \
- 1, \
- { { "board_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_telemetry_request_tc_t, board_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_TELEMETRY_REQUEST_TC { \
- "TELEMETRY_REQUEST_TC", \
- 1, \
- { { "board_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_telemetry_request_tc_t, board_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a telemetry_request_tc 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 board_id A member of the MavTMList enum.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_telemetry_request_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t board_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, board_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN);
-#else
- mavlink_telemetry_request_tc_t packet;
- packet.board_id = board_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Pack a telemetry_request_tc 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 board_id A member of the MavTMList enum.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_telemetry_request_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t board_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, board_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN);
-#else
- mavlink_telemetry_request_tc_t packet;
- packet.board_id = board_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-}
-
-/**
- * @brief Encode a telemetry_request_tc 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 telemetry_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_telemetry_request_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_telemetry_request_tc_t* telemetry_request_tc)
-{
- return mavlink_msg_telemetry_request_tc_pack(system_id, component_id, msg, telemetry_request_tc->board_id);
-}
-
-/**
- * @brief Encode a telemetry_request_tc 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 telemetry_request_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_telemetry_request_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_telemetry_request_tc_t* telemetry_request_tc)
-{
- return mavlink_msg_telemetry_request_tc_pack_chan(system_id, component_id, chan, msg, telemetry_request_tc->board_id);
-}
-
-/**
- * @brief Send a telemetry_request_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param board_id A member of the MavTMList enum.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_telemetry_request_tc_send(mavlink_channel_t chan, uint8_t board_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN];
- _mav_put_uint8_t(buf, 0, board_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC, buf, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-#else
- mavlink_telemetry_request_tc_t packet;
- packet.board_id = board_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC, (const char *)&packet, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a telemetry_request_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_telemetry_request_tc_send_struct(mavlink_channel_t chan, const mavlink_telemetry_request_tc_t* telemetry_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_telemetry_request_tc_send(chan, telemetry_request_tc->board_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC, (const char *)telemetry_request_tc, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_telemetry_request_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t board_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, board_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC, buf, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-#else
- mavlink_telemetry_request_tc_t *packet = (mavlink_telemetry_request_tc_t *)msgbuf;
- packet->board_id = board_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC, (const char *)packet, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE TELEMETRY_REQUEST_TC UNPACKING
-
-
-/**
- * @brief Get field board_id from telemetry_request_tc message
- *
- * @return A member of the MavTMList enum.
- */
-static inline uint8_t mavlink_msg_telemetry_request_tc_get_board_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a telemetry_request_tc message into a struct
- *
- * @param msg The message to decode
- * @param telemetry_request_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_telemetry_request_tc_decode(const mavlink_message_t* msg, mavlink_telemetry_request_tc_t* telemetry_request_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- telemetry_request_tc->board_id = mavlink_msg_telemetry_request_tc_get_board_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN? msg->len : MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN;
- memset(telemetry_request_tc, 0, MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_LEN);
- memcpy(telemetry_request_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/r2a/r2a.h b/mavlink_lib/r2a/r2a.h
deleted file mode 100644
index 3ccb33c8e576fae936fb9a6f3d34443424ca2f5b..0000000000000000000000000000000000000000
--- a/mavlink_lib/r2a/r2a.h
+++ /dev/null
@@ -1,116 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol generated from r2a.xml
- * @see http://mavlink.org
- */
-#pragma once
-#ifndef MAVLINK_R2A_H
-#define MAVLINK_R2A_H
-
-#ifndef MAVLINK_H
- #error Wrong include order: MAVLINK_R2A.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
-
-#undef MAVLINK_THIS_XML_IDX
-#define MAVLINK_THIS_XML_IDX 0
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-// MESSAGE LENGTHS AND CRCS
-
-#ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {0, 8, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 19, 2, 2, 0, 0, 0, 0, 0, 0, 0, 14, 0, 0, 0, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
-#endif
-
-#ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {0, 136, 0, 0, 0, 0, 0, 0, 0, 0, 77, 0, 0, 0, 0, 0, 0, 0, 0, 0, 43, 0, 0, 0, 0, 0, 0, 0, 0, 0, 105, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 119, 45, 55, 0, 0, 0, 0, 0, 0, 0, 244, 0, 0, 0, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
-#endif
-
-#include "../protocol.h"
-
-#define MAVLINK_ENABLED_R2A
-
-// ENUM DEFINITIONS
-
-
-/** @brief Enum list for all the telemetries that can be requested from ground. */
-#ifndef HAVE_ENUM_MavTMList
-#define HAVE_ENUM_MavTMList
-typedef enum MavTMList
-{
- MAV_HOMEONE_TM_ID=1, /* State of the Homeone Board | */
- MAV_IGNITION_TM_ID=2, /* State of the Ignition Board | */
- MAV_NOSECONE_TM_ID=3, /* State of the Nosecone Board | */
- MAV_HR_TM_ID=4, /* High Rate telemetry | */
- MAV_LR_TM_ID=5, /* Low Rate telemetry | */
- MAV_POS_TM_ID=6, /* Position Telemetry | */
- MavTMList_ENUM_END=7, /* | */
-} MavTMList;
-#endif
-
-/** @brief Enum of the commands that don't have any message payload. */
-#ifndef HAVE_ENUM_MavCommandList
-#define HAVE_ENUM_MavCommandList
-typedef enum MavCommandList
-{
- MAV_CMD_ARM=10, /* Command to arm the rocket. | */
- MAV_CMD_DISARM=15, /* Command to disarm the rocket. | */
- MAV_CMD_ABORT=50, /* Command to abort the launch. | */
- MAV_CMD_NOSECONE_OPEN=60, /* Command to open the nosecone. | */
- MAV_CMD_NOSECONE_CLOSE=61, /* Command to close the nosecone. | */
- MAV_CMD_CUT_FIRST_DROGUE=65, /* Command to activate the thermal cutters and cut the first drogue. | */
- MAV_CMD_CUT_ALL=66, /* Command to cut all the drogues. | */
- MAV_CMD_START_LOGGING=70, /* Command to enable the logging. | */
- MAV_CMD_STOP_LOGGING=71, /* Command to disable the logging. | */
- MAV_CMD_END_MISSION=100, /* Command to communicate the end of the mission and close the file descriptors in the SD card. | */
- MAV_CMD_TEST_MODE=200, /* Command to enter the test mode. | */
- MAV_CMD_BOARD_RESET=201, /* Command to reset the board from test status. | */
- MAV_CMD_REQ_DEBUG_INFO=205, /* Command to request the debug information. | */
- MAV_CMD_MANUAL_MODE=210, /* Command to enter the manual mode and prevent the internal events from triggering deployment. | */
- MavCommandList_ENUM_END=211, /* | */
-} MavCommandList;
-#endif
-
-// MAVLINK VERSION
-
-#ifndef MAVLINK_VERSION
-#define MAVLINK_VERSION 2
-#endif
-
-#if (MAVLINK_VERSION == 0)
-#undef MAVLINK_VERSION
-#define MAVLINK_VERSION 2
-#endif
-
-// MESSAGE DEFINITIONS
-#include "./mavlink_msg_ping_tc.h"
-#include "./mavlink_msg_noarg_tc.h"
-#include "./mavlink_msg_start_launch_tc.h"
-#include "./mavlink_msg_telemetry_request_tc.h"
-#include "./mavlink_msg_raw_event_tc.h"
-#include "./mavlink_msg_ack_tm.h"
-#include "./mavlink_msg_homeone_status_tm.h"
-#include "./mavlink_msg_nosecone_status_tm.h"
-#include "./mavlink_msg_ignition_status_tm.h"
-#include "./mavlink_msg_lr_sample_data_tm.h"
-#include "./mavlink_msg_hr_sample_data_tm.h"
-
-// base include
-
-
-#undef MAVLINK_THIS_XML_IDX
-#define MAVLINK_THIS_XML_IDX 0
-
-#if MAVLINK_THIS_XML_IDX == MAVLINK_PRIMARY_XML_IDX
-# define MAVLINK_MESSAGE_INFO {{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_NOARG_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_START_LAUNCH_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_TELEMETRY_REQUEST_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_RAW_EVENT_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACK_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_HOMEONE_STATUS_TM, MAVLINK_MESSAGE_INFO_NOSECONE_STATUS_TM, MAVLINK_MESSAGE_INFO_IGNITION_STATUS_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LR_SAMPLE_DATA_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_HR_SAMPLE_DATA_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
-# define MAVLINK_MESSAGE_NAMES {{ "ACK_TM", 130 }, { "HOMEONE_STATUS_TM", 140 }, { "HR_SAMPLE_DATA_TM", 155 }, { "IGNITION_STATUS_TM", 142 }, { "LR_SAMPLE_DATA_TM", 150 }, { "NOARG_TC", 10 }, { "NOSECONE_STATUS_TM", 141 }, { "PING_TC", 1 }, { "RAW_EVENT_TC", 80 }, { "START_LAUNCH_TC", 20 }, { "TELEMETRY_REQUEST_TC", 30 }}
-# if MAVLINK_COMMAND_24BIT
-# include "../mavlink_get_info.h"
-# endif
-#endif
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // MAVLINK_R2A_H
diff --git a/mavlink_lib/r2a/testsuite.h b/mavlink_lib/r2a/testsuite.h
deleted file mode 100644
index 27d6dd1624a4bc022ca8979ebbdcca47ceea237c..0000000000000000000000000000000000000000
--- a/mavlink_lib/r2a/testsuite.h
+++ /dev/null
@@ -1,654 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol testsuite generated from r2a.xml
- * @see http://qgroundcontrol.org/mavlink/
- */
-#pragma once
-#ifndef R2A_TESTSUITE_H
-#define R2A_TESTSUITE_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#ifndef MAVLINK_TEST_ALL
-#define MAVLINK_TEST_ALL
-
-static void mavlink_test_r2a(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_r2a(system_id, component_id, last_msg);
-}
-#endif
-
-
-
-
-static void mavlink_test_ping_tc(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_PING_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ping_tc_t packet_in = {
- 93372036854775807ULL
- };
- mavlink_ping_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_PING_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PING_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ping_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_pack(system_id, component_id, &msg , packet1.timestamp );
- mavlink_msg_ping_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp );
- mavlink_msg_ping_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ping_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_send(MAVLINK_COMM_1 , packet1.timestamp );
- mavlink_msg_ping_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_noarg_tc(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_NOARG_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_noarg_tc_t packet_in = {
- 5
- };
- mavlink_noarg_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.command_id = packet_in.command_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_NOARG_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NOARG_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_noarg_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_noarg_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_noarg_tc_pack(system_id, component_id, &msg , packet1.command_id );
- mavlink_msg_noarg_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_noarg_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.command_id );
- mavlink_msg_noarg_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_noarg_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_noarg_tc_send(MAVLINK_COMM_1 , packet1.command_id );
- mavlink_msg_noarg_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_start_launch_tc(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_START_LAUNCH_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_start_launch_tc_t packet_in = {
- 93372036854775807ULL
- };
- mavlink_start_launch_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.launch_code = packet_in.launch_code;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_START_LAUNCH_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_start_launch_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_start_launch_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_start_launch_tc_pack(system_id, component_id, &msg , packet1.launch_code );
- mavlink_msg_start_launch_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_start_launch_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.launch_code );
- mavlink_msg_start_launch_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_start_launch_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_start_launch_tc_send(MAVLINK_COMM_1 , packet1.launch_code );
- mavlink_msg_start_launch_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_telemetry_request_tc(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_TELEMETRY_REQUEST_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_telemetry_request_tc_t packet_in = {
- 5
- };
- mavlink_telemetry_request_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.board_id = packet_in.board_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TELEMETRY_REQUEST_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_telemetry_request_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_telemetry_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_telemetry_request_tc_pack(system_id, component_id, &msg , packet1.board_id );
- mavlink_msg_telemetry_request_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_telemetry_request_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.board_id );
- mavlink_msg_telemetry_request_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_telemetry_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_telemetry_request_tc_send(MAVLINK_COMM_1 , packet1.board_id );
- mavlink_msg_telemetry_request_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_raw_event_tc(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_RAW_EVENT_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_raw_event_tc_t packet_in = {
- 5,72
- };
- mavlink_raw_event_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.Event_id = packet_in.Event_id;
- packet1.Topic_id = packet_in.Topic_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RAW_EVENT_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_raw_event_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_pack(system_id, component_id, &msg , packet1.Event_id , packet1.Topic_id );
- mavlink_msg_raw_event_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.Event_id , packet1.Topic_id );
- mavlink_msg_raw_event_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_raw_event_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_event_tc_send(MAVLINK_COMM_1 , packet1.Event_id , packet1.Topic_id );
- mavlink_msg_raw_event_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_ack_tm(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_ACK_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ack_tm_t packet_in = {
- 5,72
- };
- mavlink_ack_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.recv_msgid = packet_in.recv_msgid;
- packet1.seq_ack = packet_in.seq_ack;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_ACK_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ACK_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_pack(system_id, component_id, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_ack_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_ack_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ack_tm_send(MAVLINK_COMM_1 , packet1.recv_msgid , packet1.seq_ack );
- mavlink_msg_ack_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_homeone_status_tm(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_HOMEONE_STATUS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_homeone_status_tm_t packet_in = {
- 5,72,139,'D',{ 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31 }
- };
- mavlink_homeone_status_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.sampling_status = packet_in.sampling_status;
- packet1.FMM_current_state = packet_in.FMM_current_state;
- packet1.log_status = packet_in.log_status;
- packet1.umbilical_connection_status = packet_in.umbilical_connection_status;
-
- mav_array_memcpy(packet1.fault_counter_array, packet_in.fault_counter_array, sizeof(uint8_t)*15);
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_HOMEONE_STATUS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HOMEONE_STATUS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_homeone_status_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_homeone_status_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_homeone_status_tm_pack(system_id, component_id, &msg , packet1.sampling_status , packet1.FMM_current_state , packet1.log_status , packet1.umbilical_connection_status , packet1.fault_counter_array );
- mavlink_msg_homeone_status_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_homeone_status_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.sampling_status , packet1.FMM_current_state , packet1.log_status , packet1.umbilical_connection_status , packet1.fault_counter_array );
- mavlink_msg_homeone_status_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_homeone_status_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_homeone_status_tm_send(MAVLINK_COMM_1 , packet1.sampling_status , packet1.FMM_current_state , packet1.log_status , packet1.umbilical_connection_status , packet1.fault_counter_array );
- mavlink_msg_homeone_status_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_nosecone_status_tm(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_NOSECONE_STATUS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_nosecone_status_tm_t packet_in = {
- 5,72
- };
- mavlink_nosecone_status_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.connected = packet_in.connected;
- packet1.dpl_state = packet_in.dpl_state;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_NOSECONE_STATUS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NOSECONE_STATUS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nosecone_status_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_nosecone_status_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nosecone_status_tm_pack(system_id, component_id, &msg , packet1.connected , packet1.dpl_state );
- mavlink_msg_nosecone_status_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nosecone_status_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.connected , packet1.dpl_state );
- mavlink_msg_nosecone_status_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_nosecone_status_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_nosecone_status_tm_send(MAVLINK_COMM_1 , packet1.connected , packet1.dpl_state );
- mavlink_msg_nosecone_status_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_ignition_status_tm(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_IGNITION_STATUS_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ignition_status_tm_t packet_in = {
- 5,72
- };
- mavlink_ignition_status_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.connected = packet_in.connected;
- packet1.ignition_state = packet_in.ignition_state;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_IGNITION_STATUS_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_IGNITION_STATUS_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ignition_status_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ignition_status_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ignition_status_tm_pack(system_id, component_id, &msg , packet1.connected , packet1.ignition_state );
- mavlink_msg_ignition_status_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ignition_status_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.connected , packet1.ignition_state );
- mavlink_msg_ignition_status_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ignition_status_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ignition_status_tm_send(MAVLINK_COMM_1 , packet1.connected , packet1.ignition_state );
- mavlink_msg_ignition_status_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_lr_sample_data_tm(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_LR_SAMPLE_DATA_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_lr_sample_data_tm_t packet_in = {
- 17235,17339,17443,17547,17651,17755,17859
- };
- mavlink_lr_sample_data_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.pressure = packet_in.pressure;
- packet1.imu1_acc_x = packet_in.imu1_acc_x;
- packet1.imu1_acc_y = packet_in.imu1_acc_y;
- packet1.imu1_acc_z = packet_in.imu1_acc_z;
- packet1.imu1_gyr_x = packet_in.imu1_gyr_x;
- packet1.imu1_gyr_y = packet_in.imu1_gyr_y;
- packet1.imu1_gyr_z = packet_in.imu1_gyr_z;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LR_SAMPLE_DATA_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_lr_sample_data_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_lr_sample_data_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_lr_sample_data_tm_pack(system_id, component_id, &msg , packet1.pressure , packet1.imu1_acc_x , packet1.imu1_acc_y , packet1.imu1_acc_z , packet1.imu1_gyr_x , packet1.imu1_gyr_y , packet1.imu1_gyr_z );
- mavlink_msg_lr_sample_data_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_lr_sample_data_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.pressure , packet1.imu1_acc_x , packet1.imu1_acc_y , packet1.imu1_acc_z , packet1.imu1_gyr_x , packet1.imu1_gyr_y , packet1.imu1_gyr_z );
- mavlink_msg_lr_sample_data_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_lr_sample_data_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_lr_sample_data_tm_send(MAVLINK_COMM_1 , packet1.pressure , packet1.imu1_acc_x , packet1.imu1_acc_y , packet1.imu1_acc_z , packet1.imu1_gyr_x , packet1.imu1_gyr_y , packet1.imu1_gyr_z );
- mavlink_msg_lr_sample_data_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_hr_sample_data_tm(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_HR_SAMPLE_DATA_TM >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_hr_sample_data_tm_t packet_in = {
- 17235
- };
- mavlink_hr_sample_data_tm_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.pressure = packet_in.pressure;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HR_SAMPLE_DATA_TM_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_hr_sample_data_tm_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_hr_sample_data_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_hr_sample_data_tm_pack(system_id, component_id, &msg , packet1.pressure );
- mavlink_msg_hr_sample_data_tm_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_hr_sample_data_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.pressure );
- mavlink_msg_hr_sample_data_tm_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_hr_sample_data_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_hr_sample_data_tm_send(MAVLINK_COMM_1 , packet1.pressure );
- mavlink_msg_hr_sample_data_tm_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_r2a(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
-{
- mavlink_test_ping_tc(system_id, component_id, last_msg);
- mavlink_test_noarg_tc(system_id, component_id, last_msg);
- mavlink_test_start_launch_tc(system_id, component_id, last_msg);
- mavlink_test_telemetry_request_tc(system_id, component_id, last_msg);
- mavlink_test_raw_event_tc(system_id, component_id, last_msg);
- mavlink_test_ack_tm(system_id, component_id, last_msg);
- mavlink_test_homeone_status_tm(system_id, component_id, last_msg);
- mavlink_test_nosecone_status_tm(system_id, component_id, last_msg);
- mavlink_test_ignition_status_tm(system_id, component_id, last_msg);
- mavlink_test_lr_sample_data_tm(system_id, component_id, last_msg);
- mavlink_test_hr_sample_data_tm(system_id, component_id, last_msg);
-}
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // R2A_TESTSUITE_H
diff --git a/mavlink_lib/r2a/version.h b/mavlink_lib/r2a/version.h
deleted file mode 100644
index 5a249ae6e162dbc0e85de784ef9f7b6290aff186..0000000000000000000000000000000000000000
--- a/mavlink_lib/r2a/version.h
+++ /dev/null
@@ -1,14 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol built from r2a.xml
- * @see http://mavlink.org
- */
-#pragma once
-
-#ifndef MAVLINK_VERSION_H
-#define MAVLINK_VERSION_H
-
-#define MAVLINK_BUILD_DATE "Tue Mar 12 2019"
-#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
-#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 19
-
-#endif // MAVLINK_VERSION_H
diff --git a/mavlink_lib/test/StatusRepos.h b/mavlink_lib/test/StatusRepos.h
deleted file mode 100644
index e43e56169ffd756e3cc3a772ac210160904fa160..0000000000000000000000000000000000000000
--- a/mavlink_lib/test/StatusRepos.h
+++ /dev/null
@@ -1,45 +0,0 @@
-/** @file
- * @brief Skyward Status Repository
- */
-#pragma once
-
-namespace StatusRepo
-{
- /* Enumeration of all possible TMs */
- enum MavTMList: uint8_t
- {
- MAV_NOARG_TC_ID,
-
- };
-
- /* Struct containing all tms in the form of mavlink structs */
- static struct status_repo_t
- {
- mavlink_noarg_tc_t noarg_tc;
-
- } status repo;
-
- /**
- * Retrieve one of the telemetry structs
- * @req_tm required telemetry
- * @return packed mavlink struct of that telemetry
- */
- static mavlink_message_t getTM(uint8_t req_tm, uint8_t sys_id, uint8_t comp_id)
- {
- mavlink_message_t m;
-
- switch (req_tm)
- {
- case MavTMList::MAV_NOARG_TC_ID:
- mavlink_msg_noarg_tc_encode(sys_id, comp_id, &m, &(repo.noarg_tc));
- break;
-
- default:
- // TODO: manage error
- break;
- }
-
- return m;
- }
-
-}
diff --git a/mavlink_lib/test/mavlink.h b/mavlink_lib/test/mavlink.h
deleted file mode 100644
index da154d1af0b7518cc17a37454766bfa481073920..0000000000000000000000000000000000000000
--- a/mavlink_lib/test/mavlink.h
+++ /dev/null
@@ -1,34 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol built from test.xml
- * @see http://mavlink.org
- */
-#pragma once
-#ifndef MAVLINK_H
-#define MAVLINK_H
-
-#define MAVLINK_PRIMARY_XML_IDX 0
-
-#ifndef MAVLINK_STX
-#define MAVLINK_STX 254
-#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 0
-#endif
-
-#include "version.h"
-#include "test.h"
-
-#endif // MAVLINK_H
diff --git a/mavlink_lib/test/mavlink_msg_noarg_tc.h b/mavlink_lib/test/mavlink_msg_noarg_tc.h
deleted file mode 100644
index 7de53c9223ff12524224dede49dcfee4c45f38c1..0000000000000000000000000000000000000000
--- a/mavlink_lib/test/mavlink_msg_noarg_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE NOARG_TC PACKING
-
-#define MAVLINK_MSG_ID_NOARG_TC 10
-
-MAVPACKED(
-typedef struct __mavlink_noarg_tc_t {
- uint8_t command_id; /*< A member of the MavCommandList enum.*/
-}) mavlink_noarg_tc_t;
-
-#define MAVLINK_MSG_ID_NOARG_TC_LEN 1
-#define MAVLINK_MSG_ID_NOARG_TC_MIN_LEN 1
-#define MAVLINK_MSG_ID_10_LEN 1
-#define MAVLINK_MSG_ID_10_MIN_LEN 1
-
-#define MAVLINK_MSG_ID_NOARG_TC_CRC 77
-#define MAVLINK_MSG_ID_10_CRC 77
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_NOARG_TC { \
- 10, \
- "NOARG_TC", \
- 1, \
- { { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_noarg_tc_t, command_id) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_NOARG_TC { \
- "NOARG_TC", \
- 1, \
- { { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_noarg_tc_t, command_id) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a noarg_tc 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_id A member of the MavCommandList enum.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_noarg_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NOARG_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NOARG_TC_LEN);
-#else
- mavlink_noarg_tc_t packet;
- packet.command_id = command_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NOARG_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NOARG_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-}
-
-/**
- * @brief Pack a noarg_tc 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_id A member of the MavCommandList enum.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_noarg_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NOARG_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NOARG_TC_LEN);
-#else
- mavlink_noarg_tc_t packet;
- packet.command_id = command_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NOARG_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_NOARG_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-}
-
-/**
- * @brief Encode a noarg_tc 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 noarg_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_noarg_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_noarg_tc_t* noarg_tc)
-{
- return mavlink_msg_noarg_tc_pack(system_id, component_id, msg, noarg_tc->command_id);
-}
-
-/**
- * @brief Encode a noarg_tc 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 noarg_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_noarg_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_noarg_tc_t* noarg_tc)
-{
- return mavlink_msg_noarg_tc_pack_chan(system_id, component_id, chan, msg, noarg_tc->command_id);
-}
-
-/**
- * @brief Send a noarg_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param command_id A member of the MavCommandList enum.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_noarg_tc_send(mavlink_channel_t chan, uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_NOARG_TC_LEN];
- _mav_put_uint8_t(buf, 0, command_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOARG_TC, buf, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-#else
- mavlink_noarg_tc_t packet;
- packet.command_id = command_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOARG_TC, (const char *)&packet, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a noarg_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_noarg_tc_send_struct(mavlink_channel_t chan, const mavlink_noarg_tc_t* noarg_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_noarg_tc_send(chan, noarg_tc->command_id);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOARG_TC, (const char *)noarg_tc, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_NOARG_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_noarg_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint8_t(buf, 0, command_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOARG_TC, buf, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-#else
- mavlink_noarg_tc_t *packet = (mavlink_noarg_tc_t *)msgbuf;
- packet->command_id = command_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NOARG_TC, (const char *)packet, MAVLINK_MSG_ID_NOARG_TC_MIN_LEN, MAVLINK_MSG_ID_NOARG_TC_LEN, MAVLINK_MSG_ID_NOARG_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE NOARG_TC UNPACKING
-
-
-/**
- * @brief Get field command_id from noarg_tc message
- *
- * @return A member of the MavCommandList enum.
- */
-static inline uint8_t mavlink_msg_noarg_tc_get_command_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a noarg_tc message into a struct
- *
- * @param msg The message to decode
- * @param noarg_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_noarg_tc_decode(const mavlink_message_t* msg, mavlink_noarg_tc_t* noarg_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- noarg_tc->command_id = mavlink_msg_noarg_tc_get_command_id(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_NOARG_TC_LEN? msg->len : MAVLINK_MSG_ID_NOARG_TC_LEN;
- memset(noarg_tc, 0, MAVLINK_MSG_ID_NOARG_TC_LEN);
- memcpy(noarg_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/test/mavlink_msg_ping_tc.h b/mavlink_lib/test/mavlink_msg_ping_tc.h
deleted file mode 100644
index cb1575a0f48705e36177dc8186d3ae85bbd41391..0000000000000000000000000000000000000000
--- a/mavlink_lib/test/mavlink_msg_ping_tc.h
+++ /dev/null
@@ -1,213 +0,0 @@
-#pragma once
-// MESSAGE PING_TC PACKING
-
-#define MAVLINK_MSG_ID_PING_TC 1
-
-MAVPACKED(
-typedef struct __mavlink_ping_tc_t {
- uint64_t timestamp; /*< Timestamp to identify when it was sent.*/
-}) mavlink_ping_tc_t;
-
-#define MAVLINK_MSG_ID_PING_TC_LEN 8
-#define MAVLINK_MSG_ID_PING_TC_MIN_LEN 8
-#define MAVLINK_MSG_ID_1_LEN 8
-#define MAVLINK_MSG_ID_1_MIN_LEN 8
-
-#define MAVLINK_MSG_ID_PING_TC_CRC 136
-#define MAVLINK_MSG_ID_1_CRC 136
-
-
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_PING_TC { \
- 1, \
- "PING_TC", \
- 1, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_tc_t, timestamp) }, \
- } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_PING_TC { \
- "PING_TC", \
- 1, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_tc_t, timestamp) }, \
- } \
-}
-#endif
-
-/**
- * @brief Pack a ping_tc 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 Timestamp to identify when it was sent.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ping_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_TC_LEN);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PING_TC;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-}
-
-/**
- * @brief Pack a ping_tc 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 Timestamp to identify when it was sent.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_ping_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_TC_LEN);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_TC_LEN);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PING_TC;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-}
-
-/**
- * @brief Encode a ping_tc 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_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ping_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_tc_t* ping_tc)
-{
- return mavlink_msg_ping_tc_pack(system_id, component_id, msg, ping_tc->timestamp);
-}
-
-/**
- * @brief Encode a ping_tc 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_tc C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_ping_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ping_tc_t* ping_tc)
-{
- return mavlink_msg_ping_tc_pack_chan(system_id, component_id, chan, msg, ping_tc->timestamp);
-}
-
-/**
- * @brief Send a ping_tc message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp Timestamp to identify when it was sent.
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_ping_tc_send(mavlink_channel_t chan, uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_PING_TC_LEN];
- _mav_put_uint64_t(buf, 0, timestamp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, buf, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#else
- mavlink_ping_tc_t packet;
- packet.timestamp = timestamp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)&packet, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-
-/**
- * @brief Send a ping_tc message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_ping_tc_send_struct(mavlink_channel_t chan, const mavlink_ping_tc_t* ping_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_ping_tc_send(chan, ping_tc->timestamp);
-#else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)ping_tc, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_PING_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
-/*
- This varient 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_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint64_t(buf, 0, timestamp);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, buf, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#else
- mavlink_ping_tc_t *packet = (mavlink_ping_tc_t *)msgbuf;
- packet->timestamp = timestamp;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING_TC, (const char *)packet, MAVLINK_MSG_ID_PING_TC_MIN_LEN, MAVLINK_MSG_ID_PING_TC_LEN, MAVLINK_MSG_ID_PING_TC_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE PING_TC UNPACKING
-
-
-/**
- * @brief Get field timestamp from ping_tc message
- *
- * @return Timestamp to identify when it was sent.
- */
-static inline uint64_t mavlink_msg_ping_tc_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Decode a ping_tc message into a struct
- *
- * @param msg The message to decode
- * @param ping_tc C-struct to decode the message contents into
- */
-static inline void mavlink_msg_ping_tc_decode(const mavlink_message_t* msg, mavlink_ping_tc_t* ping_tc)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- ping_tc->timestamp = mavlink_msg_ping_tc_get_timestamp(msg);
-#else
- uint8_t len = msg->len < MAVLINK_MSG_ID_PING_TC_LEN? msg->len : MAVLINK_MSG_ID_PING_TC_LEN;
- memset(ping_tc, 0, MAVLINK_MSG_ID_PING_TC_LEN);
- memcpy(ping_tc, _MAV_PAYLOAD(msg), len);
-#endif
-}
diff --git a/mavlink_lib/test/test.h b/mavlink_lib/test/test.h
deleted file mode 100644
index 827eefaeee360de47581ca66ac989e00399dac51..0000000000000000000000000000000000000000
--- a/mavlink_lib/test/test.h
+++ /dev/null
@@ -1,107 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol generated from test.xml
- * @see http://mavlink.org
- */
-#pragma once
-#ifndef MAVLINK_TEST_H
-#define MAVLINK_TEST_H
-
-#ifndef MAVLINK_H
- #error Wrong include order: MAVLINK_TEST.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
-
-#undef MAVLINK_THIS_XML_IDX
-#define MAVLINK_THIS_XML_IDX 0
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-// MESSAGE LENGTHS AND CRCS
-
-#ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {0, 8, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
-#endif
-
-#ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {0, 136, 0, 0, 0, 0, 0, 0, 0, 0, 77, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
-#endif
-
-#include "../protocol.h"
-
-#define MAVLINK_ENABLED_TEST
-
-// ENUM DEFINITIONS
-
-
-/** @brief Enum list for all the telemetries that can be requested from ground. */
-#ifndef HAVE_ENUM_MavTMList
-#define HAVE_ENUM_MavTMList
-typedef enum MavTMList
-{
- MAV_HOMEONE_TM_ID=1, /* State of the Homeone Board | */
- MAV_IGNITION_TM_ID=2, /* State of the Ignition Board | */
- MAV_NOSECONE_TM_ID=3, /* State of the Nosecone Board | */
- MAV_HR_TM_ID=4, /* High Rate telemetry | */
- MAV_LR_TM_ID=5, /* Low Rate telemetry | */
- MAV_POS_TM_ID=6, /* Position Telemetry | */
- MavTMList_ENUM_END=7, /* | */
-} MavTMList;
-#endif
-
-/** @brief Enum of the commands that don't have any message payload. */
-#ifndef HAVE_ENUM_MavCommandList
-#define HAVE_ENUM_MavCommandList
-typedef enum MavCommandList
-{
- MAV_CMD_ARM=10, /* Command to arm the rocket. | */
- MAV_CMD_DISARM=15, /* Command to disarm the rocket. | */
- MAV_CMD_ABORT=50, /* Command to abort the launch. | */
- MAV_CMD_NOSECONE_OPEN=60, /* Command to open the nosecone. | */
- MAV_CMD_NOSECONE_CLOSE=61, /* Command to close the nosecone. | */
- MAV_CMD_CUT_FIRST_DROGUE=65, /* Command to activate the thermal cutters and cut the first drogue. | */
- MAV_CMD_CUT_ALL=66, /* Command to cut all the drogues. | */
- MAV_CMD_START_LOGGING=70, /* Command to enable the logging. | */
- MAV_CMD_STOP_LOGGING=71, /* Command to disable the logging. | */
- MAV_CMD_END_MISSION=100, /* Command to communicate the end of the mission and close the file descriptors in the SD card. | */
- MAV_CMD_TEST_MODE=200, /* Command to enter the test mode. | */
- MAV_CMD_BOARD_RESET=201, /* Command to reset the board from test status. | */
- MAV_CMD_REQ_DEBUG_INFO=205, /* Command to request the debug information. | */
- MAV_CMD_MANUAL_MODE=210, /* Command to enter the manual mode and prevent the internal events from triggering deployment. | */
- MavCommandList_ENUM_END=211, /* | */
-} MavCommandList;
-#endif
-
-// MAVLINK VERSION
-
-#ifndef MAVLINK_VERSION
-#define MAVLINK_VERSION 2
-#endif
-
-#if (MAVLINK_VERSION == 0)
-#undef MAVLINK_VERSION
-#define MAVLINK_VERSION 2
-#endif
-
-// MESSAGE DEFINITIONS
-#include "./mavlink_msg_ping_tc.h"
-#include "./mavlink_msg_noarg_tc.h"
-
-// base include
-
-
-#undef MAVLINK_THIS_XML_IDX
-#define MAVLINK_THIS_XML_IDX 0
-
-#if MAVLINK_THIS_XML_IDX == MAVLINK_PRIMARY_XML_IDX
-# define MAVLINK_MESSAGE_INFO {{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_NOARG_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
-# define MAVLINK_MESSAGE_NAMES {{ "NOARG_TC", 10 }, { "PING_TC", 1 }}
-# if MAVLINK_COMMAND_24BIT
-# include "../mavlink_get_info.h"
-# endif
-#endif
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // MAVLINK_TEST_H
diff --git a/mavlink_lib/test/testsuite.h b/mavlink_lib/test/testsuite.h
deleted file mode 100644
index 50be1a8ec3dcf3ba0f345cfdf3c642c4e6920196..0000000000000000000000000000000000000000
--- a/mavlink_lib/test/testsuite.h
+++ /dev/null
@@ -1,145 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol testsuite generated from test.xml
- * @see http://qgroundcontrol.org/mavlink/
- */
-#pragma once
-#ifndef TEST_TESTSUITE_H
-#define TEST_TESTSUITE_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#ifndef MAVLINK_TEST_ALL
-#define MAVLINK_TEST_ALL
-
-static void mavlink_test_test(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_test(system_id, component_id, last_msg);
-}
-#endif
-
-
-
-
-static void mavlink_test_ping_tc(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_PING_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_ping_tc_t packet_in = {
- 93372036854775807ULL
- };
- mavlink_ping_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_PING_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PING_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_ping_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_pack(system_id, component_id, &msg , packet1.timestamp );
- mavlink_msg_ping_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp );
- mavlink_msg_ping_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_ping_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_ping_tc_send(MAVLINK_COMM_1 , packet1.timestamp );
- mavlink_msg_ping_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_noarg_tc(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_NOARG_TC >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_noarg_tc_t packet_in = {
- 5
- };
- mavlink_noarg_tc_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.command_id = packet_in.command_id;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_NOARG_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NOARG_TC_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_noarg_tc_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_noarg_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_noarg_tc_pack(system_id, component_id, &msg , packet1.command_id );
- mavlink_msg_noarg_tc_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_noarg_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.command_id );
- mavlink_msg_noarg_tc_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<mavlink_msg_get_send_buffer_length(&msg); i++) {
- comm_send_ch(MAVLINK_COMM_0, buffer[i]);
- }
- mavlink_msg_noarg_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_noarg_tc_send(MAVLINK_COMM_1 , packet1.command_id );
- mavlink_msg_noarg_tc_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_test(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
-{
- mavlink_test_ping_tc(system_id, component_id, last_msg);
- mavlink_test_noarg_tc(system_id, component_id, last_msg);
-}
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // TEST_TESTSUITE_H
diff --git a/mavlink_lib/test/version.h b/mavlink_lib/test/version.h
deleted file mode 100644
index 221c5478a9e85a58d8984a2dfcd799a6e1ffd3c4..0000000000000000000000000000000000000000
--- a/mavlink_lib/test/version.h
+++ /dev/null
@@ -1,14 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol built from test.xml
- * @see http://mavlink.org
- */
-#pragma once
-
-#ifndef MAVLINK_VERSION_H
-#define MAVLINK_VERSION_H
-
-#define MAVLINK_BUILD_DATE "Tue Mar 12 2019"
-#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
-#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 8
-
-#endif // MAVLINK_VERSION_H