mavlink_msg_debug_vect.h 5.91 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3
// MESSAGE DEBUG_VECT PACKING

#define MAVLINK_MSG_ID_DEBUG_VECT 251
lm's avatar
lm committed
4 5
#define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30
#define MAVLINK_MSG_251_LEN 30
James Goppert's avatar
James Goppert committed
6 7 8 9 10 11 12

typedef struct __mavlink_debug_vect_t 
{
	uint64_t usec; ///< Timestamp
	float x; ///< x
	float y; ///< y
	float z; ///< z
13
	char name[10]; ///< Name
James Goppert's avatar
James Goppert committed
14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32

} mavlink_debug_vect_t;
#define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10

/**
 * @brief Pack a debug_vect message
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 *
 * @param name Name
 * @param usec Timestamp
 * @param x x
 * @param y y
 * @param z z
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const char* name, uint64_t usec, float x, float y, float z)
{
lm's avatar
lm committed
33
	mavlink_debug_vect_t *p = (mavlink_debug_vect_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
34 35
	msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;

lm's avatar
lm committed
36 37 38 39 40
	memcpy(p->name, name, sizeof(p->name)); // char[10]:Name
	p->usec = usec; // uint64_t:Timestamp
	p->x = x; // float:x
	p->y = y; // float:y
	p->z = z; // float:z
James Goppert's avatar
James Goppert committed
41

lm's avatar
lm committed
42
	return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
James Goppert's avatar
James Goppert committed
43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59
}

/**
 * @brief Pack a debug_vect message
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param chan The MAVLink channel this message was sent over
 * @param msg The MAVLink message to compress the data into
 * @param name Name
 * @param usec Timestamp
 * @param x x
 * @param y y
 * @param z z
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const char* name, uint64_t usec, float x, float y, float z)
{
lm's avatar
lm committed
60
	mavlink_debug_vect_t *p = (mavlink_debug_vect_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
61 62
	msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;

lm's avatar
lm committed
63 64 65 66 67
	memcpy(p->name, name, sizeof(p->name)); // char[10]:Name
	p->usec = usec; // uint64_t:Timestamp
	p->x = x; // float:x
	p->y = y; // float:y
	p->z = z; // float:z
James Goppert's avatar
James Goppert committed
68

lm's avatar
lm committed
69
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
James Goppert's avatar
James Goppert committed
70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94
}

/**
 * @brief Encode a debug_vect 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_vect C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect)
{
	return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->usec, debug_vect->x, debug_vect->y, debug_vect->z);
}

/**
 * @brief Send a debug_vect message
 * @param chan MAVLink channel to send the message
 *
 * @param name Name
 * @param usec Timestamp
 * @param x x
 * @param y y
 * @param z z
 */
lm's avatar
lm committed
95 96


97
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
lm's avatar
lm committed
98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127
static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char* name, uint64_t usec, float x, float y, float z)
{
	mavlink_header_t hdr;
	mavlink_debug_vect_t payload;
	uint16_t checksum;
	mavlink_debug_vect_t *p = &payload;

	memcpy(p->name, name, sizeof(p->name)); // char[10]:Name
	p->usec = usec; // uint64_t:Timestamp
	p->x = x; // float:x
	p->y = y; // float:y
	p->z = z; // float:z

	hdr.STX = MAVLINK_STX;
	hdr.len = MAVLINK_MSG_ID_DEBUG_VECT_LEN;
	hdr.msgid = MAVLINK_MSG_ID_DEBUG_VECT;
	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 );

	crc_init(&checksum);
	checksum = crc_calculate_mem((uint8_t *)&hdr.len, &checksum, MAVLINK_CORE_HEADER_LEN);
	checksum = crc_calculate_mem((uint8_t *)&payload, &checksum, hdr.len );
	hdr.ck_a = (uint8_t)(checksum & 0xFF); ///< Low byte
	hdr.ck_b = (uint8_t)(checksum >> 8); ///< High byte

	mavlink_send_mem(chan, (uint8_t *)&payload, hdr.len);
	mavlink_send_mem(chan, (uint8_t *)&hdr.ck_a, MAVLINK_NUM_CHECKSUM_BYTES);
James Goppert's avatar
James Goppert committed
128 129 130 131 132 133 134 135 136 137
}

#endif
// MESSAGE DEBUG_VECT UNPACKING

/**
 * @brief Get field name from debug_vect message
 *
 * @return Name
 */
lm's avatar
lm committed
138
static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char* name)
James Goppert's avatar
James Goppert committed
139
{
lm's avatar
lm committed
140
	mavlink_debug_vect_t *p = (mavlink_debug_vect_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
141

lm's avatar
lm committed
142 143
	memcpy(name, p->name, sizeof(p->name));
	return sizeof(p->name);
James Goppert's avatar
James Goppert committed
144 145 146 147 148 149 150 151 152
}

/**
 * @brief Get field usec from debug_vect message
 *
 * @return Timestamp
 */
static inline uint64_t mavlink_msg_debug_vect_get_usec(const mavlink_message_t* msg)
{
lm's avatar
lm committed
153 154
	mavlink_debug_vect_t *p = (mavlink_debug_vect_t *)&msg->payload[0];
	return (uint64_t)(p->usec);
James Goppert's avatar
James Goppert committed
155 156 157 158 159 160 161 162 163
}

/**
 * @brief Get field x from debug_vect message
 *
 * @return x
 */
static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg)
{
lm's avatar
lm committed
164 165
	mavlink_debug_vect_t *p = (mavlink_debug_vect_t *)&msg->payload[0];
	return (float)(p->x);
James Goppert's avatar
James Goppert committed
166 167 168 169 170 171 172 173 174
}

/**
 * @brief Get field y from debug_vect message
 *
 * @return y
 */
static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg)
{
lm's avatar
lm committed
175 176
	mavlink_debug_vect_t *p = (mavlink_debug_vect_t *)&msg->payload[0];
	return (float)(p->y);
James Goppert's avatar
James Goppert committed
177 178 179 180 181 182 183 184 185
}

/**
 * @brief Get field z from debug_vect message
 *
 * @return z
 */
static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg)
{
lm's avatar
lm committed
186 187
	mavlink_debug_vect_t *p = (mavlink_debug_vect_t *)&msg->payload[0];
	return (float)(p->z);
James Goppert's avatar
James Goppert committed
188 189 190 191 192 193 194 195 196 197
}

/**
 * @brief Decode a debug_vect message into a struct
 *
 * @param msg The message to decode
 * @param debug_vect C-struct to decode the message contents into
 */
static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect)
{
lm's avatar
lm committed
198
	memcpy( debug_vect, msg->payload, sizeof(mavlink_debug_vect_t));
James Goppert's avatar
James Goppert committed
199
}