3 #define MAVLINK_MSG_ID_DEBUG_VECT 250
14 #define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30
15 #define MAVLINK_MSG_ID_250_LEN 30
17 #define MAVLINK_MSG_ID_DEBUG_VECT_CRC 49
18 #define MAVLINK_MSG_ID_250_CRC 49
20 #define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10
22 #define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \
25 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \
26 { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \
27 { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \
28 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \
29 { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \
47 static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
48 const char *name, uint64_t time_usec,
float x,
float y,
float z)
50 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
51 char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN];
52 _mav_put_uint64_t(buf, 0, time_usec);
53 _mav_put_float(buf, 8, x);
54 _mav_put_float(buf, 12, y);
55 _mav_put_float(buf, 16, z);
56 _mav_put_char_array(buf, 20, name, 10);
57 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
64 mav_array_memcpy(packet.
name, name,
sizeof(
char)*10);
65 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
68 msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
70 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
72 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
89 static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
90 mavlink_message_t* msg,
91 const char *name,uint64_t time_usec,
float x,
float y,
float z)
93 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
94 char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN];
95 _mav_put_uint64_t(buf, 0, time_usec);
96 _mav_put_float(buf, 8, x);
97 _mav_put_float(buf, 12, y);
98 _mav_put_float(buf, 16, z);
99 _mav_put_char_array(buf, 20, name, 10);
100 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
107 mav_array_memcpy(packet.
name, name,
sizeof(
char)*10);
108 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
111 msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
112 #if MAVLINK_CRC_EXTRA
113 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
115 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
127 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)
129 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);
141 static 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)
143 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);
156 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
158 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)
160 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
161 char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN];
162 _mav_put_uint64_t(buf, 0, time_usec);
163 _mav_put_float(buf, 8, x);
164 _mav_put_float(buf, 12, y);
165 _mav_put_float(buf, 16, z);
166 _mav_put_char_array(buf, 20, name, 10);
167 #if MAVLINK_CRC_EXTRA
168 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
170 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
178 mav_array_memcpy(packet.
name, name,
sizeof(
char)*10);
179 #if MAVLINK_CRC_EXTRA
180 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (
const char *)&packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
182 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (
const char *)&packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
187 #if MAVLINK_MSG_ID_DEBUG_VECT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
195 static 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)
197 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
198 char *buf = (
char *)msgbuf;
199 _mav_put_uint64_t(buf, 0, time_usec);
200 _mav_put_float(buf, 8, x);
201 _mav_put_float(buf, 12, y);
202 _mav_put_float(buf, 16, z);
203 _mav_put_char_array(buf, 20, name, 10);
204 #if MAVLINK_CRC_EXTRA
205 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
207 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
215 mav_array_memcpy(packet->
name, name,
sizeof(
char)*10);
216 #if MAVLINK_CRC_EXTRA
217 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (
const char *)packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
219 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (
const char *)packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
235 static inline uint16_t mavlink_msg_debug_vect_get_name(
const mavlink_message_t* msg,
char *name)
237 return _MAV_RETURN_char_array(msg, name, 10, 20);
245 static inline uint64_t mavlink_msg_debug_vect_get_time_usec(
const mavlink_message_t* msg)
247 return _MAV_RETURN_uint64_t(msg, 0);
255 static inline float mavlink_msg_debug_vect_get_x(
const mavlink_message_t* msg)
257 return _MAV_RETURN_float(msg, 8);
265 static inline float mavlink_msg_debug_vect_get_y(
const mavlink_message_t* msg)
267 return _MAV_RETURN_float(msg, 12);
275 static inline float mavlink_msg_debug_vect_get_z(
const mavlink_message_t* msg)
277 return _MAV_RETURN_float(msg, 16);
286 static inline void mavlink_msg_debug_vect_decode(
const mavlink_message_t* msg,
mavlink_debug_vect_t* debug_vect)
288 #if MAVLINK_NEED_BYTE_SWAP
289 debug_vect->
time_usec = mavlink_msg_debug_vect_get_time_usec(msg);
290 debug_vect->
x = mavlink_msg_debug_vect_get_x(msg);
291 debug_vect->
y = mavlink_msg_debug_vect_get_y(msg);
292 debug_vect->
z = mavlink_msg_debug_vect_get_z(msg);
293 mavlink_msg_debug_vect_get_name(msg, debug_vect->
name);
295 memcpy(debug_vect, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DEBUG_VECT_LEN);
float y
y
Definition: mavlink_msg_debug_vect.h:9
char name[10]
Name.
Definition: mavlink_msg_debug_vect.h:11
Definition: mavlink_msg_debug_vect.h:5
uint64_t time_usec
Timestamp.
Definition: mavlink_msg_debug_vect.h:7
float x
x
Definition: mavlink_msg_debug_vect.h:8
float z
z
Definition: mavlink_msg_debug_vect.h:10