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) }, \
44 static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
45 uint64_t usec,
float x,
float y,
float z)
47 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
85 static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
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
123 static inline 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)
125 return mavlink_msg_vision_speed_estimate_pack(system_id, component_id, msg, vision_speed_estimate->
usec, vision_speed_estimate->
x, vision_speed_estimate->
y, vision_speed_estimate->
z);
137 static inline 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)
139 return mavlink_msg_vision_speed_estimate_pack_chan(system_id, component_id, chan, msg, vision_speed_estimate->
usec, vision_speed_estimate->
x, vision_speed_estimate->
y, vision_speed_estimate->
z);
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
230 static inline uint64_t mavlink_msg_vision_speed_estimate_get_usec(
const mavlink_message_t* msg)
232 return _MAV_RETURN_uint64_t(msg, 0);
240 static inline float mavlink_msg_vision_speed_estimate_get_x(
const mavlink_message_t* msg)
242 return _MAV_RETURN_float(msg, 8);
250 static inline float mavlink_msg_vision_speed_estimate_get_y(
const mavlink_message_t* msg)
252 return _MAV_RETURN_float(msg, 12);
260 static inline float mavlink_msg_vision_speed_estimate_get_z(
const mavlink_message_t* msg)
262 return _MAV_RETURN_float(msg, 16);
273 #if MAVLINK_NEED_BYTE_SWAP
274 vision_speed_estimate->
usec = mavlink_msg_vision_speed_estimate_get_usec(msg);
275 vision_speed_estimate->
x = mavlink_msg_vision_speed_estimate_get_x(msg);
276 vision_speed_estimate->
y = mavlink_msg_vision_speed_estimate_get_y(msg);
277 vision_speed_estimate->
z = mavlink_msg_vision_speed_estimate_get_z(msg);
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN
Definition: mavlink_msg_vision_speed_estimate.h:13
float y
Global Y speed.
Definition: mavlink_msg_vision_speed_estimate.h:9
struct __mavlink_vision_speed_estimate_t mavlink_vision_speed_estimate_t
uint64_t usec
Timestamp (microseconds, synced to UNIX time or since system boot)
Definition: mavlink_msg_vision_speed_estimate.h:7
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.
Definition: mavlink_helpers.h:105
#define _mav_put_uint64_t(buf, wire_offset, b)
Definition: protocol.h:143
#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC
Definition: mavlink_msg_vision_speed_estimate.h:16
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE
Definition: mavlink_msg_vision_speed_estimate.h:3
mavlink_channel_t
Definition: mavlink_types.h:178
Definition: mavlink_msg_vision_speed_estimate.h:5
float x
Global X speed.
Definition: mavlink_msg_vision_speed_estimate.h:8
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
uint8_t z
set the acc deadband for z-Axis, this ignores small accelerations
Definition: accelerometer.h:52
float z
Global Z speed.
Definition: mavlink_msg_vision_speed_estimate.h:10
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.
Definition: mavlink_helpers.h:71