3 #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 103 13 #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 20 14 #define MAVLINK_MSG_ID_103_LEN 20 16 #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC 208 17 #define MAVLINK_MSG_ID_103_CRC 208 21 #define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE { \ 22 "VISION_SPEED_ESTIMATE", \ 24 { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_speed_estimate_t, usec) }, \ 25 { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_speed_estimate_t, x) }, \ 26 { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_speed_estimate_t, y) }, \ 27 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_speed_estimate_t, z) }, \ 45 uint64_t
usec,
float x,
float y,
float z)
47 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 86 mavlink_message_t* msg,
87 uint64_t
usec,
float x,
float y,
float z)
89 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 108 #if MAVLINK_CRC_EXTRA 151 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 153 static inline void mavlink_msg_vision_speed_estimate_send(
mavlink_channel_t chan, uint64_t
usec,
float x,
float y,
float z)
155 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 162 #if MAVLINK_CRC_EXTRA 174 #if MAVLINK_CRC_EXTRA 182 #if MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN 190 static inline void mavlink_msg_vision_speed_estimate_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint64_t
usec,
float x,
float y,
float z)
192 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 193 char *buf = (
char *)msgbuf;
199 #if MAVLINK_CRC_EXTRA 211 #if MAVLINK_CRC_EXTRA 232 return _MAV_RETURN_uint64_t(msg, 0);
242 return _MAV_RETURN_float(msg, 8);
252 return _MAV_RETURN_float(msg, 12);
262 return _MAV_RETURN_float(msg, 16);
273 #if MAVLINK_NEED_BYTE_SWAP #define _mav_put_float(buf, wire_offset, b)
#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN
struct __mavlink_vision_speed_estimate_t mavlink_vision_speed_estimate_t
static void mavlink_msg_vision_speed_estimate_decode(const mavlink_message_t *msg, mavlink_vision_speed_estimate_t *vision_speed_estimate)
Decode a vision_speed_estimate message into a struct.
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 MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC
#define _MAV_PAYLOAD_NON_CONST(msg)
#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE
static uint64_t mavlink_msg_vision_speed_estimate_get_usec(const mavlink_message_t *msg)
Send a vision_speed_estimate message.
#define _MAV_PAYLOAD(msg)
static uint16_t mavlink_msg_vision_speed_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_vision_speed_estimate_t *vision_speed_estimate)
Encode a vision_speed_estimate struct.
static uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t usec, float x, float y, float z)
Pack a vision_speed_estimate message on a channel.
static float mavlink_msg_vision_speed_estimate_get_x(const mavlink_message_t *msg)
Get field x from vision_speed_estimate message.
static uint16_t mavlink_msg_vision_speed_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_vision_speed_estimate_t *vision_speed_estimate)
Encode a vision_speed_estimate struct on a channel.
static uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t usec, float x, float y, float z)
Pack a vision_speed_estimate message.
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_vision_speed_estimate_get_z(const mavlink_message_t *msg)
Get field z from vision_speed_estimate message.
static float mavlink_msg_vision_speed_estimate_get_y(const mavlink_message_t *msg)
Get field y from vision_speed_estimate message.