1 // MESSAGE OPTICAL_FLOW_RAD PACKING
3 #define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD 106
5 typedef struct __mavlink_optical_flow_rad_t
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
19 } mavlink_optical_flow_rad_t
;
21 #define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN 44
22 #define MAVLINK_MSG_ID_106_LEN 44
24 #define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC 138
25 #define MAVLINK_MSG_ID_106_CRC 138
29 #define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD { \
32 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_rad_t, time_usec) }, \
33 { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_optical_flow_rad_t, integration_time_us) }, \
34 { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_rad_t, integrated_x) }, \
35 { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_rad_t, integrated_y) }, \
36 { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_optical_flow_rad_t, integrated_xgyro) }, \
37 { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_optical_flow_rad_t, integrated_ygyro) }, \
38 { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_optical_flow_rad_t, integrated_zgyro) }, \
39 { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_optical_flow_rad_t, time_delta_distance_us) }, \
40 { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_optical_flow_rad_t, distance) }, \
41 { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_optical_flow_rad_t, temperature) }, \
42 { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_optical_flow_rad_t, sensor_id) }, \
43 { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_optical_flow_rad_t, quality) }, \
49 * @brief Pack a optical_flow_rad message
50 * @param system_id ID of this system
51 * @param component_id ID of this component (e.g. 200 for IMU)
52 * @param msg The MAVLink message to compress the data into
54 * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
55 * @param sensor_id Sensor ID
56 * @param 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.
57 * @param 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.)
58 * @param 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.)
59 * @param integrated_xgyro RH rotation around X axis (rad)
60 * @param integrated_ygyro RH rotation around Y axis (rad)
61 * @param integrated_zgyro RH rotation around Z axis (rad)
62 * @param temperature Temperature * 100 in centi-degrees Celsius
63 * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
64 * @param time_delta_distance_us Time in microseconds since the distance was sampled.
65 * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
66 * @return length of the message in bytes (excluding serial stream start sign)
68 static inline uint16_t mavlink_msg_optical_flow_rad_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
)
71 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
72 char buf
[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN
];
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
);
86 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN
);
88 mavlink_optical_flow_rad_t packet
;
89 packet
.time_usec
= time_usec
;
90 packet
.integration_time_us
= integration_time_us
;
91 packet
.integrated_x
= integrated_x
;
92 packet
.integrated_y
= integrated_y
;
93 packet
.integrated_xgyro
= integrated_xgyro
;
94 packet
.integrated_ygyro
= integrated_ygyro
;
95 packet
.integrated_zgyro
= integrated_zgyro
;
96 packet
.time_delta_distance_us
= time_delta_distance_us
;
97 packet
.distance
= distance
;
98 packet
.temperature
= temperature
;
99 packet
.sensor_id
= sensor_id
;
100 packet
.quality
= quality
;
102 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN
);
105 msg
->msgid
= MAVLINK_MSG_ID_OPTICAL_FLOW_RAD
;
106 #if MAVLINK_CRC_EXTRA
107 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC
);
109 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN
);
114 * @brief Pack a optical_flow_rad message on a channel
115 * @param system_id ID of this system
116 * @param component_id ID of this component (e.g. 200 for IMU)
117 * @param chan The MAVLink channel this message will be sent over
118 * @param msg The MAVLink message to compress the data into
119 * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
120 * @param sensor_id Sensor ID
121 * @param 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.
122 * @param 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.)
123 * @param 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.)
124 * @param integrated_xgyro RH rotation around X axis (rad)
125 * @param integrated_ygyro RH rotation around Y axis (rad)
126 * @param integrated_zgyro RH rotation around Z axis (rad)
127 * @param temperature Temperature * 100 in centi-degrees Celsius
128 * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
129 * @param time_delta_distance_us Time in microseconds since the distance was sampled.
130 * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
131 * @return length of the message in bytes (excluding serial stream start sign)
133 static inline uint16_t mavlink_msg_optical_flow_rad_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
)
137 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
138 char buf
[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN
];
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
);
152 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN
);
154 mavlink_optical_flow_rad_t packet
;
155 packet
.time_usec
= time_usec
;
156 packet
.integration_time_us
= integration_time_us
;
157 packet
.integrated_x
= integrated_x
;
158 packet
.integrated_y
= integrated_y
;
159 packet
.integrated_xgyro
= integrated_xgyro
;
160 packet
.integrated_ygyro
= integrated_ygyro
;
161 packet
.integrated_zgyro
= integrated_zgyro
;
162 packet
.time_delta_distance_us
= time_delta_distance_us
;
163 packet
.distance
= distance
;
164 packet
.temperature
= temperature
;
165 packet
.sensor_id
= sensor_id
;
166 packet
.quality
= quality
;
168 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN
);
171 msg
->msgid
= MAVLINK_MSG_ID_OPTICAL_FLOW_RAD
;
172 #if MAVLINK_CRC_EXTRA
173 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC
);
175 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN
);
180 * @brief Encode a optical_flow_rad struct
182 * @param system_id ID of this system
183 * @param component_id ID of this component (e.g. 200 for IMU)
184 * @param msg The MAVLink message to compress the data into
185 * @param optical_flow_rad C-struct to read the message contents from
187 static inline uint16_t mavlink_msg_optical_flow_rad_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
, const mavlink_optical_flow_rad_t
* optical_flow_rad
)
189 return mavlink_msg_optical_flow_rad_pack(system_id
, component_id
, msg
, optical_flow_rad
->time_usec
, optical_flow_rad
->sensor_id
, optical_flow_rad
->integration_time_us
, optical_flow_rad
->integrated_x
, optical_flow_rad
->integrated_y
, optical_flow_rad
->integrated_xgyro
, optical_flow_rad
->integrated_ygyro
, optical_flow_rad
->integrated_zgyro
, optical_flow_rad
->temperature
, optical_flow_rad
->quality
, optical_flow_rad
->time_delta_distance_us
, optical_flow_rad
->distance
);
193 * @brief Encode a optical_flow_rad struct on a channel
195 * @param system_id ID of this system
196 * @param component_id ID of this component (e.g. 200 for IMU)
197 * @param chan The MAVLink channel this message will be sent over
198 * @param msg The MAVLink message to compress the data into
199 * @param optical_flow_rad C-struct to read the message contents from
201 static inline uint16_t mavlink_msg_optical_flow_rad_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_optical_flow_rad_t
* optical_flow_rad
)
203 return mavlink_msg_optical_flow_rad_pack_chan(system_id
, component_id
, chan
, msg
, optical_flow_rad
->time_usec
, optical_flow_rad
->sensor_id
, optical_flow_rad
->integration_time_us
, optical_flow_rad
->integrated_x
, optical_flow_rad
->integrated_y
, optical_flow_rad
->integrated_xgyro
, optical_flow_rad
->integrated_ygyro
, optical_flow_rad
->integrated_zgyro
, optical_flow_rad
->temperature
, optical_flow_rad
->quality
, optical_flow_rad
->time_delta_distance_us
, optical_flow_rad
->distance
);
207 * @brief Send a optical_flow_rad message
208 * @param chan MAVLink channel to send the message
210 * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
211 * @param sensor_id Sensor ID
212 * @param 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.
213 * @param 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.)
214 * @param 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.)
215 * @param integrated_xgyro RH rotation around X axis (rad)
216 * @param integrated_ygyro RH rotation around Y axis (rad)
217 * @param integrated_zgyro RH rotation around Z axis (rad)
218 * @param temperature Temperature * 100 in centi-degrees Celsius
219 * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
220 * @param time_delta_distance_us Time in microseconds since the distance was sampled.
221 * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
223 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
225 static inline void mavlink_msg_optical_flow_rad_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
)
227 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
228 char buf
[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN
];
229 _mav_put_uint64_t(buf
, 0, time_usec
);
230 _mav_put_uint32_t(buf
, 8, integration_time_us
);
231 _mav_put_float(buf
, 12, integrated_x
);
232 _mav_put_float(buf
, 16, integrated_y
);
233 _mav_put_float(buf
, 20, integrated_xgyro
);
234 _mav_put_float(buf
, 24, integrated_ygyro
);
235 _mav_put_float(buf
, 28, integrated_zgyro
);
236 _mav_put_uint32_t(buf
, 32, time_delta_distance_us
);
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
);
242 #if MAVLINK_CRC_EXTRA
243 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD
, buf
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC
);
245 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD
, buf
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN
);
248 mavlink_optical_flow_rad_t packet
;
249 packet
.time_usec
= time_usec
;
250 packet
.integration_time_us
= integration_time_us
;
251 packet
.integrated_x
= integrated_x
;
252 packet
.integrated_y
= integrated_y
;
253 packet
.integrated_xgyro
= integrated_xgyro
;
254 packet
.integrated_ygyro
= integrated_ygyro
;
255 packet
.integrated_zgyro
= integrated_zgyro
;
256 packet
.time_delta_distance_us
= time_delta_distance_us
;
257 packet
.distance
= distance
;
258 packet
.temperature
= temperature
;
259 packet
.sensor_id
= sensor_id
;
260 packet
.quality
= quality
;
262 #if MAVLINK_CRC_EXTRA
263 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD
, (const char *)&packet
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC
);
265 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD
, (const char *)&packet
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN
);
270 #if MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN <= MAVLINK_MAX_PAYLOAD_LEN
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.
278 static inline void mavlink_msg_optical_flow_rad_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
)
280 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
281 char *buf
= (char *)msgbuf
;
282 _mav_put_uint64_t(buf
, 0, time_usec
);
283 _mav_put_uint32_t(buf
, 8, integration_time_us
);
284 _mav_put_float(buf
, 12, integrated_x
);
285 _mav_put_float(buf
, 16, integrated_y
);
286 _mav_put_float(buf
, 20, integrated_xgyro
);
287 _mav_put_float(buf
, 24, integrated_ygyro
);
288 _mav_put_float(buf
, 28, integrated_zgyro
);
289 _mav_put_uint32_t(buf
, 32, time_delta_distance_us
);
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
);
295 #if MAVLINK_CRC_EXTRA
296 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD
, buf
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC
);
298 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD
, buf
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN
);
301 mavlink_optical_flow_rad_t
*packet
= (mavlink_optical_flow_rad_t
*)msgbuf
;
302 packet
->time_usec
= time_usec
;
303 packet
->integration_time_us
= integration_time_us
;
304 packet
->integrated_x
= integrated_x
;
305 packet
->integrated_y
= integrated_y
;
306 packet
->integrated_xgyro
= integrated_xgyro
;
307 packet
->integrated_ygyro
= integrated_ygyro
;
308 packet
->integrated_zgyro
= integrated_zgyro
;
309 packet
->time_delta_distance_us
= time_delta_distance_us
;
310 packet
->distance
= distance
;
311 packet
->temperature
= temperature
;
312 packet
->sensor_id
= sensor_id
;
313 packet
->quality
= quality
;
315 #if MAVLINK_CRC_EXTRA
316 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD
, (const char *)packet
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC
);
318 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD
, (const char *)packet
, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN
);
326 // MESSAGE OPTICAL_FLOW_RAD UNPACKING
330 * @brief Get field time_usec from optical_flow_rad message
332 * @return Timestamp (microseconds, synced to UNIX time or since system boot)
334 static inline uint64_t mavlink_msg_optical_flow_rad_get_time_usec(const mavlink_message_t
* msg
)
336 return _MAV_RETURN_uint64_t(msg
, 0);
340 * @brief Get field sensor_id from optical_flow_rad message
344 static inline uint8_t mavlink_msg_optical_flow_rad_get_sensor_id(const mavlink_message_t
* msg
)
346 return _MAV_RETURN_uint8_t(msg
, 42);
350 * @brief Get field integration_time_us from optical_flow_rad message
352 * @return Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
354 static inline uint32_t mavlink_msg_optical_flow_rad_get_integration_time_us(const mavlink_message_t
* msg
)
356 return _MAV_RETURN_uint32_t(msg
, 8);
360 * @brief Get field integrated_x from optical_flow_rad message
362 * @return 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.)
364 static inline float mavlink_msg_optical_flow_rad_get_integrated_x(const mavlink_message_t
* msg
)
366 return _MAV_RETURN_float(msg
, 12);
370 * @brief Get field integrated_y from optical_flow_rad message
372 * @return 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.)
374 static inline float mavlink_msg_optical_flow_rad_get_integrated_y(const mavlink_message_t
* msg
)
376 return _MAV_RETURN_float(msg
, 16);
380 * @brief Get field integrated_xgyro from optical_flow_rad message
382 * @return RH rotation around X axis (rad)
384 static inline float mavlink_msg_optical_flow_rad_get_integrated_xgyro(const mavlink_message_t
* msg
)
386 return _MAV_RETURN_float(msg
, 20);
390 * @brief Get field integrated_ygyro from optical_flow_rad message
392 * @return RH rotation around Y axis (rad)
394 static inline float mavlink_msg_optical_flow_rad_get_integrated_ygyro(const mavlink_message_t
* msg
)
396 return _MAV_RETURN_float(msg
, 24);
400 * @brief Get field integrated_zgyro from optical_flow_rad message
402 * @return RH rotation around Z axis (rad)
404 static inline float mavlink_msg_optical_flow_rad_get_integrated_zgyro(const mavlink_message_t
* msg
)
406 return _MAV_RETURN_float(msg
, 28);
410 * @brief Get field temperature from optical_flow_rad message
412 * @return Temperature * 100 in centi-degrees Celsius
414 static inline int16_t mavlink_msg_optical_flow_rad_get_temperature(const mavlink_message_t
* msg
)
416 return _MAV_RETURN_int16_t(msg
, 40);
420 * @brief Get field quality from optical_flow_rad message
422 * @return Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
424 static inline uint8_t mavlink_msg_optical_flow_rad_get_quality(const mavlink_message_t
* msg
)
426 return _MAV_RETURN_uint8_t(msg
, 43);
430 * @brief Get field time_delta_distance_us from optical_flow_rad message
432 * @return Time in microseconds since the distance was sampled.
434 static inline uint32_t mavlink_msg_optical_flow_rad_get_time_delta_distance_us(const mavlink_message_t
* msg
)
436 return _MAV_RETURN_uint32_t(msg
, 32);
440 * @brief Get field distance from optical_flow_rad message
442 * @return Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
444 static inline float mavlink_msg_optical_flow_rad_get_distance(const mavlink_message_t
* msg
)
446 return _MAV_RETURN_float(msg
, 36);
450 * @brief Decode a optical_flow_rad message into a struct
452 * @param msg The message to decode
453 * @param optical_flow_rad C-struct to decode the message contents into
455 static inline void mavlink_msg_optical_flow_rad_decode(const mavlink_message_t
* msg
, mavlink_optical_flow_rad_t
* optical_flow_rad
)
457 #if MAVLINK_NEED_BYTE_SWAP
458 optical_flow_rad
->time_usec
= mavlink_msg_optical_flow_rad_get_time_usec(msg
);
459 optical_flow_rad
->integration_time_us
= mavlink_msg_optical_flow_rad_get_integration_time_us(msg
);
460 optical_flow_rad
->integrated_x
= mavlink_msg_optical_flow_rad_get_integrated_x(msg
);
461 optical_flow_rad
->integrated_y
= mavlink_msg_optical_flow_rad_get_integrated_y(msg
);
462 optical_flow_rad
->integrated_xgyro
= mavlink_msg_optical_flow_rad_get_integrated_xgyro(msg
);
463 optical_flow_rad
->integrated_ygyro
= mavlink_msg_optical_flow_rad_get_integrated_ygyro(msg
);
464 optical_flow_rad
->integrated_zgyro
= mavlink_msg_optical_flow_rad_get_integrated_zgyro(msg
);
465 optical_flow_rad
->time_delta_distance_us
= mavlink_msg_optical_flow_rad_get_time_delta_distance_us(msg
);
466 optical_flow_rad
->distance
= mavlink_msg_optical_flow_rad_get_distance(msg
);
467 optical_flow_rad
->temperature
= mavlink_msg_optical_flow_rad_get_temperature(msg
);
468 optical_flow_rad
->sensor_id
= mavlink_msg_optical_flow_rad_get_sensor_id(msg
);
469 optical_flow_rad
->quality
= mavlink_msg_optical_flow_rad_get_quality(msg
);
471 memcpy(optical_flow_rad
, _MAV_PAYLOAD(msg
), MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN
);