123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316 |
- #pragma once
- // MESSAGE DEBUG PACKING
- #define MAVLINK_MSG_ID_DEBUG 254
- typedef struct __mavlink_debug_t {
- uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
- float value; /*< DEBUG value*/
- uint8_t ind; /*< index of debug variable*/
- } mavlink_debug_t;
- #define MAVLINK_MSG_ID_DEBUG_LEN 9
- #define MAVLINK_MSG_ID_DEBUG_MIN_LEN 9
- #define MAVLINK_MSG_ID_254_LEN 9
- #define MAVLINK_MSG_ID_254_MIN_LEN 9
- #define MAVLINK_MSG_ID_DEBUG_CRC 46
- #define MAVLINK_MSG_ID_254_CRC 46
- #if MAVLINK_COMMAND_24BIT
- #define MAVLINK_MESSAGE_INFO_DEBUG { \
- 254, \
- "DEBUG", \
- 3, \
- { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_debug_t, time_boot_ms) }, \
- { "ind", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_debug_t, ind) }, \
- { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \
- } \
- }
- #else
- #define MAVLINK_MESSAGE_INFO_DEBUG { \
- "DEBUG", \
- 3, \
- { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_debug_t, time_boot_ms) }, \
- { "ind", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_debug_t, ind) }, \
- { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \
- } \
- }
- #endif
- /**
- * @brief Pack a debug message
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param msg The MAVLink message to compress the data into
- *
- * @param time_boot_ms [ms] Timestamp (time since system boot).
- * @param ind index of debug variable
- * @param value DEBUG value
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint32_t time_boot_ms, uint8_t ind, float value)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_DEBUG_LEN];
- _mav_put_uint32_t(buf, 0, time_boot_ms);
- _mav_put_float(buf, 4, value);
- _mav_put_uint8_t(buf, 8, ind);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_LEN);
- #else
- mavlink_debug_t packet;
- packet.time_boot_ms = time_boot_ms;
- packet.value = value;
- packet.ind = ind;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_DEBUG;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
- }
- /**
- * @brief Pack a debug message
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param status MAVLink status structure
- * @param msg The MAVLink message to compress the data into
- *
- * @param time_boot_ms [ms] Timestamp (time since system boot).
- * @param ind index of debug variable
- * @param value DEBUG value
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_debug_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
- uint32_t time_boot_ms, uint8_t ind, float value)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_DEBUG_LEN];
- _mav_put_uint32_t(buf, 0, time_boot_ms);
- _mav_put_float(buf, 4, value);
- _mav_put_uint8_t(buf, 8, ind);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_LEN);
- #else
- mavlink_debug_t packet;
- packet.time_boot_ms = time_boot_ms;
- packet.value = value;
- packet.ind = ind;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_DEBUG;
- #if MAVLINK_CRC_EXTRA
- return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
- #else
- return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN);
- #endif
- }
- /**
- * @brief Pack a debug message on a channel
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message will be sent over
- * @param msg The MAVLink message to compress the data into
- * @param time_boot_ms [ms] Timestamp (time since system boot).
- * @param ind index of debug variable
- * @param value DEBUG value
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint32_t time_boot_ms,uint8_t ind,float value)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_DEBUG_LEN];
- _mav_put_uint32_t(buf, 0, time_boot_ms);
- _mav_put_float(buf, 4, value);
- _mav_put_uint8_t(buf, 8, ind);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_LEN);
- #else
- mavlink_debug_t packet;
- packet.time_boot_ms = time_boot_ms;
- packet.value = value;
- packet.ind = ind;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_DEBUG;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
- }
- /**
- * @brief Encode a debug struct
- *
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param msg The MAVLink message to compress the data into
- * @param debug C-struct to read the message contents from
- */
- static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_t* debug)
- {
- return mavlink_msg_debug_pack(system_id, component_id, msg, debug->time_boot_ms, debug->ind, debug->value);
- }
- /**
- * @brief Encode a debug struct on a channel
- *
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message will be sent over
- * @param msg The MAVLink message to compress the data into
- * @param debug C-struct to read the message contents from
- */
- static inline uint16_t mavlink_msg_debug_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_t* debug)
- {
- return mavlink_msg_debug_pack_chan(system_id, component_id, chan, msg, debug->time_boot_ms, debug->ind, debug->value);
- }
- /**
- * @brief Encode a debug struct with provided status structure
- *
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param status MAVLink status structure
- * @param msg The MAVLink message to compress the data into
- * @param debug C-struct to read the message contents from
- */
- static inline uint16_t mavlink_msg_debug_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_debug_t* debug)
- {
- return mavlink_msg_debug_pack_status(system_id, component_id, _status, msg, debug->time_boot_ms, debug->ind, debug->value);
- }
- /**
- * @brief Send a debug message
- * @param chan MAVLink channel to send the message
- *
- * @param time_boot_ms [ms] Timestamp (time since system boot).
- * @param ind index of debug variable
- * @param value DEBUG value
- */
- #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
- static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_DEBUG_LEN];
- _mav_put_uint32_t(buf, 0, time_boot_ms);
- _mav_put_float(buf, 4, value);
- _mav_put_uint8_t(buf, 8, ind);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
- #else
- mavlink_debug_t packet;
- packet.time_boot_ms = time_boot_ms;
- packet.value = value;
- packet.ind = ind;
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
- #endif
- }
- /**
- * @brief Send a debug message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
- static inline void mavlink_msg_debug_send_struct(mavlink_channel_t chan, const mavlink_debug_t* debug)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_debug_send(chan, debug->time_boot_ms, debug->ind, debug->value);
- #else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)debug, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
- #endif
- }
- #if MAVLINK_MSG_ID_DEBUG_LEN <= MAVLINK_MAX_PAYLOAD_LEN
- /*
- This variant of _send() can be used to save stack space by re-using
- memory from the receive buffer. The caller provides a
- mavlink_message_t which is the size of a full mavlink message. This
- is usually the receive buffer for the channel, and allows a reply to an
- incoming message with minimum stack space usage.
- */
- static inline void mavlink_msg_debug_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint32_t(buf, 0, time_boot_ms);
- _mav_put_float(buf, 4, value);
- _mav_put_uint8_t(buf, 8, ind);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
- #else
- mavlink_debug_t *packet = (mavlink_debug_t *)msgbuf;
- packet->time_boot_ms = time_boot_ms;
- packet->value = value;
- packet->ind = ind;
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)packet, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
- #endif
- }
- #endif
- #endif
- // MESSAGE DEBUG UNPACKING
- /**
- * @brief Get field time_boot_ms from debug message
- *
- * @return [ms] Timestamp (time since system boot).
- */
- static inline uint32_t mavlink_msg_debug_get_time_boot_ms(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint32_t(msg, 0);
- }
- /**
- * @brief Get field ind from debug message
- *
- * @return index of debug variable
- */
- static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint8_t(msg, 8);
- }
- /**
- * @brief Get field value from debug message
- *
- * @return DEBUG value
- */
- static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 4);
- }
- /**
- * @brief Decode a debug message into a struct
- *
- * @param msg The message to decode
- * @param debug C-struct to decode the message contents into
- */
- static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlink_debug_t* debug)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- debug->time_boot_ms = mavlink_msg_debug_get_time_boot_ms(msg);
- debug->value = mavlink_msg_debug_get_value(msg);
- debug->ind = mavlink_msg_debug_get_ind(msg);
- #else
- uint8_t len = msg->len < MAVLINK_MSG_ID_DEBUG_LEN? msg->len : MAVLINK_MSG_ID_DEBUG_LEN;
- memset(debug, 0, MAVLINK_MSG_ID_DEBUG_LEN);
- memcpy(debug, _MAV_PAYLOAD(msg), len);
- #endif
- }
|