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) }, \ 50 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 90 mavlink_message_t* msg,
93 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 112 #if MAVLINK_CRC_EXTRA 156 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 160 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 167 #if MAVLINK_CRC_EXTRA 179 #if MAVLINK_CRC_EXTRA 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;
204 #if MAVLINK_CRC_EXTRA 216 #if MAVLINK_CRC_EXTRA 247 return _MAV_RETURN_uint64_t(msg, 0);
257 return _MAV_RETURN_float(msg, 8);
267 return _MAV_RETURN_float(msg, 12);
277 return _MAV_RETURN_float(msg, 16);
288 #if MAVLINK_NEED_BYTE_SWAP #define _mav_put_float(buf, wire_offset, b)
static 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 time_usec, float x, float y, float z)
Pack a debug_vect message on a channel.
#define MAVLINK_MSG_ID_DEBUG_VECT
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
#define _mav_put_uint64_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
#define _MAV_PAYLOAD(msg)
static float mavlink_msg_debug_vect_get_x(const mavlink_message_t *msg)
Get field x from debug_vect message.
struct __mavlink_debug_vect_t mavlink_debug_vect_t
static uint64_t mavlink_msg_debug_vect_get_time_usec(const mavlink_message_t *msg)
Get field time_usec from debug_vect message.
static uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t *msg, char *name)
Send a debug_vect message.
static 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)
Encode a debug_vect struct on a channel.
static float mavlink_msg_debug_vect_get_y(const mavlink_message_t *msg)
Get field y from debug_vect message.
static void mav_array_memcpy(void *dest, const void *src, size_t n)
static uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value, uint8_t array_length, uint8_t wire_offset)
static void mavlink_msg_debug_vect_decode(const mavlink_message_t *msg, mavlink_debug_vect_t *debug_vect)
Decode a debug_vect message into a struct.
static void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
#define MAVLINK_MSG_ID_DEBUG_VECT_LEN
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
static float mavlink_msg_debug_vect_get_z(const mavlink_message_t *msg)
Get field z from debug_vect message.
static 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)
Encode a debug_vect struct.
static uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const char *name, uint64_t time_usec, float x, float y, float z)
Pack a debug_vect message.
#define MAVLINK_MSG_ID_DEBUG_VECT_CRC