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

#define MAVLINK_MSG_ID_DEBUG_VECT 251

lm's avatar
lm committed
5
typedef struct __mavlink_debug_vect_t
James Goppert's avatar
James Goppert committed
6
{
lm's avatar
lm committed
7 8 9 10 11
 uint64_t usec; ///< Timestamp
 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 15 16

#define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30
#define MAVLINK_MSG_ID_251_LEN 30

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 22 23 24 25 26 27 28 29 30
#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \
	"DEBUG_VECT", \
	5, \
	{  { "usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, usec) }, \
         { "x", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \
         { "y", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \
         { "z", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \
         { "name", MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \
         } \
}


James Goppert's avatar
James Goppert committed
31 32 33 34 35 36 37 38 39 40 41 42 43
/**
 * @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)
 */
lm's avatar
lm committed
44 45
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)
James Goppert's avatar
James Goppert committed
46 47 48
{
	msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;

lm's avatar
lm committed
49 50 51 52 53
	put_uint64_t_by_index(msg, 0, usec); // Timestamp
	put_float_by_index(msg, 8, x); // x
	put_float_by_index(msg, 12, y); // y
	put_float_by_index(msg, 16, z); // z
	put_char_array_by_index(msg, 20, name, 10); // Name
James Goppert's avatar
James Goppert committed
54

lm's avatar
lm committed
55
	return mavlink_finalize_message(msg, system_id, component_id, 30, 15);
James Goppert's avatar
James Goppert committed
56 57 58
}

/**
lm's avatar
lm committed
59
 * @brief Pack a debug_vect message on a channel
James Goppert's avatar
James Goppert committed
60 61 62 63 64 65 66 67 68 69 70
 * @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)
 */
lm's avatar
lm committed
71 72 73
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)
James Goppert's avatar
James Goppert committed
74 75 76
{
	msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;

lm's avatar
lm committed
77 78 79 80 81
	put_uint64_t_by_index(msg, 0, usec); // Timestamp
	put_float_by_index(msg, 8, x); // x
	put_float_by_index(msg, 12, y); // y
	put_float_by_index(msg, 16, z); // z
	put_char_array_by_index(msg, 20, name, 10); // Name
James Goppert's avatar
James Goppert committed
82

lm's avatar
lm committed
83
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 30, 15);
James Goppert's avatar
James Goppert committed
84 85
}

lm's avatar
lm committed
86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

/**
 * @brief Pack a debug_vect message on a channel and send
 * @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
 */
static inline void mavlink_msg_debug_vect_pack_chan_send(mavlink_channel_t chan,
							   mavlink_message_t* msg,
						           const char *name,uint64_t usec,float x,float y,float z)
{
	msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;

	put_uint64_t_by_index(msg, 0, usec); // Timestamp
	put_float_by_index(msg, 8, x); // x
	put_float_by_index(msg, 12, y); // y
	put_float_by_index(msg, 16, z); // z
	put_char_array_by_index(msg, 20, name, 10); // Name

	mavlink_finalize_message_chan_send(msg, chan, 30, 15);
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS


James Goppert's avatar
James Goppert committed
115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137
/**
 * @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
138 139 140
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char *name, uint64_t usec, float x, float y, float z)
lm's avatar
lm committed
141
{
lm's avatar
lm committed
142 143
	MAVLINK_ALIGNED_MESSAGE(msg, 30);
	mavlink_msg_debug_vect_pack_chan_send(chan, msg, name, usec, x, y, z);
James Goppert's avatar
James Goppert committed
144 145 146
}

#endif
lm's avatar
lm committed
147

James Goppert's avatar
James Goppert committed
148 149
// MESSAGE DEBUG_VECT UNPACKING

lm's avatar
lm committed
150

James Goppert's avatar
James Goppert committed
151 152 153 154 155
/**
 * @brief Get field name from debug_vect message
 *
 * @return Name
 */
lm's avatar
lm committed
156
static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char *name)
James Goppert's avatar
James Goppert committed
157
{
lm's avatar
lm committed
158
	return MAVLINK_MSG_RETURN_char_array(msg, name, 10,  20);
James Goppert's avatar
James Goppert committed
159 160 161 162 163 164 165 166 167
}

/**
 * @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
168
	return MAVLINK_MSG_RETURN_uint64_t(msg,  0);
James Goppert's avatar
James Goppert committed
169 170 171 172 173 174 175 176 177
}

/**
 * @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
178
	return MAVLINK_MSG_RETURN_float(msg,  8);
James Goppert's avatar
James Goppert committed
179 180 181 182 183 184 185 186 187
}

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

/**
 * @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
198
	return MAVLINK_MSG_RETURN_float(msg,  16);
James Goppert's avatar
James Goppert committed
199 200 201 202 203 204 205 206 207 208
}

/**
 * @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
209 210 211 212 213 214 215 216 217
#if MAVLINK_NEED_BYTE_SWAP
	debug_vect->usec = mavlink_msg_debug_vect_get_usec(msg);
	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
	memcpy(debug_vect, MAVLINK_PAYLOAD(msg), 30);
#endif
James Goppert's avatar
James Goppert committed
218
}