4#define MAVLINK_MSG_ID_DEBUG_VECT 250
7typedef struct __mavlink_debug_vect_t {
13}) mavlink_debug_vect_t;
15#define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30
16#define MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN 30
17#define MAVLINK_MSG_ID_250_LEN 30
18#define MAVLINK_MSG_ID_250_MIN_LEN 30
20#define MAVLINK_MSG_ID_DEBUG_VECT_CRC 49
21#define MAVLINK_MSG_ID_250_CRC 49
23#define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10
25#if MAVLINK_COMMAND_24BIT
26#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \
30 { { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \
31 { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \
32 { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \
33 { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \
34 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \
38#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \
41 { { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \
42 { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \
43 { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \
44 { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \
45 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \
63static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
64 const char *name, uint64_t time_usec,
float x,
float y,
float z)
66#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
67 char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN];
68 _mav_put_uint64_t(buf, 0, time_usec);
69 _mav_put_float(buf, 8, x);
70 _mav_put_float(buf, 12, y);
71 _mav_put_float(buf, 16, z);
72 _mav_put_char_array(buf, 20, name, 10);
73 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
75 mavlink_debug_vect_t packet;
76 packet.time_usec = time_usec;
80 mav_array_memcpy(packet.name, name,
sizeof(
char)*10);
81 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
84 msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
85 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
101static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
102 mavlink_message_t* msg,
103 const char *name,uint64_t time_usec,
float x,
float y,
float z)
105#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
106 char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN];
107 _mav_put_uint64_t(buf, 0, time_usec);
108 _mav_put_float(buf, 8, x);
109 _mav_put_float(buf, 12, y);
110 _mav_put_float(buf, 16, z);
111 _mav_put_char_array(buf, 20, name, 10);
112 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
114 mavlink_debug_vect_t packet;
115 packet.time_usec = time_usec;
119 mav_array_memcpy(packet.name, name,
sizeof(
char)*10);
120 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
123 msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
124 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
135static 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)
137 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);
149static inline uint16_t mavlink_msg_debug_vect_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_debug_vect_t* debug_vect)
151 return mavlink_msg_debug_vect_pack_chan(system_id, component_id, chan, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z);
164#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
166static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan,
const char *name, uint64_t time_usec,
float x,
float y,
float z)
168#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
169 char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN];
170 _mav_put_uint64_t(buf, 0, time_usec);
171 _mav_put_float(buf, 8, x);
172 _mav_put_float(buf, 12, y);
173 _mav_put_float(buf, 16, z);
174 _mav_put_char_array(buf, 20, name, 10);
175 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
177 mavlink_debug_vect_t packet;
178 packet.time_usec = time_usec;
182 mav_array_memcpy(packet.name, name,
sizeof(
char)*10);
183 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (
const char *)&packet, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
192static inline void mavlink_msg_debug_vect_send_struct(mavlink_channel_t chan,
const mavlink_debug_vect_t* debug_vect)
194#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
195 mavlink_msg_debug_vect_send(chan, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z);
197 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (
const char *)debug_vect, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
201#if MAVLINK_MSG_ID_DEBUG_VECT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
209static inline void mavlink_msg_debug_vect_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,
const char *name, uint64_t time_usec,
float x,
float y,
float z)
211#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
212 char *buf = (
char *)msgbuf;
213 _mav_put_uint64_t(buf, 0, time_usec);
214 _mav_put_float(buf, 8, x);
215 _mav_put_float(buf, 12, y);
216 _mav_put_float(buf, 16, z);
217 _mav_put_char_array(buf, 20, name, 10);
218 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
220 mavlink_debug_vect_t *packet = (mavlink_debug_vect_t *)msgbuf;
221 packet->time_usec = time_usec;
225 mav_array_memcpy(packet->name, name,
sizeof(
char)*10);
226 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (
const char *)packet, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
241static inline uint16_t mavlink_msg_debug_vect_get_name(
const mavlink_message_t* msg,
char *name)
243 return _MAV_RETURN_char_array(msg, name, 10, 20);
251static inline uint64_t mavlink_msg_debug_vect_get_time_usec(
const mavlink_message_t* msg)
253 return _MAV_RETURN_uint64_t(msg, 0);
261static inline float mavlink_msg_debug_vect_get_x(
const mavlink_message_t* msg)
263 return _MAV_RETURN_float(msg, 8);
271static inline float mavlink_msg_debug_vect_get_y(
const mavlink_message_t* msg)
273 return _MAV_RETURN_float(msg, 12);
281static inline float mavlink_msg_debug_vect_get_z(
const mavlink_message_t* msg)
283 return _MAV_RETURN_float(msg, 16);
292static inline void mavlink_msg_debug_vect_decode(
const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect)
294#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
295 debug_vect->time_usec = mavlink_msg_debug_vect_get_time_usec(msg);
296 debug_vect->x = mavlink_msg_debug_vect_get_x(msg);
297 debug_vect->y = mavlink_msg_debug_vect_get_y(msg);
298 debug_vect->z = mavlink_msg_debug_vect_get_z(msg);
299 mavlink_msg_debug_vect_get_name(msg, debug_vect->name);
301 uint8_t len = msg->len < MAVLINK_MSG_ID_DEBUG_VECT_LEN? msg->len : MAVLINK_MSG_ID_DEBUG_VECT_LEN;
302 memset(debug_vect, 0, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
303 memcpy(debug_vect, _MAV_PAYLOAD(msg), len);