From 3a2f353b3f8fb5a3d6bbc8df0f4301231dd43ab2 Mon Sep 17 00:00:00 2001 From: Alberto Nidasio <alberto.nidasio@skywarder.eu> Date: Sun, 4 Sep 2022 23:38:53 +0200 Subject: [PATCH] [Pyxis] Added voltage message, updated load cell sensor id and fixed timestamp units --- mavlink_lib/pyxis/mavlink.h | 2 +- mavlink_lib/pyxis/mavlink_msg_ada_tm.h | 10 +- mavlink_lib/pyxis/mavlink_msg_adc_tm.h | 10 +- mavlink_lib/pyxis/mavlink_msg_attitude_tm.h | 20 +- mavlink_lib/pyxis/mavlink_msg_can_tm.h | 10 +- mavlink_lib/pyxis/mavlink_msg_current_tm.h | 20 +- mavlink_lib/pyxis/mavlink_msg_fsm_tm.h | 10 +- mavlink_lib/pyxis/mavlink_msg_gps_tm.h | 10 +- mavlink_lib/pyxis/mavlink_msg_imu_tm.h | 10 +- mavlink_lib/pyxis/mavlink_msg_load_tm.h | 20 +- mavlink_lib/pyxis/mavlink_msg_logger_tm.h | 10 +- .../pyxis/mavlink_msg_mavlink_stats_tm.h | 10 +- mavlink_lib/pyxis/mavlink_msg_nas_tm.h | 10 +- .../pyxis/mavlink_msg_payload_flight_tm.h | 10 +- .../pyxis/mavlink_msg_payload_stats_tm.h | 50 ++-- mavlink_lib/pyxis/mavlink_msg_pin_tm.h | 20 +- mavlink_lib/pyxis/mavlink_msg_pressure_tm.h | 10 +- .../pyxis/mavlink_msg_rocket_flight_tm.h | 10 +- .../pyxis/mavlink_msg_rocket_stats_tm.h | 60 ++--- .../pyxis/mavlink_msg_sensor_state_tm.h | 10 +- mavlink_lib/pyxis/mavlink_msg_servo_tm.h | 10 +- mavlink_lib/pyxis/mavlink_msg_sys_tm.h | 10 +- mavlink_lib/pyxis/mavlink_msg_task_stats_tm.h | 10 +- mavlink_lib/pyxis/mavlink_msg_temp_tm.h | 20 +- mavlink_lib/pyxis/mavlink_msg_voltage_tm.h | 255 ++++++++++++++++++ mavlink_lib/pyxis/pyxis.h | 17 +- mavlink_lib/pyxis/testsuite.h | 62 +++++ mavlink_lib/pyxis/version.h | 2 +- message_definitions/pyxis.xml | 86 +++--- 29 files changed, 559 insertions(+), 235 deletions(-) create mode 100644 mavlink_lib/pyxis/mavlink_msg_voltage_tm.h diff --git a/mavlink_lib/pyxis/mavlink.h b/mavlink_lib/pyxis/mavlink.h index 57b4b46..4959e01 100644 --- a/mavlink_lib/pyxis/mavlink.h +++ b/mavlink_lib/pyxis/mavlink.h @@ -6,7 +6,7 @@ #ifndef MAVLINK_H #define MAVLINK_H -#define MAVLINK_PRIMARY_XML_HASH -671787516688891623 +#define MAVLINK_PRIMARY_XML_HASH 7385479015685416320 #ifndef MAVLINK_STX #define MAVLINK_STX 254 diff --git a/mavlink_lib/pyxis/mavlink_msg_ada_tm.h b/mavlink_lib/pyxis/mavlink_msg_ada_tm.h index 584d3a8..5291aad 100644 --- a/mavlink_lib/pyxis/mavlink_msg_ada_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_ada_tm.h @@ -5,7 +5,7 @@ typedef struct __mavlink_ada_tm_t { - uint64_t timestamp; /*< [ms] When was this logged*/ + 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)*/ @@ -74,7 +74,7 @@ typedef struct __mavlink_ada_tm_t { * @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 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) @@ -135,7 +135,7 @@ static inline uint16_t mavlink_msg_ada_tm_pack(uint8_t system_id, uint8_t compon * @param component_id ID of this component (e.g. 200 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 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) @@ -222,7 +222,7 @@ static inline uint16_t mavlink_msg_ada_tm_encode_chan(uint8_t system_id, uint8_t * @brief Send a ada_tm message * @param chan MAVLink channel to send the message * - * @param timestamp [ms] When was this logged + * @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) @@ -342,7 +342,7 @@ static inline void mavlink_msg_ada_tm_send_buf(mavlink_message_t *msgbuf, mavlin /** * @brief Get field timestamp from ada_tm message * - * @return [ms] When was this logged + * @return [us] When was this logged */ static inline uint64_t mavlink_msg_ada_tm_get_timestamp(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_adc_tm.h b/mavlink_lib/pyxis/mavlink_msg_adc_tm.h index ea6116c..3624e4f 100644 --- a/mavlink_lib/pyxis/mavlink_msg_adc_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_adc_tm.h @@ -5,7 +5,7 @@ typedef struct __mavlink_adc_tm_t { - uint64_t timestamp; /*< [ms] When was this logged*/ + 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*/ @@ -56,7 +56,7 @@ typedef struct __mavlink_adc_tm_t { * @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 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 @@ -97,7 +97,7 @@ static inline uint16_t mavlink_msg_adc_tm_pack(uint8_t system_id, uint8_t compon * @param component_id ID of this component (e.g. 200 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 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 @@ -164,7 +164,7 @@ static inline uint16_t mavlink_msg_adc_tm_encode_chan(uint8_t system_id, uint8_t * @brief Send a adc_tm message * @param chan MAVLink channel to send the message * - * @param timestamp [ms] When was this logged + * @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 @@ -250,7 +250,7 @@ static inline void mavlink_msg_adc_tm_send_buf(mavlink_message_t *msgbuf, mavlin /** * @brief Get field timestamp from adc_tm message * - * @return [ms] When was this logged + * @return [us] When was this logged */ static inline uint64_t mavlink_msg_adc_tm_get_timestamp(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_attitude_tm.h b/mavlink_lib/pyxis/mavlink_msg_attitude_tm.h index 47689d4..7e503ec 100644 --- a/mavlink_lib/pyxis/mavlink_msg_attitude_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_attitude_tm.h @@ -1,11 +1,11 @@ #pragma once // MESSAGE ATTITUDE_TM PACKING -#define MAVLINK_MSG_ID_ATTITUDE_TM 109 +#define MAVLINK_MSG_ID_ATTITUDE_TM 110 typedef struct __mavlink_attitude_tm_t { - uint64_t timestamp; /*< [ms] When was this logged*/ + uint64_t timestamp; /*< [us] When was this logged*/ float roll; /*< [deg] Roll angle*/ float pitch; /*< [deg] Pitch angle*/ float yaw; /*< [deg] Yaw angle*/ @@ -18,17 +18,17 @@ typedef struct __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_109_LEN 56 -#define MAVLINK_MSG_ID_109_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_109_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 { \ - 109, \ + 110, \ "ATTITUDE_TM", \ 9, \ { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_attitude_tm_t, timestamp) }, \ @@ -65,7 +65,7 @@ typedef struct __mavlink_attitude_tm_t { * @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 timestamp [us] When was this logged * @param sensor_id Sensor name * @param roll [deg] Roll angle * @param pitch [deg] Pitch angle @@ -115,7 +115,7 @@ static inline uint16_t mavlink_msg_attitude_tm_pack(uint8_t system_id, uint8_t c * @param component_id ID of this component (e.g. 200 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 timestamp [us] When was this logged * @param sensor_id Sensor name * @param roll [deg] Roll angle * @param pitch [deg] Pitch angle @@ -191,7 +191,7 @@ static inline uint16_t mavlink_msg_attitude_tm_encode_chan(uint8_t system_id, ui * @brief Send a attitude_tm message * @param chan MAVLink channel to send the message * - * @param timestamp [ms] When was this logged + * @param timestamp [us] When was this logged * @param sensor_id Sensor name * @param roll [deg] Roll angle * @param pitch [deg] Pitch angle @@ -292,7 +292,7 @@ static inline void mavlink_msg_attitude_tm_send_buf(mavlink_message_t *msgbuf, m /** * @brief Get field timestamp from attitude_tm message * - * @return [ms] When was this logged + * @return [us] When was this logged */ static inline uint64_t mavlink_msg_attitude_tm_get_timestamp(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_can_tm.h b/mavlink_lib/pyxis/mavlink_msg_can_tm.h index 4df6f9a..150c474 100644 --- a/mavlink_lib/pyxis/mavlink_msg_can_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_can_tm.h @@ -5,7 +5,7 @@ typedef struct __mavlink_can_tm_t { - uint64_t timestamp; /*< [ms] When was this logged*/ + 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*/ @@ -59,7 +59,7 @@ typedef struct __mavlink_can_tm_t { * @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 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 @@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_can_tm_pack(uint8_t system_id, uint8_t compon * @param component_id ID of this component (e.g. 200 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 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 @@ -177,7 +177,7 @@ static inline uint16_t mavlink_msg_can_tm_encode_chan(uint8_t system_id, uint8_t * @brief Send a can_tm message * @param chan MAVLink channel to send the message * - * @param timestamp [ms] When was this logged + * @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 @@ -272,7 +272,7 @@ static inline void mavlink_msg_can_tm_send_buf(mavlink_message_t *msgbuf, mavlin /** * @brief Get field timestamp from can_tm message * - * @return [ms] When was this logged + * @return [us] When was this logged */ static inline uint64_t mavlink_msg_can_tm_get_timestamp(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_current_tm.h b/mavlink_lib/pyxis/mavlink_msg_current_tm.h index 2fb229a..0c26717 100644 --- a/mavlink_lib/pyxis/mavlink_msg_current_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_current_tm.h @@ -1,28 +1,28 @@ #pragma once // MESSAGE CURRENT_TM PACKING -#define MAVLINK_MSG_ID_CURRENT_TM 106 +#define MAVLINK_MSG_ID_CURRENT_TM 107 typedef struct __mavlink_current_tm_t { - uint64_t timestamp; /*< [ms] When was this logged*/ + 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_106_LEN 32 -#define MAVLINK_MSG_ID_106_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_106_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 { \ - 106, \ + 107, \ "CURRENT_TM", \ 3, \ { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_current_tm_t, timestamp) }, \ @@ -47,7 +47,7 @@ typedef struct __mavlink_current_tm_t { * @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 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) @@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_current_tm_pack(uint8_t system_id, uint8_t co * @param component_id ID of this component (e.g. 200 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 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) @@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_current_tm_encode_chan(uint8_t system_id, uin * @brief Send a current_tm message * @param chan MAVLink channel to send the message * - * @param timestamp [ms] When was this logged + * @param timestamp [us] When was this logged * @param sensor_id Sensor name * @param current [A] Current */ @@ -208,7 +208,7 @@ static inline void mavlink_msg_current_tm_send_buf(mavlink_message_t *msgbuf, ma /** * @brief Get field timestamp from current_tm message * - * @return [ms] When was this logged + * @return [us] When was this logged */ static inline uint64_t mavlink_msg_current_tm_get_timestamp(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_fsm_tm.h b/mavlink_lib/pyxis/mavlink_msg_fsm_tm.h index 276ff87..099f3a7 100644 --- a/mavlink_lib/pyxis/mavlink_msg_fsm_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_fsm_tm.h @@ -5,7 +5,7 @@ typedef struct __mavlink_fsm_tm_t { - uint64_t timestamp; /*< [ms] Timestamp*/ + uint64_t timestamp; /*< [us] Timestamp*/ uint8_t ada_state; /*< Apogee Detection Algorithm state*/ uint8_t abk_state; /*< AirBrakes state*/ uint8_t dpl_state; /*< Deployment state*/ @@ -59,7 +59,7 @@ typedef struct __mavlink_fsm_tm_t { * @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 timestamp [us] Timestamp * @param ada_state Apogee Detection Algorithm state * @param abk_state AirBrakes state * @param dpl_state Deployment state @@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_fsm_tm_pack(uint8_t system_id, uint8_t compon * @param component_id ID of this component (e.g. 200 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 timestamp [us] Timestamp * @param ada_state Apogee Detection Algorithm state * @param abk_state AirBrakes state * @param dpl_state Deployment state @@ -177,7 +177,7 @@ static inline uint16_t mavlink_msg_fsm_tm_encode_chan(uint8_t system_id, uint8_t * @brief Send a fsm_tm message * @param chan MAVLink channel to send the message * - * @param timestamp [ms] Timestamp + * @param timestamp [us] Timestamp * @param ada_state Apogee Detection Algorithm state * @param abk_state AirBrakes state * @param dpl_state Deployment state @@ -272,7 +272,7 @@ static inline void mavlink_msg_fsm_tm_send_buf(mavlink_message_t *msgbuf, mavlin /** * @brief Get field timestamp from fsm_tm message * - * @return [ms] Timestamp + * @return [us] Timestamp */ static inline uint64_t mavlink_msg_fsm_tm_get_timestamp(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_gps_tm.h b/mavlink_lib/pyxis/mavlink_msg_gps_tm.h index 38a0bc2..779f8b8 100644 --- a/mavlink_lib/pyxis/mavlink_msg_gps_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_gps_tm.h @@ -5,7 +5,7 @@ typedef struct __mavlink_gps_tm_t { - uint64_t timestamp; /*< [ms] When was this logged*/ + uint64_t timestamp; /*< [us] When was this logged*/ double latitude; /*< [deg] Latitude*/ double longitude; /*< [deg] Longitude*/ double height; /*< [m] Altitude*/ @@ -74,7 +74,7 @@ typedef struct __mavlink_gps_tm_t { * @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 timestamp [us] When was this logged * @param sensor_id Sensor name * @param fix Wether the GPS has a FIX * @param latitude [deg] Latitude @@ -133,7 +133,7 @@ static inline uint16_t mavlink_msg_gps_tm_pack(uint8_t system_id, uint8_t compon * @param component_id ID of this component (e.g. 200 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 timestamp [us] When was this logged * @param sensor_id Sensor name * @param fix Wether the GPS has a FIX * @param latitude [deg] Latitude @@ -218,7 +218,7 @@ static inline uint16_t mavlink_msg_gps_tm_encode_chan(uint8_t system_id, uint8_t * @brief Send a gps_tm message * @param chan MAVLink channel to send the message * - * @param timestamp [ms] When was this logged + * @param timestamp [us] When was this logged * @param sensor_id Sensor name * @param fix Wether the GPS has a FIX * @param latitude [deg] Latitude @@ -334,7 +334,7 @@ static inline void mavlink_msg_gps_tm_send_buf(mavlink_message_t *msgbuf, mavlin /** * @brief Get field timestamp from gps_tm message * - * @return [ms] When was this logged + * @return [us] When was this logged */ static inline uint64_t mavlink_msg_gps_tm_get_timestamp(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_imu_tm.h b/mavlink_lib/pyxis/mavlink_msg_imu_tm.h index ada7e01..c522e3a 100644 --- a/mavlink_lib/pyxis/mavlink_msg_imu_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_imu_tm.h @@ -5,7 +5,7 @@ typedef struct __mavlink_imu_tm_t { - uint64_t timestamp; /*< [ms] When was this logged*/ + 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*/ @@ -71,7 +71,7 @@ typedef struct __mavlink_imu_tm_t { * @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 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 @@ -127,7 +127,7 @@ static inline uint16_t mavlink_msg_imu_tm_pack(uint8_t system_id, uint8_t compon * @param component_id ID of this component (e.g. 200 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 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 @@ -209,7 +209,7 @@ static inline uint16_t mavlink_msg_imu_tm_encode_chan(uint8_t system_id, uint8_t * @brief Send a imu_tm message * @param chan MAVLink channel to send the message * - * @param timestamp [ms] When was this logged + * @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 @@ -320,7 +320,7 @@ static inline void mavlink_msg_imu_tm_send_buf(mavlink_message_t *msgbuf, mavlin /** * @brief Get field timestamp from imu_tm message * - * @return [ms] When was this logged + * @return [us] When was this logged */ static inline uint64_t mavlink_msg_imu_tm_get_timestamp(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_load_tm.h b/mavlink_lib/pyxis/mavlink_msg_load_tm.h index c3cb360..ce806b6 100644 --- a/mavlink_lib/pyxis/mavlink_msg_load_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_load_tm.h @@ -1,28 +1,28 @@ #pragma once // MESSAGE LOAD_TM PACKING -#define MAVLINK_MSG_ID_LOAD_TM 108 +#define MAVLINK_MSG_ID_LOAD_TM 109 typedef struct __mavlink_load_tm_t { - uint64_t timestamp; /*< [ms] When was this logged*/ + 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_108_LEN 32 -#define MAVLINK_MSG_ID_108_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_108_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 { \ - 108, \ + 109, \ "LOAD_TM", \ 3, \ { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_load_tm_t, timestamp) }, \ @@ -47,7 +47,7 @@ typedef struct __mavlink_load_tm_t { * @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 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) @@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_load_tm_pack(uint8_t system_id, uint8_t compo * @param component_id ID of this component (e.g. 200 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 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) @@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_load_tm_encode_chan(uint8_t system_id, uint8_ * @brief Send a load_tm message * @param chan MAVLink channel to send the message * - * @param timestamp [ms] When was this logged + * @param timestamp [us] When was this logged * @param sensor_id Sensor name * @param load [deg] Load force */ @@ -208,7 +208,7 @@ static inline void mavlink_msg_load_tm_send_buf(mavlink_message_t *msgbuf, mavli /** * @brief Get field timestamp from load_tm message * - * @return [ms] When was this logged + * @return [us] When was this logged */ static inline uint64_t mavlink_msg_load_tm_get_timestamp(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_logger_tm.h b/mavlink_lib/pyxis/mavlink_msg_logger_tm.h index df91066..ac52b5a 100644 --- a/mavlink_lib/pyxis/mavlink_msg_logger_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_logger_tm.h @@ -5,7 +5,7 @@ typedef struct __mavlink_logger_tm_t { - uint64_t timestamp; /*< [ms] Timestamp*/ + 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*/ @@ -71,7 +71,7 @@ typedef struct __mavlink_logger_tm_t { * @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 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 @@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_logger_tm_pack(uint8_t system_id, uint8_t com * @param component_id ID of this component (e.g. 200 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 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 @@ -213,7 +213,7 @@ static inline uint16_t mavlink_msg_logger_tm_encode_chan(uint8_t system_id, uint * @brief Send a logger_tm message * @param chan MAVLink channel to send the message * - * @param timestamp [ms] Timestamp + * @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 @@ -328,7 +328,7 @@ static inline void mavlink_msg_logger_tm_send_buf(mavlink_message_t *msgbuf, mav /** * @brief Get field timestamp from logger_tm message * - * @return [ms] Timestamp + * @return [us] Timestamp */ static inline uint64_t mavlink_msg_logger_tm_get_timestamp(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_mavlink_stats_tm.h b/mavlink_lib/pyxis/mavlink_msg_mavlink_stats_tm.h index 1d8ce90..ba89b5f 100644 --- a/mavlink_lib/pyxis/mavlink_msg_mavlink_stats_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_mavlink_stats_tm.h @@ -5,7 +5,7 @@ typedef struct __mavlink_mavlink_stats_tm_t { - uint64_t timestamp; /*< [ms] When was this logged */ + 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 */ @@ -77,7 +77,7 @@ typedef struct __mavlink_mavlink_stats_tm_t { * @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 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 @@ -141,7 +141,7 @@ static inline uint16_t mavlink_msg_mavlink_stats_tm_pack(uint8_t system_id, uint * @param component_id ID of this component (e.g. 200 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 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 @@ -231,7 +231,7 @@ static inline uint16_t mavlink_msg_mavlink_stats_tm_encode_chan(uint8_t system_i * @brief Send a mavlink_stats_tm message * @param chan MAVLink channel to send the message * - * @param timestamp [ms] When was this logged + * @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 @@ -356,7 +356,7 @@ static inline void mavlink_msg_mavlink_stats_tm_send_buf(mavlink_message_t *msgb /** * @brief Get field timestamp from mavlink_stats_tm message * - * @return [ms] When was this logged + * @return [us] When was this logged */ static inline uint64_t mavlink_msg_mavlink_stats_tm_get_timestamp(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_nas_tm.h b/mavlink_lib/pyxis/mavlink_msg_nas_tm.h index 1ec78e8..47a786d 100644 --- a/mavlink_lib/pyxis/mavlink_msg_nas_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_nas_tm.h @@ -5,7 +5,7 @@ typedef struct __mavlink_nas_tm_t { - uint64_t timestamp; /*< [ms] When was this logged*/ + 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*/ @@ -95,7 +95,7 @@ typedef struct __mavlink_nas_tm_t { * @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 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 @@ -177,7 +177,7 @@ static inline uint16_t mavlink_msg_nas_tm_pack(uint8_t system_id, uint8_t compon * @param component_id ID of this component (e.g. 200 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 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 @@ -285,7 +285,7 @@ static inline uint16_t mavlink_msg_nas_tm_encode_chan(uint8_t system_id, uint8_t * @brief Send a nas_tm message * @param chan MAVLink channel to send the message * - * @param timestamp [ms] When was this logged + * @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 @@ -440,7 +440,7 @@ static inline void mavlink_msg_nas_tm_send_buf(mavlink_message_t *msgbuf, mavlin /** * @brief Get field timestamp from nas_tm message * - * @return [ms] When was this logged + * @return [us] When was this logged */ static inline uint64_t mavlink_msg_nas_tm_get_timestamp(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_payload_flight_tm.h b/mavlink_lib/pyxis/mavlink_msg_payload_flight_tm.h index aedfc75..3370efb 100644 --- a/mavlink_lib/pyxis/mavlink_msg_payload_flight_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_payload_flight_tm.h @@ -5,7 +5,7 @@ typedef struct __mavlink_payload_flight_tm_t { - uint64_t timestamp; /*< [ms] Timestamp in milliseconds*/ + 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*/ @@ -161,7 +161,7 @@ typedef struct __mavlink_payload_flight_tm_t { * @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 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 @@ -309,7 +309,7 @@ static inline uint16_t mavlink_msg_payload_flight_tm_pack(uint8_t system_id, uin * @param component_id ID of this component (e.g. 200 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 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 @@ -483,7 +483,7 @@ static inline uint16_t mavlink_msg_payload_flight_tm_encode_chan(uint8_t system_ * @brief Send a payload_flight_tm message * @param chan MAVLink channel to send the message * - * @param timestamp [ms] Timestamp in milliseconds + * @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 @@ -748,7 +748,7 @@ static inline void mavlink_msg_payload_flight_tm_send_buf(mavlink_message_t *msg /** * @brief Get field timestamp from payload_flight_tm message * - * @return [ms] Timestamp in milliseconds + * @return [us] Timestamp in milliseconds */ static inline uint64_t mavlink_msg_payload_flight_tm_get_timestamp(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_payload_stats_tm.h b/mavlink_lib/pyxis/mavlink_msg_payload_stats_tm.h index d461aa9..9a226a3 100644 --- a/mavlink_lib/pyxis/mavlink_msg_payload_stats_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_payload_stats_tm.h @@ -5,11 +5,11 @@ typedef struct __mavlink_payload_stats_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 liftoff_ts; /*< [us] System clock at liftoff*/ + uint64_t liftoff_max_acc_ts; /*< [us] System clock at the maximum liftoff acceleration*/ + uint64_t max_z_speed_ts; /*< [us] System clock at ADA max vertical speed*/ + uint64_t apogee_ts; /*< [us] System clock at apogee*/ + uint64_t drogue_dpl_ts; /*< [us] System clock at drouge 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*/ @@ -95,14 +95,14 @@ typedef struct __mavlink_payload_stats_tm_t { * @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_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 max_z_speed_ts [ms] System clock at ADA max vertical speed + * @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 [ms] System clock at apogee + * @param apogee_ts [us] 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 @@ -110,7 +110,7 @@ typedef struct __mavlink_payload_stats_tm_t { * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered * @param baro_max_altitude [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_ts [us] System clock at drouge deployment * @param drogue_dpl_max_acc [m/s2] Max acceleration during drouge deployment * @param cpu_load CPU load in percentage * @param free_heap Amount of available heap in memory @@ -177,14 +177,14 @@ static inline uint16_t mavlink_msg_payload_stats_tm_pack(uint8_t system_id, uint * @param component_id ID of this component (e.g. 200 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_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 max_z_speed_ts [ms] System clock at ADA max vertical speed + * @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 [ms] System clock at apogee + * @param apogee_ts [us] 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 @@ -192,7 +192,7 @@ static inline uint16_t mavlink_msg_payload_stats_tm_pack(uint8_t system_id, uint * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered * @param baro_max_altitude [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_ts [us] System clock at drouge deployment * @param drogue_dpl_max_acc [m/s2] Max acceleration during drouge deployment * @param cpu_load CPU load in percentage * @param free_heap Amount of available heap in memory @@ -285,14 +285,14 @@ static inline uint16_t mavlink_msg_payload_stats_tm_encode_chan(uint8_t system_i * @brief Send a payload_stats_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_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 max_z_speed_ts [ms] System clock at ADA max vertical speed + * @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 [ms] System clock at apogee + * @param apogee_ts [us] 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 @@ -300,7 +300,7 @@ static inline uint16_t mavlink_msg_payload_stats_tm_encode_chan(uint8_t system_i * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered * @param baro_max_altitude [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_ts [us] System clock at drouge deployment * @param drogue_dpl_max_acc [m/s2] Max acceleration during drouge deployment * @param cpu_load CPU load in percentage * @param free_heap Amount of available heap in memory @@ -440,7 +440,7 @@ static inline void mavlink_msg_payload_stats_tm_send_buf(mavlink_message_t *msgb /** * @brief Get field liftoff_ts from payload_stats_tm message * - * @return [ms] System clock at liftoff + * @return [us] System clock at liftoff */ static inline uint64_t mavlink_msg_payload_stats_tm_get_liftoff_ts(const mavlink_message_t* msg) { @@ -450,7 +450,7 @@ static inline uint64_t mavlink_msg_payload_stats_tm_get_liftoff_ts(const mavlink /** * @brief Get field liftoff_max_acc_ts from payload_stats_tm message * - * @return [ms] System clock at the maximum liftoff acceleration + * @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) { @@ -470,7 +470,7 @@ static inline float mavlink_msg_payload_stats_tm_get_liftoff_max_acc(const mavli /** * @brief Get field max_z_speed_ts from payload_stats_tm message * - * @return [ms] System clock at ADA max vertical speed + * @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) { @@ -510,7 +510,7 @@ static inline float mavlink_msg_payload_stats_tm_get_max_speed_altitude(const ma /** * @brief Get field apogee_ts from payload_stats_tm message * - * @return [ms] System clock at apogee + * @return [us] System clock at apogee */ static inline uint64_t mavlink_msg_payload_stats_tm_get_apogee_ts(const mavlink_message_t* msg) { @@ -590,7 +590,7 @@ static inline float mavlink_msg_payload_stats_tm_get_gps_max_altitude(const mavl /** * @brief Get field drogue_dpl_ts from payload_stats_tm message * - * @return [ms] System clock at drouge deployment + * @return [us] System clock at drouge deployment */ static inline uint64_t mavlink_msg_payload_stats_tm_get_drogue_dpl_ts(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_pin_tm.h b/mavlink_lib/pyxis/mavlink_msg_pin_tm.h index 9a93502..80cc7d6 100644 --- a/mavlink_lib/pyxis/mavlink_msg_pin_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_pin_tm.h @@ -1,11 +1,11 @@ #pragma once // MESSAGE PIN_TM PACKING -#define MAVLINK_MSG_ID_PIN_TM 112 +#define MAVLINK_MSG_ID_PIN_TM 113 typedef struct __mavlink_pin_tm_t { - uint64_t timestamp; /*< [ms] Timestamp*/ + 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*/ @@ -14,17 +14,17 @@ typedef struct __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_112_LEN 19 -#define MAVLINK_MSG_ID_112_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_112_CRC 255 +#define MAVLINK_MSG_ID_113_CRC 255 #if MAVLINK_COMMAND_24BIT #define MAVLINK_MESSAGE_INFO_PIN_TM { \ - 112, \ + 113, \ "PIN_TM", \ 5, \ { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_pin_tm_t, timestamp) }, \ @@ -53,7 +53,7 @@ typedef struct __mavlink_pin_tm_t { * @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 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 @@ -93,7 +93,7 @@ static inline uint16_t mavlink_msg_pin_tm_pack(uint8_t system_id, uint8_t compon * @param component_id ID of this component (e.g. 200 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 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 @@ -159,7 +159,7 @@ static inline uint16_t mavlink_msg_pin_tm_encode_chan(uint8_t system_id, uint8_t * @brief Send a pin_tm message * @param chan MAVLink channel to send the message * - * @param timestamp [ms] Timestamp + * @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 @@ -244,7 +244,7 @@ static inline void mavlink_msg_pin_tm_send_buf(mavlink_message_t *msgbuf, mavlin /** * @brief Get field timestamp from pin_tm message * - * @return [ms] Timestamp + * @return [us] Timestamp */ static inline uint64_t mavlink_msg_pin_tm_get_timestamp(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_pressure_tm.h b/mavlink_lib/pyxis/mavlink_msg_pressure_tm.h index 109fbc7..0c5f1ba 100644 --- a/mavlink_lib/pyxis/mavlink_msg_pressure_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_pressure_tm.h @@ -5,7 +5,7 @@ typedef struct __mavlink_pressure_tm_t { - uint64_t timestamp; /*< [ms] When was this logged*/ + 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; @@ -47,7 +47,7 @@ typedef struct __mavlink_pressure_tm_t { * @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 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) @@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_pressure_tm_pack(uint8_t system_id, uint8_t c * @param component_id ID of this component (e.g. 200 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 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) @@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_pressure_tm_encode_chan(uint8_t system_id, ui * @brief Send a pressure_tm message * @param chan MAVLink channel to send the message * - * @param timestamp [ms] When was this logged + * @param timestamp [us] When was this logged * @param sensor_id Sensor name * @param pressure [Pa] Pressure of the digital barometer */ @@ -208,7 +208,7 @@ static inline void mavlink_msg_pressure_tm_send_buf(mavlink_message_t *msgbuf, m /** * @brief Get field timestamp from pressure_tm message * - * @return [ms] When was this logged + * @return [us] When was this logged */ static inline uint64_t mavlink_msg_pressure_tm_get_timestamp(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_rocket_flight_tm.h b/mavlink_lib/pyxis/mavlink_msg_rocket_flight_tm.h index e9c4b63..088796d 100644 --- a/mavlink_lib/pyxis/mavlink_msg_rocket_flight_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_rocket_flight_tm.h @@ -5,7 +5,7 @@ typedef struct __mavlink_rocket_flight_tm_t { - uint64_t timestamp; /*< [ms] Timestamp in milliseconds*/ + 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*/ @@ -182,7 +182,7 @@ typedef struct __mavlink_rocket_flight_tm_t { * @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 timestamp [us] Timestamp in milliseconds * @param ada_state ADA Controller State * @param fmm_state Flight Mode Manager State * @param dpl_state Deployment Controller State @@ -351,7 +351,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_pack(uint8_t system_id, uint * @param component_id ID of this component (e.g. 200 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 timestamp [us] Timestamp in milliseconds * @param ada_state ADA Controller State * @param fmm_state Flight Mode Manager State * @param dpl_state Deployment Controller State @@ -546,7 +546,7 @@ static inline uint16_t mavlink_msg_rocket_flight_tm_encode_chan(uint8_t system_i * @brief Send a rocket_flight_tm message * @param chan MAVLink channel to send the message * - * @param timestamp [ms] Timestamp in milliseconds + * @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 @@ -846,7 +846,7 @@ static inline void mavlink_msg_rocket_flight_tm_send_buf(mavlink_message_t *msgb /** * @brief Get field timestamp from rocket_flight_tm message * - * @return [ms] Timestamp in milliseconds + * @return [us] Timestamp in milliseconds */ static inline uint64_t mavlink_msg_rocket_flight_tm_get_timestamp(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_rocket_stats_tm.h b/mavlink_lib/pyxis/mavlink_msg_rocket_stats_tm.h index bf80eda..3440fd4 100644 --- a/mavlink_lib/pyxis/mavlink_msg_rocket_stats_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_rocket_stats_tm.h @@ -5,12 +5,12 @@ typedef struct __mavlink_rocket_stats_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*/ + 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 max_z_speed_ts; /*< [us] System clock at ADA max vertical speed*/ + uint64_t apogee_ts; /*< [us] System clock at apogee*/ + uint64_t drogue_dpl_ts; /*< [us] System clock at drouge deployment*/ + uint64_t main_dpl_altitude_ts; /*< [us] 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*/ @@ -110,14 +110,14 @@ typedef struct __mavlink_rocket_stats_tm_t { * @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_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 max_z_speed_ts [ms] System clock at ADA max vertical speed + * @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 [ms] System clock at apogee + * @param apogee_ts [us] 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 @@ -125,10 +125,10 @@ typedef struct __mavlink_rocket_stats_tm_t { * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered * @param baro_max_altitude [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_ts [us] 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_ts [us] 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 @@ -207,14 +207,14 @@ static inline uint16_t mavlink_msg_rocket_stats_tm_pack(uint8_t system_id, uint8 * @param component_id ID of this component (e.g. 200 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_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 max_z_speed_ts [ms] System clock at ADA max vertical speed + * @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 [ms] System clock at apogee + * @param apogee_ts [us] 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 @@ -222,10 +222,10 @@ static inline uint16_t mavlink_msg_rocket_stats_tm_pack(uint8_t system_id, uint8 * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered * @param baro_max_altitude [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_ts [us] 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_ts [us] 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 @@ -330,14 +330,14 @@ static inline uint16_t mavlink_msg_rocket_stats_tm_encode_chan(uint8_t system_id * @brief Send a rocket_stats_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_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 max_z_speed_ts [ms] System clock at ADA max vertical speed + * @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 [ms] System clock at apogee + * @param apogee_ts [us] 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 @@ -345,10 +345,10 @@ static inline uint16_t mavlink_msg_rocket_stats_tm_encode_chan(uint8_t system_id * @param ada_min_pressure [Pa] Apogee pressure - ADA filtered * @param baro_max_altitude [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_ts [us] 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_ts [us] 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 @@ -510,7 +510,7 @@ static inline void mavlink_msg_rocket_stats_tm_send_buf(mavlink_message_t *msgbu /** * @brief Get field liftoff_ts from rocket_stats_tm message * - * @return [ms] System clock at liftoff + * @return [us] System clock at liftoff */ static inline uint64_t mavlink_msg_rocket_stats_tm_get_liftoff_ts(const mavlink_message_t* msg) { @@ -520,7 +520,7 @@ static inline uint64_t mavlink_msg_rocket_stats_tm_get_liftoff_ts(const mavlink_ /** * @brief Get field liftoff_max_acc_ts from rocket_stats_tm message * - * @return [ms] System clock at the maximum liftoff acceleration + * @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) { @@ -540,7 +540,7 @@ static inline float mavlink_msg_rocket_stats_tm_get_liftoff_max_acc(const mavlin /** * @brief Get field max_z_speed_ts from rocket_stats_tm message * - * @return [ms] System clock at ADA max vertical speed + * @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) { @@ -580,7 +580,7 @@ static inline float mavlink_msg_rocket_stats_tm_get_max_speed_altitude(const mav /** * @brief Get field apogee_ts from rocket_stats_tm message * - * @return [ms] System clock at apogee + * @return [us] System clock at apogee */ static inline uint64_t mavlink_msg_rocket_stats_tm_get_apogee_ts(const mavlink_message_t* msg) { @@ -660,7 +660,7 @@ static inline float mavlink_msg_rocket_stats_tm_get_gps_max_altitude(const mavli /** * @brief Get field drogue_dpl_ts from rocket_stats_tm message * - * @return [ms] System clock at drouge deployment + * @return [us] System clock at drouge deployment */ static inline uint64_t mavlink_msg_rocket_stats_tm_get_drogue_dpl_ts(const mavlink_message_t* msg) { @@ -690,7 +690,7 @@ static inline float mavlink_msg_rocket_stats_tm_get_dpl_vane_max_pressure(const /** * @brief Get field main_dpl_altitude_ts from rocket_stats_tm message * - * @return [ms] System clock at main chute deployment + * @return [us] System clock at main chute deployment */ static inline uint64_t mavlink_msg_rocket_stats_tm_get_main_dpl_altitude_ts(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_sensor_state_tm.h b/mavlink_lib/pyxis/mavlink_msg_sensor_state_tm.h index 4cd3ad1..fed43a8 100644 --- a/mavlink_lib/pyxis/mavlink_msg_sensor_state_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_sensor_state_tm.h @@ -1,7 +1,7 @@ #pragma once // MESSAGE SENSOR_STATE_TM PACKING -#define MAVLINK_MSG_ID_SENSOR_STATE_TM 110 +#define MAVLINK_MSG_ID_SENSOR_STATE_TM 111 typedef struct __mavlink_sensor_state_tm_t { @@ -11,17 +11,17 @@ typedef struct __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_110_LEN 21 -#define MAVLINK_MSG_ID_110_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_110_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 { \ - 110, \ + 111, \ "SENSOR_STATE_TM", \ 2, \ { { "sensor_id", NULL, MAVLINK_TYPE_CHAR, 20, 0, offsetof(mavlink_sensor_state_tm_t, sensor_id) }, \ diff --git a/mavlink_lib/pyxis/mavlink_msg_servo_tm.h b/mavlink_lib/pyxis/mavlink_msg_servo_tm.h index 87036fd..0ffe705 100644 --- a/mavlink_lib/pyxis/mavlink_msg_servo_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_servo_tm.h @@ -1,7 +1,7 @@ #pragma once // MESSAGE SERVO_TM PACKING -#define MAVLINK_MSG_ID_SERVO_TM 111 +#define MAVLINK_MSG_ID_SERVO_TM 112 typedef struct __mavlink_servo_tm_t { @@ -11,17 +11,17 @@ typedef struct __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_111_LEN 5 -#define MAVLINK_MSG_ID_111_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_111_CRC 87 +#define MAVLINK_MSG_ID_112_CRC 87 #if MAVLINK_COMMAND_24BIT #define MAVLINK_MESSAGE_INFO_SERVO_TM { \ - 111, \ + 112, \ "SERVO_TM", \ 2, \ { { "servo_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_servo_tm_t, servo_id) }, \ diff --git a/mavlink_lib/pyxis/mavlink_msg_sys_tm.h b/mavlink_lib/pyxis/mavlink_msg_sys_tm.h index 3714091..460e076 100644 --- a/mavlink_lib/pyxis/mavlink_msg_sys_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_sys_tm.h @@ -5,7 +5,7 @@ typedef struct __mavlink_sys_tm_t { - uint64_t timestamp; /*< [ms] Timestamp*/ + 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*/ @@ -59,7 +59,7 @@ typedef struct __mavlink_sys_tm_t { * @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 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 @@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_sys_tm_pack(uint8_t system_id, uint8_t compon * @param component_id ID of this component (e.g. 200 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 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 @@ -177,7 +177,7 @@ static inline uint16_t mavlink_msg_sys_tm_encode_chan(uint8_t system_id, uint8_t * @brief Send a sys_tm message * @param chan MAVLink channel to send the message * - * @param timestamp [ms] Timestamp + * @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 @@ -272,7 +272,7 @@ static inline void mavlink_msg_sys_tm_send_buf(mavlink_message_t *msgbuf, mavlin /** * @brief Get field timestamp from sys_tm message * - * @return [ms] Timestamp + * @return [us] Timestamp */ static inline uint64_t mavlink_msg_sys_tm_get_timestamp(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_task_stats_tm.h b/mavlink_lib/pyxis/mavlink_msg_task_stats_tm.h index 72be686..8172705 100644 --- a/mavlink_lib/pyxis/mavlink_msg_task_stats_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_task_stats_tm.h @@ -5,7 +5,7 @@ typedef struct __mavlink_task_stats_tm_t { - uint64_t timestamp; /*< [ms] When was this logged */ + 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*/ @@ -59,7 +59,7 @@ typedef struct __mavlink_task_stats_tm_t { * @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 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 @@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_task_stats_tm_pack(uint8_t system_id, uint8_t * @param component_id ID of this component (e.g. 200 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 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 @@ -177,7 +177,7 @@ static inline uint16_t mavlink_msg_task_stats_tm_encode_chan(uint8_t system_id, * @brief Send a task_stats_tm message * @param chan MAVLink channel to send the message * - * @param timestamp [ms] When was this logged + * @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 @@ -272,7 +272,7 @@ static inline void mavlink_msg_task_stats_tm_send_buf(mavlink_message_t *msgbuf, /** * @brief Get field timestamp from task_stats_tm message * - * @return [ms] When was this logged + * @return [us] When was this logged */ static inline uint64_t mavlink_msg_task_stats_tm_get_timestamp(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_temp_tm.h b/mavlink_lib/pyxis/mavlink_msg_temp_tm.h index 3b4dfa9..dc45028 100644 --- a/mavlink_lib/pyxis/mavlink_msg_temp_tm.h +++ b/mavlink_lib/pyxis/mavlink_msg_temp_tm.h @@ -1,28 +1,28 @@ #pragma once // MESSAGE TEMP_TM PACKING -#define MAVLINK_MSG_ID_TEMP_TM 107 +#define MAVLINK_MSG_ID_TEMP_TM 108 typedef struct __mavlink_temp_tm_t { - uint64_t timestamp; /*< [ms] When was this logged*/ + 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_107_LEN 32 -#define MAVLINK_MSG_ID_107_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_107_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 { \ - 107, \ + 108, \ "TEMP_TM", \ 3, \ { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_temp_tm_t, timestamp) }, \ @@ -47,7 +47,7 @@ typedef struct __mavlink_temp_tm_t { * @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 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) @@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_temp_tm_pack(uint8_t system_id, uint8_t compo * @param component_id ID of this component (e.g. 200 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 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) @@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_temp_tm_encode_chan(uint8_t system_id, uint8_ * @brief Send a temp_tm message * @param chan MAVLink channel to send the message * - * @param timestamp [ms] When was this logged + * @param timestamp [us] When was this logged * @param sensor_id Sensor name * @param temperature [deg] Temperature */ @@ -208,7 +208,7 @@ static inline void mavlink_msg_temp_tm_send_buf(mavlink_message_t *msgbuf, mavli /** * @brief Get field timestamp from temp_tm message * - * @return [ms] When was this logged + * @return [us] When was this logged */ static inline uint64_t mavlink_msg_temp_tm_get_timestamp(const mavlink_message_t* msg) { diff --git a/mavlink_lib/pyxis/mavlink_msg_voltage_tm.h b/mavlink_lib/pyxis/mavlink_msg_voltage_tm.h new file mode 100644 index 0000000..3bb29bb --- /dev/null +++ b/mavlink_lib/pyxis/mavlink_msg_voltage_tm.h @@ -0,0 +1,255 @@ +#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/pyxis.h b/mavlink_lib/pyxis/pyxis.h index 1db94a9..58561dd 100644 --- a/mavlink_lib/pyxis/pyxis.h +++ b/mavlink_lib/pyxis/pyxis.h @@ -11,7 +11,7 @@ #endif #undef MAVLINK_THIS_XML_HASH -#define MAVLINK_THIS_XML_HASH -671787516688891623 +#define MAVLINK_THIS_XML_HASH 7385479015685416320 #ifdef __cplusplus extern "C" { @@ -20,11 +20,11 @@ extern "C" { // 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, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 49, 77, 30, 163, 150, 120, 96, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 49, 77, 30, 163, 150, 120, 96, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 69, 142, 108, 133, 79, 66, 169, 252, 223, 169, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 69, 142, 108, 133, 79, 66, 169, 252, 223, 169, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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" @@ -73,7 +73,7 @@ typedef enum SensorsTMList 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_STRAIN_GAUGE_ID=14, /* Strain gauge data | */ + MAV_LOAD_CELL_ID=14, /* Load cell data | */ SensorsTMList_ENUM_END=15, /* | */ } SensorsTMList; #endif @@ -93,7 +93,7 @@ typedef enum MavCommandList 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_CLOSE_LOG=11, /* Command to permanently close the log file | */ + 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 | */ @@ -162,6 +162,7 @@ typedef enum PinsList #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" @@ -186,11 +187,11 @@ typedef enum PinsList #undef MAVLINK_THIS_XML_HASH -#define MAVLINK_THIS_XML_HASH -671787516688891623 +#define MAVLINK_THIS_XML_HASH 7385479015685416320 #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_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}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_CAN_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}}}} -# define MAVLINK_MESSAGE_NAMES {{ "ACK_TM", 100 }, { "ADA_TM", 205 }, { "ADC_TM", 105 }, { "ATTITUDE_TM", 109 }, { "CAN_TM", 207 }, { "COMMAND_TC", 2 }, { "CURRENT_TM", 106 }, { "FSM_TM", 201 }, { "GPS_TM", 102 }, { "IMU_TM", 103 }, { "LOAD_TM", 108 }, { "LOGGER_TM", 202 }, { "MAVLINK_STATS_TM", 203 }, { "NACK_TM", 101 }, { "NAS_TM", 206 }, { "PAYLOAD_FLIGHT_TM", 209 }, { "PAYLOAD_STATS_TM", 211 }, { "PING_TC", 1 }, { "PIN_TM", 112 }, { "PRESSURE_TM", 104 }, { "RAW_EVENT_TC", 13 }, { "RESET_SERVO_TC", 8 }, { "ROCKET_FLIGHT_TM", 208 }, { "ROCKET_STATS_TM", 210 }, { "SENSOR_STATE_TM", 110 }, { "SENSOR_TM_REQUEST_TC", 4 }, { "SERVO_TM", 111 }, { "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", 107 }, { "WIGGLE_SERVO_TC", 7 }} +# 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}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_CAN_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}}}} +# define MAVLINK_MESSAGE_NAMES {{ "ACK_TM", 100 }, { "ADA_TM", 205 }, { "ADC_TM", 105 }, { "ATTITUDE_TM", 110 }, { "CAN_TM", 207 }, { "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", 209 }, { "PAYLOAD_STATS_TM", 211 }, { "PING_TC", 1 }, { "PIN_TM", 113 }, { "PRESSURE_TM", 104 }, { "RAW_EVENT_TC", 13 }, { "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_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 diff --git a/mavlink_lib/pyxis/testsuite.h b/mavlink_lib/pyxis/testsuite.h index 7ac6786..5e6d5e2 100644 --- a/mavlink_lib/pyxis/testsuite.h +++ b/mavlink_lib/pyxis/testsuite.h @@ -1359,6 +1359,67 @@ static void mavlink_test_adc_tm(uint8_t system_id, uint8_t component_id, mavlink #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 @@ -2727,6 +2788,7 @@ static void mavlink_test_pyxis(uint8_t system_id, uint8_t component_id, mavlink_ 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); diff --git a/mavlink_lib/pyxis/version.h b/mavlink_lib/pyxis/version.h index 54b0327..954da11 100644 --- a/mavlink_lib/pyxis/version.h +++ b/mavlink_lib/pyxis/version.h @@ -7,7 +7,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Wed Aug 24 2022" +#define MAVLINK_BUILD_DATE "Sun Sep 04 2022" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 163 diff --git a/message_definitions/pyxis.xml b/message_definitions/pyxis.xml index a037a75..33b6b34 100644 --- a/message_definitions/pyxis.xml +++ b/message_definitions/pyxis.xml @@ -82,8 +82,8 @@ <entry name="MAV_BATTERY_VOLTAGE_ID" value="13"> <description>Battery voltage data</description> </entry> - <entry name="MAV_STRAIN_GAUGE_ID" value="14"> - <description>Strain gauge data</description> + <entry name="MAV_LOAD_CELL_ID" value="14"> + <description>Load cell data</description> </entry> </enum> <enum name="MavCommandList"> @@ -118,7 +118,7 @@ <entry name="MAV_CMD_START_LOGGING" value="10"> <description>Command to enable sensor logging</description> </entry> - <entry name="MAV_CMD_CLOSE_LOG" value="11"> + <entry name="MAV_CMD_STOP_LOGGING" value="11"> <description>Command to permanently close the log file</description> </entry> <entry name="MAV_CMD_FORCE_REBOOT" value="12"> @@ -239,7 +239,7 @@ </message> <message id="102" name="GPS_TM"> <description></description> - <field name="timestamp" type="uint64_t" units="ms">When was this logged</field> + <field name="timestamp" type="uint64_t" units="us">When was this logged</field> <field name="sensor_id" type="char[20]">Sensor name</field> <field name="fix" type="uint8_t">Wether the GPS has a FIX</field> <field name="latitude" type="double" units="deg">Latitude</field> @@ -254,7 +254,7 @@ </message> <message id="103" name="IMU_TM"> <description></description> - <field name="timestamp" type="uint64_t" units="ms">When was this logged</field> + <field name="timestamp" type="uint64_t" units="us">When was this logged</field> <field name="sensor_id" type="char[20]">Sensor name</field> <field name="acc_x" type="float" units="m/s2">X axis acceleration</field> <field name="acc_y" type="float" units="m/s2">Y axis acceleration</field> @@ -268,40 +268,46 @@ </message> <message id="104" name="PRESSURE_TM"> <description></description> - <field name="timestamp" type="uint64_t" units="ms">When was this logged</field> + <field name="timestamp" type="uint64_t" units="us">When was this logged</field> <field name="sensor_id" type="char[20]">Sensor name</field> <field name="pressure" type="float" units="Pa">Pressure of the digital barometer</field> </message> <message id="105" name="ADC_TM"> <description></description> - <field name="timestamp" type="uint64_t" units="ms">When was this logged</field> + <field name="timestamp" type="uint64_t" units="us">When was this logged</field> <field name="sensor_id" type="char[20]">Sensor name</field> <field name="channel_0" type="float" units="V">ADC voltage measured on channel 0</field> <field name="channel_1" type="float" units="V">ADC voltage measured on channel 1</field> <field name="channel_2" type="float" units="V">ADC voltage measured on channel 2</field> <field name="channel_3" type="float" units="V">ADC voltage measured on channel 3</field> </message> - <message id="106" name="CURRENT_TM"> + <message id="106" name="VOLTAGE_TM"> <description></description> - <field name="timestamp" type="uint64_t" units="ms">When was this logged</field> + <field name="timestamp" type="uint64_t" units="us">When was this logged</field> + <field name="sensor_id" type="char[20]">Sensor name</field> + <field name="voltage" type="float" units="V">Voltage</field> + </message> + <message id="107" name="CURRENT_TM"> + <description></description> + <field name="timestamp" type="uint64_t" units="us">When was this logged</field> <field name="sensor_id" type="char[20]">Sensor name</field> <field name="current" type="float" units="A">Current</field> </message> - <message id="107" name="TEMP_TM"> + <message id="108" name="TEMP_TM"> <description></description> - <field name="timestamp" type="uint64_t" units="ms">When was this logged</field> + <field name="timestamp" type="uint64_t" units="us">When was this logged</field> <field name="sensor_id" type="char[20]">Sensor name</field> <field name="temperature" type="float" units="deg">Temperature</field> </message> - <message id="108" name="LOAD_TM"> + <message id="109" name="LOAD_TM"> <description></description> - <field name="timestamp" type="uint64_t" units="ms">When was this logged</field> + <field name="timestamp" type="uint64_t" units="us">When was this logged</field> <field name="sensor_id" type="char[20]">Sensor name</field> <field name="load" type="float" units="deg">Load force</field> </message> - <message id="109" name="ATTITUDE_TM"> + <message id="110" name="ATTITUDE_TM"> <description></description> - <field name="timestamp" type="uint64_t" units="ms">When was this logged</field> + <field name="timestamp" type="uint64_t" units="us">When was this logged</field> <field name="sensor_id" type="char[20]">Sensor name</field> <field name="roll" type="float" units="deg">Roll angle</field> <field name="pitch" type="float" units="deg">Pitch angle</field> @@ -311,19 +317,19 @@ <field name="quat_z" type="float">Quaternion z component</field> <field name="quat_w" type="float">Quaternion w component</field> </message> - <message id="110" name="SENSOR_STATE_TM"> + <message id="111" name="SENSOR_STATE_TM"> <description></description> <field name="sensor_id" type="char[20]">Sensor name</field> <field name="state" type="uint8_t">Boolean that represents the init state</field> </message> - <message id="111" name="SERVO_TM"> + <message id="112" name="SERVO_TM"> <description></description> <field name="servo_id" type="uint8_t">A member of the ServosList enum</field> <field name="servo_position" type="float">Position of the servo [0-1]</field> </message> - <message id="112" name="PIN_TM"> + <message id="113" name="PIN_TM"> <description></description> - <field name="timestamp" type="uint64_t" units="ms">Timestamp</field> + <field name="timestamp" type="uint64_t" units="us">Timestamp</field> <field name="pin_id" type="uint8_t">A member of the PinsList enum</field> <field name="last_change_timestamp" type="uint64_t">Last change timestamp of pin</field> <field name="changes_counter" type="uint8_t">Number of changes of pin</field> @@ -333,7 +339,7 @@ <!-- FROM ROCKET TO GROUND: SPECIFIC --> <message id="200" name="SYS_TM"> <description>System status telemetry</description> - <field name="timestamp" type="uint64_t" units="ms">Timestamp</field> + <field name="timestamp" type="uint64_t" units="us">Timestamp</field> <field name="logger" type="uint8_t">True if the logger started correctly</field> <field name="event_broker" type="uint8_t">True if the event broker started correctly</field> <field name="radio" type="uint8_t">True if the radio started correctly</field> @@ -344,7 +350,7 @@ <message id="201" name="FSM_TM"> <!-- SAME FOR ROCKET AND PAYLOAD BUT ONE SET SHOULD CONTAIN THE OTHER --> <description>Flight State Machine status telemetry</description> - <field name="timestamp" type="uint64_t" units="ms">Timestamp</field> + <field name="timestamp" type="uint64_t" units="us">Timestamp</field> <field name="ada_state" type="uint8_t">Apogee Detection Algorithm state</field> <field name="abk_state" type="uint8_t">AirBrakes state</field> <field name="dpl_state" type="uint8_t">Deployment state</field> @@ -354,7 +360,7 @@ </message> <message id="202" name="LOGGER_TM"> <description>Logger status telemetry</description> - <field name="timestamp" type="uint64_t" units="ms">Timestamp</field> + <field name="timestamp" type="uint64_t" units="us">Timestamp</field> <field name="log_number" type="int16_t">Currently active log file, -1 if the logger is inactive</field> <field name="too_large_samples" type="int32_t">Number of dropped samples because too large</field> <field name="dropped_samples" type="int32_t">Number of dropped samples due to fifo full</field> @@ -368,7 +374,7 @@ </message> <message id="203" name="MAVLINK_STATS_TM"> <description>Status of the TMTCManager telemetry</description> - <field name="timestamp" type="uint64_t" units="ms">When was this logged </field> + <field name="timestamp" type="uint64_t" units="us">When was this logged </field> <field name="n_send_queue" type="uint16_t">Current len of the occupied portion of the queue</field> <field name="max_send_queue" type="uint16_t">Max occupied len of the queue </field> <field name="n_send_errors" type="uint16_t">Number of packet not sent correctly by the TMTC</field> @@ -385,7 +391,7 @@ <message id="204" name="TASK_STATS_TM"> <!-- At request we expect n messages as response --> <description>Statistics of the Task Scheduler</description> - <field name="timestamp" type="uint64_t" units="ms">When was this logged </field> + <field name="timestamp" type="uint64_t" units="us">When was this logged </field> <field name="task_id" type="uint8_t">Task ID</field> <field name="task_period" type="uint16_t" units="ms">Period of the task</field> <field name="task_min" type="float">Task min period</field> @@ -395,7 +401,7 @@ </message> <message id="205" name="ADA_TM"> <description>Apogee Detection Algorithm status telemetry</description> - <field name="timestamp" type="uint64_t" units="ms">When was this logged</field> + <field name="timestamp" type="uint64_t" units="us">When was this logged</field> <field name="state" type="uint8_t">ADA current state</field> <field name="kalman_x0" type="float">Kalman state variable 0 (pressure)</field> <field name="kalman_x1" type="float">Kalman state variable 1 (pressure velocity)</field> @@ -410,7 +416,7 @@ </message> <message id="206" name="NAS_TM"> <description>Navigation System status telemetry</description> - <field name="timestamp" type="uint64_t" units="ms">When was this logged</field> + <field name="timestamp" type="uint64_t" units="us">When was this logged</field> <field name="state" type="uint8_t">NAS current state</field> <field name="nas_n" type="float" units="deg">Navigation system estimated noth position</field> <field name="nas_e" type="float" units="deg">Navigation system estimated east position</field> @@ -433,7 +439,7 @@ <message id="207" name="CAN_TM"> <!-- TODO: UPDATE --> <description>Canbus driver status telemetry</description> - <field name="timestamp" type="uint64_t" units="ms">When was this logged</field> + <field name="timestamp" type="uint64_t" units="us">When was this logged</field> <field name="n_sent" type="uint16_t">Number of sent messages</field> <field name="n_rcv" type="uint16_t">Number of received messages</field> <field name="last_sent" type="uint8_t">Id of the last sent message</field> @@ -444,7 +450,7 @@ <message id="208" name="ROCKET_FLIGHT_TM"> <description>High Rate Telemetry</description> <!-- TODO: UPDATE AND DISCOVER EVENTUAL FORK BETWEEN LOW FR AND HIGH FR --> - <field name="timestamp" type="uint64_t" units="ms">Timestamp in milliseconds</field> + <field name="timestamp" type="uint64_t" units="us">Timestamp in milliseconds</field> <field name="ada_state" type="uint8_t">ADA Controller State</field> <field name="fmm_state" type="uint8_t">Flight Mode Manager State</field> <field name="dpl_state" type="uint8_t">Deployment Controller State</field> @@ -496,7 +502,7 @@ <message id="209" name="PAYLOAD_FLIGHT_TM"> <!-- TODO: COULD NEED SOMETHING ABOUT CONTROL ALGORITHM LIKE WING EFFICIENCY AND VELOCITIES DURING DESCENDING --> <description>High Rate Telemetry</description> - <field name="timestamp" type="uint64_t" units="ms">Timestamp in milliseconds</field> + <field name="timestamp" type="uint64_t" units="us">Timestamp in milliseconds</field> <field name="ada_state" type="uint8_t">ADA Controller State</field> <field name="fmm_state" type="uint8_t">Flight Mode Manager State</field> <field name="nas_state" type="uint8_t">Navigation System FSM State</field> @@ -541,14 +547,14 @@ </message> <message id="210" name="ROCKET_STATS_TM"> <description>Low Rate Telemetry</description> - <field name="liftoff_ts" type="uint64_t" units="ms">System clock at liftoff</field> - <field name="liftoff_max_acc_ts" type="uint64_t" units="ms">System clock at the maximum liftoff acceleration</field> + <field name="liftoff_ts" type="uint64_t" units="us">System clock at liftoff</field> + <field name="liftoff_max_acc_ts" type="uint64_t" units="us">System clock at the maximum liftoff acceleration</field> <field name="liftoff_max_acc" type="float" units="m/s2">Maximum liftoff acceleration</field> - <field name="max_z_speed_ts" type="uint64_t" units="ms">System clock at ADA max vertical speed</field> + <field name="max_z_speed_ts" type="uint64_t" units="us">System clock at ADA max vertical speed</field> <field name="max_z_speed" type="float" units="m/s">Max measured vertical speed - ADA</field> <field name="max_airspeed_pitot" type="float" units="m/s">Max speed read by the pitot tube</field> <field name="max_speed_altitude" type="float" units="m">Altitude at max speed</field> - <field name="apogee_ts" type="uint64_t" units="ms">System clock at apogee</field> + <field name="apogee_ts" type="uint64_t" units="us">System clock at apogee</field> <field name="apogee_lat" type="float" units="deg">Apogee latitude</field> <field name="apogee_lon" type="float" units="deg">Apogee longitude</field> <field name="static_min_pressure" type="float" units="Pa">Apogee pressure - Static ports</field> @@ -556,10 +562,10 @@ <field name="ada_min_pressure" type="float" units="Pa">Apogee pressure - ADA filtered</field> <field name="baro_max_altitude" type="float" units="m">Apogee altitude - Digital barometer</field> <field name="gps_max_altitude" type="float" units="m">Apogee altitude - GPS</field> - <field name="drogue_dpl_ts" type="uint64_t" units="ms">System clock at drouge deployment</field> + <field name="drogue_dpl_ts" type="uint64_t" units="us">System clock at drouge deployment</field> <field name="drogue_dpl_max_acc" type="float" units="m/s2">Max acceleration during drouge deployment</field> <field name="dpl_vane_max_pressure" type="float" units="Pa">Max pressure in the deployment bay during drogue deployment</field> - <field name="main_dpl_altitude_ts" type="uint64_t" units="ms">System clock at main chute deployment</field> + <field name="main_dpl_altitude_ts" type="uint64_t" units="us">System clock at main chute deployment</field> <field name="main_dpl_altitude" type="float" units="m">Altittude at main deployment (m.s.l)</field> <field name="main_dpl_zspeed" type="float" units="m/s">Vertical speed at main deployment (sensor z axis)</field> <field name="main_dpl_acc" type="float" units="m/s2">Max measured vertical acceleration (sensor z axis) after main parachute deployment</field> @@ -569,14 +575,14 @@ <message id="211" name="PAYLOAD_STATS_TM"> <description>Low Rate Telemetry</description> <!-- TODO: COULD NEED SOMETHING ABOUT CONTROL ALGORITHM LIKE WING EFFICIENCY AND VELOCITIES DURING DESCENDING --> - <field name="liftoff_ts" type="uint64_t" units="ms">System clock at liftoff</field> - <field name="liftoff_max_acc_ts" type="uint64_t" units="ms">System clock at the maximum liftoff acceleration</field> + <field name="liftoff_ts" type="uint64_t" units="us">System clock at liftoff</field> + <field name="liftoff_max_acc_ts" type="uint64_t" units="us">System clock at the maximum liftoff acceleration</field> <field name="liftoff_max_acc" type="float" units="m/s2">Maximum liftoff acceleration</field> - <field name="max_z_speed_ts" type="uint64_t" units="ms">System clock at ADA max vertical speed</field> + <field name="max_z_speed_ts" type="uint64_t" units="us">System clock at ADA max vertical speed</field> <field name="max_z_speed" type="float" units="m/s">Max measured vertical speed - ADA</field> <field name="max_airspeed_pitot" type="float" units="m/s">Max speed read by the pitot tube</field> <field name="max_speed_altitude" type="float" units="m">Altitude at max speed</field> - <field name="apogee_ts" type="uint64_t" units="ms">System clock at apogee</field> + <field name="apogee_ts" type="uint64_t" units="us">System clock at apogee</field> <field name="apogee_lat" type="float" units="deg">Apogee latitude</field> <field name="apogee_lon" type="float" units="deg">Apogee longitude</field> <field name="static_min_pressure" type="float" units="Pa">Apogee pressure - Static ports</field> @@ -584,7 +590,7 @@ <field name="ada_min_pressure" type="float" units="Pa">Apogee pressure - ADA filtered</field> <field name="baro_max_altitude" type="float" units="m">Apogee altitude - Digital barometer</field> <field name="gps_max_altitude" type="float" units="m">Apogee altitude - GPS</field> - <field name="drogue_dpl_ts" type="uint64_t" units="ms">System clock at drouge deployment</field> + <field name="drogue_dpl_ts" type="uint64_t" units="us">System clock at drouge deployment</field> <field name="drogue_dpl_max_acc" type="float" units="m/s2">Max acceleration during drouge deployment</field> <field name="cpu_load" type="float">CPU load in percentage</field> <field name="free_heap" type="uint32_t">Amount of available heap in memory</field> -- GitLab