mavlink_msg_debug.h 4.41 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3
// MESSAGE DEBUG PACKING

#define MAVLINK_MSG_ID_DEBUG 255
lm's avatar
lm committed
4 5
#define MAVLINK_MSG_ID_DEBUG_LEN 5
#define MAVLINK_MSG_255_LEN 5
lm's avatar
lm committed
6 7
#define MAVLINK_MSG_ID_DEBUG_KEY 0x54
#define MAVLINK_MSG_255_KEY 0x54
James Goppert's avatar
James Goppert committed
8 9 10

typedef struct __mavlink_debug_t 
{
lm's avatar
lm committed
11 12
	float value;	///< DEBUG value
	uint8_t ind;	///< index of debug variable
James Goppert's avatar
James Goppert committed
13 14 15 16 17 18 19 20 21 22 23 24 25 26 27

} mavlink_debug_t;

/**
 * @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 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, uint8_t ind, float value)
{
lm's avatar
lm committed
28
	mavlink_debug_t *p = (mavlink_debug_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
29 30
	msg->msgid = MAVLINK_MSG_ID_DEBUG;

lm's avatar
lm committed
31 32
	p->ind = ind;	// uint8_t:index of debug variable
	p->value = value;	// float:DEBUG value
James Goppert's avatar
James Goppert committed
33

lm's avatar
lm committed
34
	return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_LEN);
James Goppert's avatar
James Goppert committed
35 36 37 38 39 40 41 42 43 44 45 46 47 48
}

/**
 * @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 chan The MAVLink channel this message was sent over
 * @param msg The MAVLink message to compress the data into
 * @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, uint8_t ind, float value)
{
lm's avatar
lm committed
49
	mavlink_debug_t *p = (mavlink_debug_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
50 51
	msg->msgid = MAVLINK_MSG_ID_DEBUG;

lm's avatar
lm committed
52 53
	p->ind = ind;	// uint8_t:index of debug variable
	p->value = value;	// float:DEBUG value
James Goppert's avatar
James Goppert committed
54

lm's avatar
lm committed
55
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_LEN);
James Goppert's avatar
James Goppert committed
56 57 58 59 60 61 62 63 64 65 66 67 68 69 70
}

/**
 * @brief Encode a debug struct into a message
 *
 * @param system_id ID of this 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->ind, debug->value);
}

lm's avatar
lm committed
71 72

#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
James Goppert's avatar
James Goppert committed
73 74 75 76 77 78 79
/**
 * @brief Send a debug message
 * @param chan MAVLink channel to send the message
 *
 * @param ind index of debug variable
 * @param value DEBUG value
 */
lm's avatar
lm committed
80 81 82 83 84
static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint8_t ind, float value)
{
	mavlink_header_t hdr;
	mavlink_debug_t payload;

lm's avatar
lm committed
85 86 87
	MAVLINK_BUFFER_CHECK_START( chan, MAVLINK_MSG_ID_DEBUG_LEN )
	payload.ind = ind;	// uint8_t:index of debug variable
	payload.value = value;	// float:DEBUG value
lm's avatar
lm committed
88 89 90 91 92 93 94 95 96 97

	hdr.STX = MAVLINK_STX;
	hdr.len = MAVLINK_MSG_ID_DEBUG_LEN;
	hdr.msgid = MAVLINK_MSG_ID_DEBUG;
	hdr.sysid = mavlink_system.sysid;
	hdr.compid = mavlink_system.compid;
	hdr.seq = mavlink_get_channel_status(chan)->current_tx_seq;
	mavlink_get_channel_status(chan)->current_tx_seq = hdr.seq + 1;
	mavlink_send_mem(chan, (uint8_t *)&hdr.STX, MAVLINK_NUM_HEADER_BYTES );

lm's avatar
lm committed
98 99 100 101 102 103
	crc_init(&hdr.ck);
	crc_calculate_mem((uint8_t *)&hdr.len, &hdr.ck, MAVLINK_CORE_HEADER_LEN);
	crc_calculate_mem((uint8_t *)&payload, &hdr.ck, hdr.len );
	crc_accumulate( 0x54, &hdr.ck); /// include key in X25 checksum
	mavlink_send_mem(chan, (uint8_t *)&hdr.ck, MAVLINK_NUM_CHECKSUM_BYTES);
	MAVLINK_BUFFER_CHECK_END
James Goppert's avatar
James Goppert committed
104 105 106 107 108 109 110 111 112 113 114 115
}

#endif
// MESSAGE DEBUG UNPACKING

/**
 * @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)
{
lm's avatar
lm committed
116 117
	mavlink_debug_t *p = (mavlink_debug_t *)&msg->payload[0];
	return (uint8_t)(p->ind);
James Goppert's avatar
James Goppert committed
118 119 120 121 122 123 124 125 126
}

/**
 * @brief Get field value from debug message
 *
 * @return DEBUG value
 */
static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg)
{
lm's avatar
lm committed
127 128
	mavlink_debug_t *p = (mavlink_debug_t *)&msg->payload[0];
	return (float)(p->value);
James Goppert's avatar
James Goppert committed
129 130 131 132 133 134 135 136 137 138
}

/**
 * @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)
{
lm's avatar
lm committed
139
	memcpy( debug, msg->payload, sizeof(mavlink_debug_t));
James Goppert's avatar
James Goppert committed
140
}