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

3
#define MAVLINK_MSG_ID_DEBUG_VECT 250
James Goppert's avatar
James Goppert committed
4

lm's avatar
lm committed
5
typedef struct __mavlink_debug_vect_t
James Goppert's avatar
James Goppert committed
6
{
7
 uint64_t time_usec; ///< Timestamp
lm's avatar
lm committed
8 9 10 11
 float x; ///< x
 float y; ///< y
 float z; ///< z
 char name[10]; ///< Name
James Goppert's avatar
James Goppert committed
12
} mavlink_debug_vect_t;
lm's avatar
lm committed
13 14

#define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30
15
#define MAVLINK_MSG_ID_250_LEN 30
lm's avatar
lm committed
16

James Goppert's avatar
James Goppert committed
17 18
#define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10

lm's avatar
lm committed
19 20 21
#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \
	"DEBUG_VECT", \
	5, \
lm's avatar
lm committed
22 23 24 25 26
	{  { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \
         { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \
         { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \
         { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \
         { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \
lm's avatar
lm committed
27 28 29 30
         } \
}


James Goppert's avatar
James Goppert committed
31 32 33 34 35 36 37
/**
 * @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
38
 * @param time_usec Timestamp
James Goppert's avatar
James Goppert committed
39 40 41 42 43
 * @param x x
 * @param y y
 * @param z z
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
44
static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
45
						       const char *name, uint64_t time_usec, float x, float y, float z)
James Goppert's avatar
James Goppert committed
46
{
LM's avatar
LM committed
47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[30];
	_mav_put_uint64_t(buf, 0, time_usec);
	_mav_put_float(buf, 8, x);
	_mav_put_float(buf, 12, y);
	_mav_put_float(buf, 16, z);
	_mav_put_char_array(buf, 20, name, 10);
        memcpy(_MAV_PAYLOAD(msg), buf, 30);
#else
	mavlink_debug_vect_t packet;
	packet.time_usec = time_usec;
	packet.x = x;
	packet.y = y;
	packet.z = z;
	memcpy(packet.name, name, sizeof(char)*10);
        memcpy(_MAV_PAYLOAD(msg), &packet, 30);
#endif
James Goppert's avatar
James Goppert committed
64

LM's avatar
LM committed
65
	msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
66
	return mavlink_finalize_message(msg, system_id, component_id, 30, 49);
James Goppert's avatar
James Goppert committed
67 68 69
}

/**
lm's avatar
lm committed
70
 * @brief Pack a debug_vect message on a channel
James Goppert's avatar
James Goppert committed
71 72 73 74 75
 * @param system_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
76
 * @param time_usec Timestamp
James Goppert's avatar
James Goppert committed
77 78 79 80 81
 * @param x x
 * @param y y
 * @param z z
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
82 83
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,
84
						           const char *name,uint64_t time_usec,float x,float y,float z)
James Goppert's avatar
James Goppert committed
85
{
LM's avatar
LM committed
86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[30];
	_mav_put_uint64_t(buf, 0, time_usec);
	_mav_put_float(buf, 8, x);
	_mav_put_float(buf, 12, y);
	_mav_put_float(buf, 16, z);
	_mav_put_char_array(buf, 20, name, 10);
        memcpy(_MAV_PAYLOAD(msg), buf, 30);
#else
	mavlink_debug_vect_t packet;
	packet.time_usec = time_usec;
	packet.x = x;
	packet.y = y;
	packet.z = z;
	memcpy(packet.name, name, sizeof(char)*10);
        memcpy(_MAV_PAYLOAD(msg), &packet, 30);
#endif
James Goppert's avatar
James Goppert committed
103

LM's avatar
LM committed
104
	msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
105
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 30, 49);
James Goppert's avatar
James Goppert committed
106 107 108 109 110 111 112 113 114 115 116 117
}

/**
 * @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)
{
118
	return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z);
James Goppert's avatar
James Goppert committed
119 120 121 122 123 124 125
}

/**
 * @brief Send a debug_vect message
 * @param chan MAVLink channel to send the message
 *
 * @param name Name
126
 * @param time_usec Timestamp
James Goppert's avatar
James Goppert committed
127 128 129 130
 * @param x x
 * @param y y
 * @param z z
 */
lm's avatar
lm committed
131 132
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

133
static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char *name, uint64_t time_usec, float x, float y, float z)
lm's avatar
lm committed
134
{
LM's avatar
LM committed
135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[30];
	_mav_put_uint64_t(buf, 0, time_usec);
	_mav_put_float(buf, 8, x);
	_mav_put_float(buf, 12, y);
	_mav_put_float(buf, 16, z);
	_mav_put_char_array(buf, 20, name, 10);
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, 30, 49);
#else
	mavlink_debug_vect_t packet;
	packet.time_usec = time_usec;
	packet.x = x;
	packet.y = y;
	packet.z = z;
	memcpy(packet.name, name, sizeof(char)*10);
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, 30, 49);
#endif
James Goppert's avatar
James Goppert committed
152 153 154
}

#endif
lm's avatar
lm committed
155

James Goppert's avatar
James Goppert committed
156 157
// MESSAGE DEBUG_VECT UNPACKING

lm's avatar
lm committed
158

James Goppert's avatar
James Goppert committed
159 160 161 162 163
/**
 * @brief Get field name from debug_vect message
 *
 * @return Name
 */
lm's avatar
lm committed
164
static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char *name)
James Goppert's avatar
James Goppert committed
165
{
LM's avatar
LM committed
166
	return _MAV_RETURN_char_array(msg, name, 10,  20);
James Goppert's avatar
James Goppert committed
167 168 169
}

/**
170
 * @brief Get field time_usec from debug_vect message
James Goppert's avatar
James Goppert committed
171 172 173
 *
 * @return Timestamp
 */
174
static inline uint64_t mavlink_msg_debug_vect_get_time_usec(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
175
{
LM's avatar
LM committed
176
	return _MAV_RETURN_uint64_t(msg,  0);
James Goppert's avatar
James Goppert committed
177 178 179 180 181 182 183 184 185
}

/**
 * @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
186
	return _MAV_RETURN_float(msg,  8);
James Goppert's avatar
James Goppert committed
187 188 189 190 191 192 193 194 195
}

/**
 * @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
196
	return _MAV_RETURN_float(msg,  12);
James Goppert's avatar
James Goppert committed
197 198 199 200 201 202 203 204 205
}

/**
 * @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
206
	return _MAV_RETURN_float(msg,  16);
James Goppert's avatar
James Goppert committed
207 208 209 210 211 212 213 214 215 216
}

/**
 * @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
217
#if MAVLINK_NEED_BYTE_SWAP
218
	debug_vect->time_usec = mavlink_msg_debug_vect_get_time_usec(msg);
lm's avatar
lm committed
219 220 221 222 223
	debug_vect->x = mavlink_msg_debug_vect_get_x(msg);
	debug_vect->y = mavlink_msg_debug_vect_get_y(msg);
	debug_vect->z = mavlink_msg_debug_vect_get_z(msg);
	mavlink_msg_debug_vect_get_name(msg, debug_vect->name);
#else
LM's avatar
LM committed
224
	memcpy(debug_vect, _MAV_PAYLOAD(msg), 30);
lm's avatar
lm committed
225
#endif
James Goppert's avatar
James Goppert committed
226
}