3 #define MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW 106
15 #define MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN 54
16 #define MAVLINK_MSG_ID_106_LEN 54
18 #define MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC 211
19 #define MAVLINK_MSG_ID_106_CRC 211
21 #define MAVLINK_MSG_OMNIDIRECTIONAL_FLOW_FIELD_LEFT_LEN 10
22 #define MAVLINK_MSG_OMNIDIRECTIONAL_FLOW_FIELD_RIGHT_LEN 10
24 #define MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW { \
25 "OMNIDIRECTIONAL_FLOW", \
27 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_omnidirectional_flow_t, time_usec) }, \
28 { "front_distance_m", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_omnidirectional_flow_t, front_distance_m) }, \
29 { "left", NULL, MAVLINK_TYPE_INT16_T, 10, 12, offsetof(mavlink_omnidirectional_flow_t, left) }, \
30 { "right", NULL, MAVLINK_TYPE_INT16_T, 10, 32, offsetof(mavlink_omnidirectional_flow_t, right) }, \
31 { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_omnidirectional_flow_t, sensor_id) }, \
32 { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 53, offsetof(mavlink_omnidirectional_flow_t, quality) }, \
51 static inline uint16_t mavlink_msg_omnidirectional_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
52 uint64_t time_usec, uint8_t sensor_id,
const int16_t *left,
const int16_t *right, uint8_t quality,
float front_distance_m)
54 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
55 char buf[MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN];
56 _mav_put_uint64_t(buf, 0, time_usec);
57 _mav_put_float(buf, 8, front_distance_m);
58 _mav_put_uint8_t(buf, 52, sensor_id);
59 _mav_put_uint8_t(buf, 53, quality);
60 _mav_put_int16_t_array(buf, 12, left, 10);
61 _mav_put_int16_t_array(buf, 32, right, 10);
62 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
69 mav_array_memcpy(packet.
left, left,
sizeof(int16_t)*10);
70 mav_array_memcpy(packet.
right, right,
sizeof(int16_t)*10);
71 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
74 msg->msgid = MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW;
76 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC);
78 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
96 static inline uint16_t mavlink_msg_omnidirectional_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
97 mavlink_message_t* msg,
98 uint64_t time_usec,uint8_t sensor_id,
const int16_t *left,
const int16_t *right,uint8_t quality,
float front_distance_m)
100 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
101 char buf[MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN];
102 _mav_put_uint64_t(buf, 0, time_usec);
103 _mav_put_float(buf, 8, front_distance_m);
104 _mav_put_uint8_t(buf, 52, sensor_id);
105 _mav_put_uint8_t(buf, 53, quality);
106 _mav_put_int16_t_array(buf, 12, left, 10);
107 _mav_put_int16_t_array(buf, 32, right, 10);
108 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
115 mav_array_memcpy(packet.
left, left,
sizeof(int16_t)*10);
116 mav_array_memcpy(packet.
right, right,
sizeof(int16_t)*10);
117 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
120 msg->msgid = MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW;
121 #if MAVLINK_CRC_EXTRA
122 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC);
124 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
136 static inline uint16_t mavlink_msg_omnidirectional_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_omnidirectional_flow_t* omnidirectional_flow)
138 return mavlink_msg_omnidirectional_flow_pack(system_id, component_id, msg, omnidirectional_flow->
time_usec, omnidirectional_flow->
sensor_id, omnidirectional_flow->
left, omnidirectional_flow->
right, omnidirectional_flow->
quality, omnidirectional_flow->
front_distance_m);
150 static inline uint16_t mavlink_msg_omnidirectional_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_omnidirectional_flow_t* omnidirectional_flow)
152 return mavlink_msg_omnidirectional_flow_pack_chan(system_id, component_id, chan, msg, omnidirectional_flow->
time_usec, omnidirectional_flow->
sensor_id, omnidirectional_flow->
left, omnidirectional_flow->
right, omnidirectional_flow->
quality, omnidirectional_flow->
front_distance_m);
166 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
168 static inline void mavlink_msg_omnidirectional_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id,
const int16_t *left,
const int16_t *right, uint8_t quality,
float front_distance_m)
170 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
171 char buf[MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN];
172 _mav_put_uint64_t(buf, 0, time_usec);
173 _mav_put_float(buf, 8, front_distance_m);
174 _mav_put_uint8_t(buf, 52, sensor_id);
175 _mav_put_uint8_t(buf, 53, quality);
176 _mav_put_int16_t_array(buf, 12, left, 10);
177 _mav_put_int16_t_array(buf, 32, right, 10);
178 #if MAVLINK_CRC_EXTRA
179 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC);
181 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
189 mav_array_memcpy(packet.
left, left,
sizeof(int16_t)*10);
190 mav_array_memcpy(packet.
right, right,
sizeof(int16_t)*10);
191 #if MAVLINK_CRC_EXTRA
192 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, (
const char *)&packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC);
194 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, (
const char *)&packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
199 #if MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
207 static inline void mavlink_msg_omnidirectional_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id,
const int16_t *left,
const int16_t *right, uint8_t quality,
float front_distance_m)
209 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
210 char *buf = (
char *)msgbuf;
211 _mav_put_uint64_t(buf, 0, time_usec);
212 _mav_put_float(buf, 8, front_distance_m);
213 _mav_put_uint8_t(buf, 52, sensor_id);
214 _mav_put_uint8_t(buf, 53, quality);
215 _mav_put_int16_t_array(buf, 12, left, 10);
216 _mav_put_int16_t_array(buf, 32, right, 10);
217 #if MAVLINK_CRC_EXTRA
218 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC);
220 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
228 mav_array_memcpy(packet->
left, left,
sizeof(int16_t)*10);
229 mav_array_memcpy(packet->
right, right,
sizeof(int16_t)*10);
230 #if MAVLINK_CRC_EXTRA
231 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, (
const char *)packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC);
233 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, (
const char *)packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
249 static inline uint64_t mavlink_msg_omnidirectional_flow_get_time_usec(
const mavlink_message_t* msg)
251 return _MAV_RETURN_uint64_t(msg, 0);
259 static inline uint8_t mavlink_msg_omnidirectional_flow_get_sensor_id(
const mavlink_message_t* msg)
261 return _MAV_RETURN_uint8_t(msg, 52);
269 static inline uint16_t mavlink_msg_omnidirectional_flow_get_left(
const mavlink_message_t* msg, int16_t *left)
271 return _MAV_RETURN_int16_t_array(msg, left, 10, 12);
279 static inline uint16_t mavlink_msg_omnidirectional_flow_get_right(
const mavlink_message_t* msg, int16_t *right)
281 return _MAV_RETURN_int16_t_array(msg, right, 10, 32);
289 static inline uint8_t mavlink_msg_omnidirectional_flow_get_quality(
const mavlink_message_t* msg)
291 return _MAV_RETURN_uint8_t(msg, 53);
299 static inline float mavlink_msg_omnidirectional_flow_get_front_distance_m(
const mavlink_message_t* msg)
301 return _MAV_RETURN_float(msg, 8);
312 #if MAVLINK_NEED_BYTE_SWAP
313 omnidirectional_flow->
time_usec = mavlink_msg_omnidirectional_flow_get_time_usec(msg);
314 omnidirectional_flow->
front_distance_m = mavlink_msg_omnidirectional_flow_get_front_distance_m(msg);
315 mavlink_msg_omnidirectional_flow_get_left(msg, omnidirectional_flow->
left);
316 mavlink_msg_omnidirectional_flow_get_right(msg, omnidirectional_flow->
right);
317 omnidirectional_flow->
sensor_id = mavlink_msg_omnidirectional_flow_get_sensor_id(msg);
318 omnidirectional_flow->
quality = mavlink_msg_omnidirectional_flow_get_quality(msg);
320 memcpy(omnidirectional_flow, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
Definition: mavlink_msg_omnidirectional_flow.h:5
int16_t right[10]
Flow in deci pixels (1 = 0.1 pixel) on right hemisphere.
Definition: mavlink_msg_omnidirectional_flow.h:10
uint8_t quality
Optical flow quality / confidence. 0: bad, 255: maximum quality.
Definition: mavlink_msg_omnidirectional_flow.h:12
float front_distance_m
Front distance in meters. Positive value (including zero): distance known. Negative value: Unknown di...
Definition: mavlink_msg_omnidirectional_flow.h:8
uint64_t time_usec
Timestamp (microseconds, synced to UNIX time or since system boot)
Definition: mavlink_msg_omnidirectional_flow.h:7
uint8_t sensor_id
Sensor ID.
Definition: mavlink_msg_omnidirectional_flow.h:11
int16_t left[10]
Flow in deci pixels (1 = 0.1 pixel) on left hemisphere.
Definition: mavlink_msg_omnidirectional_flow.h:9