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
48 char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN];
49 _mav_put_uint64_t(buf, 0, usec);
50 _mav_put_float(buf, 8, x);
51 _mav_put_float(buf, 12, y);
52 _mav_put_float(buf, 16, z);
54 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
62 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
65 msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE;
67 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
69 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
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
90 char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN];
91 _mav_put_uint64_t(buf, 0, usec);
92 _mav_put_float(buf, 8, x);
93 _mav_put_float(buf, 12, y);
94 _mav_put_float(buf, 16, z);
96 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
104 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
107 msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE;
108 #if MAVLINK_CRC_EXTRA
109 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
111 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
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
156 char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN];
157 _mav_put_uint64_t(buf, 0, usec);
158 _mav_put_float(buf, 8, x);
159 _mav_put_float(buf, 12, y);
160 _mav_put_float(buf, 16, z);
162 #if MAVLINK_CRC_EXTRA
163 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
165 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
174 #if MAVLINK_CRC_EXTRA
175 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (
const char *)&packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
177 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (
const char *)&packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
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;
194 _mav_put_uint64_t(buf, 0, usec);
195 _mav_put_float(buf, 8, x);
196 _mav_put_float(buf, 12, y);
197 _mav_put_float(buf, 16, z);
199 #if MAVLINK_CRC_EXTRA
200 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
202 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
211 #if MAVLINK_CRC_EXTRA
212 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (
const char *)packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
214 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (
const char *)packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
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);
279 memcpy(vision_speed_estimate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
float y
Global Y speed.
Definition: mavlink_msg_vision_speed_estimate.h:9
uint64_t usec
Timestamp (microseconds, synced to UNIX time or since system boot)
Definition: mavlink_msg_vision_speed_estimate.h:7
Definition: mavlink_msg_vision_speed_estimate.h:5
float x
Global X speed.
Definition: mavlink_msg_vision_speed_estimate.h:8
float z
Global Z speed.
Definition: mavlink_msg_vision_speed_estimate.h:10