2 // MESSAGE HIL_OPTICAL_FLOW PACKING
4 #define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW 114
7 typedef struct __mavlink_hil_optical_flow_t
{
8 uint64_t time_usec
; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
9 uint32_t integration_time_us
; /*< [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.*/
10 float integrated_x
; /*< [rad] 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.)*/
11 float integrated_y
; /*< [rad] 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.)*/
12 float integrated_xgyro
; /*< [rad] RH rotation around X axis*/
13 float integrated_ygyro
; /*< [rad] RH rotation around Y axis*/
14 float integrated_zgyro
; /*< [rad] RH rotation around Z axis*/
15 uint32_t time_delta_distance_us
; /*< [us] Time since the distance was sampled.*/
16 float distance
; /*< [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.*/
17 int16_t temperature
; /*< [cdegC] Temperature*/
18 uint8_t sensor_id
; /*< Sensor ID*/
19 uint8_t quality
; /*< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality*/
20 } mavlink_hil_optical_flow_t
;
22 #define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN 44
23 #define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN 44
24 #define MAVLINK_MSG_ID_114_LEN 44
25 #define MAVLINK_MSG_ID_114_MIN_LEN 44
27 #define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC 237
28 #define MAVLINK_MSG_ID_114_CRC 237
32 #if MAVLINK_COMMAND_24BIT
33 #define MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW { \
37 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_optical_flow_t, time_usec) }, \
38 { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \
39 { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_hil_optical_flow_t, integration_time_us) }, \
40 { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_optical_flow_t, integrated_x) }, \
41 { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_optical_flow_t, integrated_y) }, \
42 { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_optical_flow_t, integrated_xgyro) }, \
43 { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_optical_flow_t, integrated_ygyro) }, \
44 { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_optical_flow_t, integrated_zgyro) }, \
45 { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \
46 { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \
47 { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_hil_optical_flow_t, time_delta_distance_us) }, \
48 { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_optical_flow_t, distance) }, \
52 #define MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW { \
55 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_optical_flow_t, time_usec) }, \
56 { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \
57 { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_hil_optical_flow_t, integration_time_us) }, \
58 { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_optical_flow_t, integrated_x) }, \
59 { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_optical_flow_t, integrated_y) }, \
60 { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_optical_flow_t, integrated_xgyro) }, \
61 { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_optical_flow_t, integrated_ygyro) }, \
62 { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_optical_flow_t, integrated_zgyro) }, \
63 { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \
64 { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \
65 { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_hil_optical_flow_t, time_delta_distance_us) }, \
66 { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_optical_flow_t, distance) }, \
72 * @brief Pack a hil_optical_flow message
73 * @param system_id ID of this system
74 * @param component_id ID of this component (e.g. 200 for IMU)
75 * @param msg The MAVLink message to compress the data into
77 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
78 * @param sensor_id Sensor ID
79 * @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
80 * @param integrated_x [rad] 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.)
81 * @param integrated_y [rad] 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.)
82 * @param integrated_xgyro [rad] RH rotation around X axis
83 * @param integrated_ygyro [rad] RH rotation around Y axis
84 * @param integrated_zgyro [rad] RH rotation around Z axis
85 * @param temperature [cdegC] Temperature
86 * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
87 * @param time_delta_distance_us [us] Time since the distance was sampled.
88 * @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.
89 * @return length of the message in bytes (excluding serial stream start sign)
91 static inline uint16_t mavlink_msg_hil_optical_flow_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
92 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
)
94 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
95 char buf
[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN
];
96 _mav_put_uint64_t(buf
, 0, time_usec
);
97 _mav_put_uint32_t(buf
, 8, integration_time_us
);
98 _mav_put_float(buf
, 12, integrated_x
);
99 _mav_put_float(buf
, 16, integrated_y
);
100 _mav_put_float(buf
, 20, integrated_xgyro
);
101 _mav_put_float(buf
, 24, integrated_ygyro
);
102 _mav_put_float(buf
, 28, integrated_zgyro
);
103 _mav_put_uint32_t(buf
, 32, time_delta_distance_us
);
104 _mav_put_float(buf
, 36, distance
);
105 _mav_put_int16_t(buf
, 40, temperature
);
106 _mav_put_uint8_t(buf
, 42, sensor_id
);
107 _mav_put_uint8_t(buf
, 43, quality
);
109 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN
);
111 mavlink_hil_optical_flow_t packet
;
112 packet
.time_usec
= time_usec
;
113 packet
.integration_time_us
= integration_time_us
;
114 packet
.integrated_x
= integrated_x
;
115 packet
.integrated_y
= integrated_y
;
116 packet
.integrated_xgyro
= integrated_xgyro
;
117 packet
.integrated_ygyro
= integrated_ygyro
;
118 packet
.integrated_zgyro
= integrated_zgyro
;
119 packet
.time_delta_distance_us
= time_delta_distance_us
;
120 packet
.distance
= distance
;
121 packet
.temperature
= temperature
;
122 packet
.sensor_id
= sensor_id
;
123 packet
.quality
= quality
;
125 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN
);
128 msg
->msgid
= MAVLINK_MSG_ID_HIL_OPTICAL_FLOW
;
129 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC
);
133 * @brief Pack a hil_optical_flow message on a channel
134 * @param system_id ID of this system
135 * @param component_id ID of this component (e.g. 200 for IMU)
136 * @param chan The MAVLink channel this message will be sent over
137 * @param msg The MAVLink message to compress the data into
138 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
139 * @param sensor_id Sensor ID
140 * @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
141 * @param integrated_x [rad] 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.)
142 * @param integrated_y [rad] 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.)
143 * @param integrated_xgyro [rad] RH rotation around X axis
144 * @param integrated_ygyro [rad] RH rotation around Y axis
145 * @param integrated_zgyro [rad] RH rotation around Z axis
146 * @param temperature [cdegC] Temperature
147 * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
148 * @param time_delta_distance_us [us] Time since the distance was sampled.
149 * @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.
150 * @return length of the message in bytes (excluding serial stream start sign)
152 static inline uint16_t mavlink_msg_hil_optical_flow_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
153 mavlink_message_t
* msg
,
154 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
)
156 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
157 char buf
[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN
];
158 _mav_put_uint64_t(buf
, 0, time_usec
);
159 _mav_put_uint32_t(buf
, 8, integration_time_us
);
160 _mav_put_float(buf
, 12, integrated_x
);
161 _mav_put_float(buf
, 16, integrated_y
);
162 _mav_put_float(buf
, 20, integrated_xgyro
);
163 _mav_put_float(buf
, 24, integrated_ygyro
);
164 _mav_put_float(buf
, 28, integrated_zgyro
);
165 _mav_put_uint32_t(buf
, 32, time_delta_distance_us
);
166 _mav_put_float(buf
, 36, distance
);
167 _mav_put_int16_t(buf
, 40, temperature
);
168 _mav_put_uint8_t(buf
, 42, sensor_id
);
169 _mav_put_uint8_t(buf
, 43, quality
);
171 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN
);
173 mavlink_hil_optical_flow_t packet
;
174 packet
.time_usec
= time_usec
;
175 packet
.integration_time_us
= integration_time_us
;
176 packet
.integrated_x
= integrated_x
;
177 packet
.integrated_y
= integrated_y
;
178 packet
.integrated_xgyro
= integrated_xgyro
;
179 packet
.integrated_ygyro
= integrated_ygyro
;
180 packet
.integrated_zgyro
= integrated_zgyro
;
181 packet
.time_delta_distance_us
= time_delta_distance_us
;
182 packet
.distance
= distance
;
183 packet
.temperature
= temperature
;
184 packet
.sensor_id
= sensor_id
;
185 packet
.quality
= quality
;
187 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN
);
190 msg
->msgid
= MAVLINK_MSG_ID_HIL_OPTICAL_FLOW
;
191 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC
);
195 * @brief Encode a hil_optical_flow struct
197 * @param system_id ID of this system
198 * @param component_id ID of this component (e.g. 200 for IMU)
199 * @param msg The MAVLink message to compress the data into
200 * @param hil_optical_flow C-struct to read the message contents from
202 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
)
204 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
);
208 * @brief Encode a hil_optical_flow struct on a channel
210 * @param system_id ID of this system
211 * @param component_id ID of this component (e.g. 200 for IMU)
212 * @param chan The MAVLink channel this message will be sent over
213 * @param msg The MAVLink message to compress the data into
214 * @param hil_optical_flow C-struct to read the message contents from
216 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
)
218 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
);
222 * @brief Send a hil_optical_flow message
223 * @param chan MAVLink channel to send the message
225 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
226 * @param sensor_id Sensor ID
227 * @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
228 * @param integrated_x [rad] 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.)
229 * @param integrated_y [rad] 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.)
230 * @param integrated_xgyro [rad] RH rotation around X axis
231 * @param integrated_ygyro [rad] RH rotation around Y axis
232 * @param integrated_zgyro [rad] RH rotation around Z axis
233 * @param temperature [cdegC] Temperature
234 * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
235 * @param time_delta_distance_us [us] Time since the distance was sampled.
236 * @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.
238 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
240 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
)
242 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
243 char buf
[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN
];
244 _mav_put_uint64_t(buf
, 0, time_usec
);
245 _mav_put_uint32_t(buf
, 8, integration_time_us
);
246 _mav_put_float(buf
, 12, integrated_x
);
247 _mav_put_float(buf
, 16, integrated_y
);
248 _mav_put_float(buf
, 20, integrated_xgyro
);
249 _mav_put_float(buf
, 24, integrated_ygyro
);
250 _mav_put_float(buf
, 28, integrated_zgyro
);
251 _mav_put_uint32_t(buf
, 32, time_delta_distance_us
);
252 _mav_put_float(buf
, 36, distance
);
253 _mav_put_int16_t(buf
, 40, temperature
);
254 _mav_put_uint8_t(buf
, 42, sensor_id
);
255 _mav_put_uint8_t(buf
, 43, quality
);
257 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW
, buf
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC
);
259 mavlink_hil_optical_flow_t packet
;
260 packet
.time_usec
= time_usec
;
261 packet
.integration_time_us
= integration_time_us
;
262 packet
.integrated_x
= integrated_x
;
263 packet
.integrated_y
= integrated_y
;
264 packet
.integrated_xgyro
= integrated_xgyro
;
265 packet
.integrated_ygyro
= integrated_ygyro
;
266 packet
.integrated_zgyro
= integrated_zgyro
;
267 packet
.time_delta_distance_us
= time_delta_distance_us
;
268 packet
.distance
= distance
;
269 packet
.temperature
= temperature
;
270 packet
.sensor_id
= sensor_id
;
271 packet
.quality
= quality
;
273 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW
, (const char *)&packet
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC
);
278 * @brief Send a hil_optical_flow message
279 * @param chan MAVLink channel to send the message
280 * @param struct The MAVLink struct to serialize
282 static inline void mavlink_msg_hil_optical_flow_send_struct(mavlink_channel_t chan
, const mavlink_hil_optical_flow_t
* hil_optical_flow
)
284 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
285 mavlink_msg_hil_optical_flow_send(chan
, 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
);
287 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW
, (const char *)hil_optical_flow
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC
);
291 #if MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
293 This varient of _send() can be used to save stack space by re-using
294 memory from the receive buffer. The caller provides a
295 mavlink_message_t which is the size of a full mavlink message. This
296 is usually the receive buffer for the channel, and allows a reply to an
297 incoming message with minimum stack space usage.
299 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
)
301 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
302 char *buf
= (char *)msgbuf
;
303 _mav_put_uint64_t(buf
, 0, time_usec
);
304 _mav_put_uint32_t(buf
, 8, integration_time_us
);
305 _mav_put_float(buf
, 12, integrated_x
);
306 _mav_put_float(buf
, 16, integrated_y
);
307 _mav_put_float(buf
, 20, integrated_xgyro
);
308 _mav_put_float(buf
, 24, integrated_ygyro
);
309 _mav_put_float(buf
, 28, integrated_zgyro
);
310 _mav_put_uint32_t(buf
, 32, time_delta_distance_us
);
311 _mav_put_float(buf
, 36, distance
);
312 _mav_put_int16_t(buf
, 40, temperature
);
313 _mav_put_uint8_t(buf
, 42, sensor_id
);
314 _mav_put_uint8_t(buf
, 43, quality
);
316 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW
, buf
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC
);
318 mavlink_hil_optical_flow_t
*packet
= (mavlink_hil_optical_flow_t
*)msgbuf
;
319 packet
->time_usec
= time_usec
;
320 packet
->integration_time_us
= integration_time_us
;
321 packet
->integrated_x
= integrated_x
;
322 packet
->integrated_y
= integrated_y
;
323 packet
->integrated_xgyro
= integrated_xgyro
;
324 packet
->integrated_ygyro
= integrated_ygyro
;
325 packet
->integrated_zgyro
= integrated_zgyro
;
326 packet
->time_delta_distance_us
= time_delta_distance_us
;
327 packet
->distance
= distance
;
328 packet
->temperature
= temperature
;
329 packet
->sensor_id
= sensor_id
;
330 packet
->quality
= quality
;
332 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW
, (const char *)packet
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN
, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC
);
339 // MESSAGE HIL_OPTICAL_FLOW UNPACKING
343 * @brief Get field time_usec from hil_optical_flow message
345 * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
347 static inline uint64_t mavlink_msg_hil_optical_flow_get_time_usec(const mavlink_message_t
* msg
)
349 return _MAV_RETURN_uint64_t(msg
, 0);
353 * @brief Get field sensor_id from hil_optical_flow message
357 static inline uint8_t mavlink_msg_hil_optical_flow_get_sensor_id(const mavlink_message_t
* msg
)
359 return _MAV_RETURN_uint8_t(msg
, 42);
363 * @brief Get field integration_time_us from hil_optical_flow message
365 * @return [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
367 static inline uint32_t mavlink_msg_hil_optical_flow_get_integration_time_us(const mavlink_message_t
* msg
)
369 return _MAV_RETURN_uint32_t(msg
, 8);
373 * @brief Get field integrated_x from hil_optical_flow message
375 * @return [rad] 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.)
377 static inline float mavlink_msg_hil_optical_flow_get_integrated_x(const mavlink_message_t
* msg
)
379 return _MAV_RETURN_float(msg
, 12);
383 * @brief Get field integrated_y from hil_optical_flow message
385 * @return [rad] 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.)
387 static inline float mavlink_msg_hil_optical_flow_get_integrated_y(const mavlink_message_t
* msg
)
389 return _MAV_RETURN_float(msg
, 16);
393 * @brief Get field integrated_xgyro from hil_optical_flow message
395 * @return [rad] RH rotation around X axis
397 static inline float mavlink_msg_hil_optical_flow_get_integrated_xgyro(const mavlink_message_t
* msg
)
399 return _MAV_RETURN_float(msg
, 20);
403 * @brief Get field integrated_ygyro from hil_optical_flow message
405 * @return [rad] RH rotation around Y axis
407 static inline float mavlink_msg_hil_optical_flow_get_integrated_ygyro(const mavlink_message_t
* msg
)
409 return _MAV_RETURN_float(msg
, 24);
413 * @brief Get field integrated_zgyro from hil_optical_flow message
415 * @return [rad] RH rotation around Z axis
417 static inline float mavlink_msg_hil_optical_flow_get_integrated_zgyro(const mavlink_message_t
* msg
)
419 return _MAV_RETURN_float(msg
, 28);
423 * @brief Get field temperature from hil_optical_flow message
425 * @return [cdegC] Temperature
427 static inline int16_t mavlink_msg_hil_optical_flow_get_temperature(const mavlink_message_t
* msg
)
429 return _MAV_RETURN_int16_t(msg
, 40);
433 * @brief Get field quality from hil_optical_flow message
435 * @return Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
437 static inline uint8_t mavlink_msg_hil_optical_flow_get_quality(const mavlink_message_t
* msg
)
439 return _MAV_RETURN_uint8_t(msg
, 43);
443 * @brief Get field time_delta_distance_us from hil_optical_flow message
445 * @return [us] Time since the distance was sampled.
447 static inline uint32_t mavlink_msg_hil_optical_flow_get_time_delta_distance_us(const mavlink_message_t
* msg
)
449 return _MAV_RETURN_uint32_t(msg
, 32);
453 * @brief Get field distance from hil_optical_flow message
455 * @return [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.
457 static inline float mavlink_msg_hil_optical_flow_get_distance(const mavlink_message_t
* msg
)
459 return _MAV_RETURN_float(msg
, 36);
463 * @brief Decode a hil_optical_flow message into a struct
465 * @param msg The message to decode
466 * @param hil_optical_flow C-struct to decode the message contents into
468 static inline void mavlink_msg_hil_optical_flow_decode(const mavlink_message_t
* msg
, mavlink_hil_optical_flow_t
* hil_optical_flow
)
470 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
471 hil_optical_flow
->time_usec
= mavlink_msg_hil_optical_flow_get_time_usec(msg
);
472 hil_optical_flow
->integration_time_us
= mavlink_msg_hil_optical_flow_get_integration_time_us(msg
);
473 hil_optical_flow
->integrated_x
= mavlink_msg_hil_optical_flow_get_integrated_x(msg
);
474 hil_optical_flow
->integrated_y
= mavlink_msg_hil_optical_flow_get_integrated_y(msg
);
475 hil_optical_flow
->integrated_xgyro
= mavlink_msg_hil_optical_flow_get_integrated_xgyro(msg
);
476 hil_optical_flow
->integrated_ygyro
= mavlink_msg_hil_optical_flow_get_integrated_ygyro(msg
);
477 hil_optical_flow
->integrated_zgyro
= mavlink_msg_hil_optical_flow_get_integrated_zgyro(msg
);
478 hil_optical_flow
->time_delta_distance_us
= mavlink_msg_hil_optical_flow_get_time_delta_distance_us(msg
);
479 hil_optical_flow
->distance
= mavlink_msg_hil_optical_flow_get_distance(msg
);
480 hil_optical_flow
->temperature
= mavlink_msg_hil_optical_flow_get_temperature(msg
);
481 hil_optical_flow
->sensor_id
= mavlink_msg_hil_optical_flow_get_sensor_id(msg
);
482 hil_optical_flow
->quality
= mavlink_msg_hil_optical_flow_get_quality(msg
);
484 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN
? msg
->len
: MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN
;
485 memset(hil_optical_flow
, 0, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN
);
486 memcpy(hil_optical_flow
, _MAV_PAYLOAD(msg
), len
);