mavlink_msg_hil_optical_flow.h
Go to the documentation of this file.
1 // MESSAGE HIL_OPTICAL_FLOW PACKING
2 
3 #define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW 114
4 
6 {
7  uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/
8  uint32_t integration_time_us; /*< Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.*/
9  float integrated_x; /*< Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)*/
10  float integrated_y; /*< Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)*/
11  float integrated_xgyro; /*< RH rotation around X axis (rad)*/
12  float integrated_ygyro; /*< RH rotation around Y axis (rad)*/
13  float integrated_zgyro; /*< RH rotation around Z axis (rad)*/
14  uint32_t time_delta_distance_us; /*< Time in microseconds since the distance was sampled.*/
15  float distance; /*< Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.*/
16  int16_t temperature; /*< Temperature * 100 in centi-degrees Celsius*/
17  uint8_t sensor_id; /*< Sensor ID*/
18  uint8_t quality; /*< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality*/
20 
21 #define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN 44
22 #define MAVLINK_MSG_ID_114_LEN 44
23 
24 #define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC 237
25 #define MAVLINK_MSG_ID_114_CRC 237
26 
27 
28 
29 #define MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW { \
30  "HIL_OPTICAL_FLOW", \
31  12, \
32  { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_optical_flow_t, time_usec) }, \
33  { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_hil_optical_flow_t, integration_time_us) }, \
34  { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_optical_flow_t, integrated_x) }, \
35  { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_optical_flow_t, integrated_y) }, \
36  { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_optical_flow_t, integrated_xgyro) }, \
37  { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_optical_flow_t, integrated_ygyro) }, \
38  { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_optical_flow_t, integrated_zgyro) }, \
39  { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_hil_optical_flow_t, time_delta_distance_us) }, \
40  { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_optical_flow_t, distance) }, \
41  { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \
42  { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \
43  { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \
44  } \
45 }
46 
47 
68 static inline uint16_t mavlink_msg_hil_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
69  uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance)
70 {
71 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
73  _mav_put_uint64_t(buf, 0, time_usec);
74  _mav_put_uint32_t(buf, 8, integration_time_us);
75  _mav_put_float(buf, 12, integrated_x);
76  _mav_put_float(buf, 16, integrated_y);
77  _mav_put_float(buf, 20, integrated_xgyro);
78  _mav_put_float(buf, 24, integrated_ygyro);
79  _mav_put_float(buf, 28, integrated_zgyro);
80  _mav_put_uint32_t(buf, 32, time_delta_distance_us);
81  _mav_put_float(buf, 36, distance);
82  _mav_put_int16_t(buf, 40, temperature);
83  _mav_put_uint8_t(buf, 42, sensor_id);
84  _mav_put_uint8_t(buf, 43, quality);
85 
87 #else
89  packet.time_usec = time_usec;
91  packet.integrated_x = integrated_x;
92  packet.integrated_y = integrated_y;
97  packet.distance = distance;
98  packet.temperature = temperature;
99  packet.sensor_id = sensor_id;
100  packet.quality = quality;
101 
103 #endif
104 
105  msg->msgid = MAVLINK_MSG_ID_HIL_OPTICAL_FLOW;
106 #if MAVLINK_CRC_EXTRA
108 #else
109  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
110 #endif
111 }
112 
133 static inline uint16_t mavlink_msg_hil_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
134  mavlink_message_t* msg,
135  uint64_t time_usec,uint8_t sensor_id,uint32_t integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,int16_t temperature,uint8_t quality,uint32_t time_delta_distance_us,float distance)
136 {
137 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
139  _mav_put_uint64_t(buf, 0, time_usec);
140  _mav_put_uint32_t(buf, 8, integration_time_us);
141  _mav_put_float(buf, 12, integrated_x);
142  _mav_put_float(buf, 16, integrated_y);
143  _mav_put_float(buf, 20, integrated_xgyro);
144  _mav_put_float(buf, 24, integrated_ygyro);
145  _mav_put_float(buf, 28, integrated_zgyro);
146  _mav_put_uint32_t(buf, 32, time_delta_distance_us);
147  _mav_put_float(buf, 36, distance);
148  _mav_put_int16_t(buf, 40, temperature);
149  _mav_put_uint8_t(buf, 42, sensor_id);
150  _mav_put_uint8_t(buf, 43, quality);
151 
153 #else
155  packet.time_usec = time_usec;
157  packet.integrated_x = integrated_x;
158  packet.integrated_y = integrated_y;
163  packet.distance = distance;
164  packet.temperature = temperature;
165  packet.sensor_id = sensor_id;
166  packet.quality = quality;
167 
169 #endif
170 
171  msg->msgid = MAVLINK_MSG_ID_HIL_OPTICAL_FLOW;
172 #if MAVLINK_CRC_EXTRA
174 #else
175  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
176 #endif
177 }
178 
187 static inline uint16_t mavlink_msg_hil_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_optical_flow_t* hil_optical_flow)
188 {
189  return mavlink_msg_hil_optical_flow_pack(system_id, component_id, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->integration_time_us, hil_optical_flow->integrated_x, hil_optical_flow->integrated_y, hil_optical_flow->integrated_xgyro, hil_optical_flow->integrated_ygyro, hil_optical_flow->integrated_zgyro, hil_optical_flow->temperature, hil_optical_flow->quality, hil_optical_flow->time_delta_distance_us, hil_optical_flow->distance);
190 }
191 
201 static inline uint16_t mavlink_msg_hil_optical_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_optical_flow_t* hil_optical_flow)
202 {
203  return mavlink_msg_hil_optical_flow_pack_chan(system_id, component_id, chan, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->integration_time_us, hil_optical_flow->integrated_x, hil_optical_flow->integrated_y, hil_optical_flow->integrated_xgyro, hil_optical_flow->integrated_ygyro, hil_optical_flow->integrated_zgyro, hil_optical_flow->temperature, hil_optical_flow->quality, hil_optical_flow->time_delta_distance_us, hil_optical_flow->distance);
204 }
205 
223 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
224 
225 static inline void mavlink_msg_hil_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance)
226 {
227 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
229  _mav_put_uint64_t(buf, 0, time_usec);
231  _mav_put_float(buf, 12, integrated_x);
232  _mav_put_float(buf, 16, integrated_y);
237  _mav_put_float(buf, 36, distance);
238  _mav_put_int16_t(buf, 40, temperature);
239  _mav_put_uint8_t(buf, 42, sensor_id);
240  _mav_put_uint8_t(buf, 43, quality);
241 
242 #if MAVLINK_CRC_EXTRA
244 #else
245  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
246 #endif
247 #else
249  packet.time_usec = time_usec;
251  packet.integrated_x = integrated_x;
252  packet.integrated_y = integrated_y;
257  packet.distance = distance;
258  packet.temperature = temperature;
259  packet.sensor_id = sensor_id;
260  packet.quality = quality;
261 
262 #if MAVLINK_CRC_EXTRA
263  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC);
264 #else
265  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
266 #endif
267 #endif
268 }
269 
270 #if MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
271 /*
272  This varient of _send() can be used to save stack space by re-using
273  memory from the receive buffer. The caller provides a
274  mavlink_message_t which is the size of a full mavlink message. This
275  is usually the receive buffer for the channel, and allows a reply to an
276  incoming message with minimum stack space usage.
277  */
278 static inline void mavlink_msg_hil_optical_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance)
279 {
280 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
281  char *buf = (char *)msgbuf;
282  _mav_put_uint64_t(buf, 0, time_usec);
284  _mav_put_float(buf, 12, integrated_x);
285  _mav_put_float(buf, 16, integrated_y);
290  _mav_put_float(buf, 36, distance);
291  _mav_put_int16_t(buf, 40, temperature);
292  _mav_put_uint8_t(buf, 42, sensor_id);
293  _mav_put_uint8_t(buf, 43, quality);
294 
295 #if MAVLINK_CRC_EXTRA
297 #else
298  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
299 #endif
300 #else
302  packet->time_usec = time_usec;
304  packet->integrated_x = integrated_x;
305  packet->integrated_y = integrated_y;
310  packet->distance = distance;
311  packet->temperature = temperature;
312  packet->sensor_id = sensor_id;
313  packet->quality = quality;
314 
315 #if MAVLINK_CRC_EXTRA
316  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC);
317 #else
318  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
319 #endif
320 #endif
321 }
322 #endif
323 
324 #endif
325 
326 // MESSAGE HIL_OPTICAL_FLOW UNPACKING
327 
328 
334 static inline uint64_t mavlink_msg_hil_optical_flow_get_time_usec(const mavlink_message_t* msg)
335 {
336  return _MAV_RETURN_uint64_t(msg, 0);
337 }
338 
344 static inline uint8_t mavlink_msg_hil_optical_flow_get_sensor_id(const mavlink_message_t* msg)
345 {
346  return _MAV_RETURN_uint8_t(msg, 42);
347 }
348 
354 static inline uint32_t mavlink_msg_hil_optical_flow_get_integration_time_us(const mavlink_message_t* msg)
355 {
356  return _MAV_RETURN_uint32_t(msg, 8);
357 }
358 
364 static inline float mavlink_msg_hil_optical_flow_get_integrated_x(const mavlink_message_t* msg)
365 {
366  return _MAV_RETURN_float(msg, 12);
367 }
368 
374 static inline float mavlink_msg_hil_optical_flow_get_integrated_y(const mavlink_message_t* msg)
375 {
376  return _MAV_RETURN_float(msg, 16);
377 }
378 
384 static inline float mavlink_msg_hil_optical_flow_get_integrated_xgyro(const mavlink_message_t* msg)
385 {
386  return _MAV_RETURN_float(msg, 20);
387 }
388 
394 static inline float mavlink_msg_hil_optical_flow_get_integrated_ygyro(const mavlink_message_t* msg)
395 {
396  return _MAV_RETURN_float(msg, 24);
397 }
398 
404 static inline float mavlink_msg_hil_optical_flow_get_integrated_zgyro(const mavlink_message_t* msg)
405 {
406  return _MAV_RETURN_float(msg, 28);
407 }
408 
414 static inline int16_t mavlink_msg_hil_optical_flow_get_temperature(const mavlink_message_t* msg)
415 {
416  return _MAV_RETURN_int16_t(msg, 40);
417 }
418 
424 static inline uint8_t mavlink_msg_hil_optical_flow_get_quality(const mavlink_message_t* msg)
425 {
426  return _MAV_RETURN_uint8_t(msg, 43);
427 }
428 
434 static inline uint32_t mavlink_msg_hil_optical_flow_get_time_delta_distance_us(const mavlink_message_t* msg)
435 {
436  return _MAV_RETURN_uint32_t(msg, 32);
437 }
438 
444 static inline float mavlink_msg_hil_optical_flow_get_distance(const mavlink_message_t* msg)
445 {
446  return _MAV_RETURN_float(msg, 36);
447 }
448 
455 static inline void mavlink_msg_hil_optical_flow_decode(const mavlink_message_t* msg, mavlink_hil_optical_flow_t* hil_optical_flow)
456 {
457 #if MAVLINK_NEED_BYTE_SWAP
458  hil_optical_flow->time_usec = mavlink_msg_hil_optical_flow_get_time_usec(msg);
466  hil_optical_flow->distance = mavlink_msg_hil_optical_flow_get_distance(msg);
468  hil_optical_flow->sensor_id = mavlink_msg_hil_optical_flow_get_sensor_id(msg);
469  hil_optical_flow->quality = mavlink_msg_hil_optical_flow_get_quality(msg);
470 #else
471  memcpy(hil_optical_flow, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
472 #endif
473 }
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:151
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:244
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:140
#define _mav_put_uint64_t(buf, wire_offset, b)
Definition: protocol.h:149
#define _mav_put_int16_t(buf, wire_offset, b)
Definition: protocol.h:146
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:147


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 19:59:24