2 // MESSAGE HIGH_LATENCY2 PACKING
4 #define MAVLINK_MSG_ID_HIGH_LATENCY2 235
7 typedef struct __mavlink_high_latency2_t
{
8 uint32_t timestamp
; /*< [ms] Timestamp (milliseconds since boot or Unix epoch)*/
9 int32_t latitude
; /*< [degE7] Latitude*/
10 int32_t longitude
; /*< [degE7] Longitude*/
11 uint16_t custom_mode
; /*< A bitfield for use for autopilot-specific flags (2 byte version).*/
12 int16_t altitude
; /*< [m] Altitude above mean sea level*/
13 int16_t target_altitude
; /*< [m] Altitude setpoint*/
14 uint16_t target_distance
; /*< [dam] Distance to target waypoint or position*/
15 uint16_t wp_num
; /*< Current waypoint number*/
16 uint16_t failure_flags
; /*< Bitmap of failure flags.*/
17 uint8_t type
; /*< Type of the MAV (quadrotor, helicopter, etc.)*/
18 uint8_t autopilot
; /*< Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.*/
19 uint8_t heading
; /*< [deg/2] Heading*/
20 uint8_t target_heading
; /*< [deg/2] Heading setpoint*/
21 uint8_t throttle
; /*< [%] Throttle*/
22 uint8_t airspeed
; /*< [m/s*5] Airspeed*/
23 uint8_t airspeed_sp
; /*< [m/s*5] Airspeed setpoint*/
24 uint8_t groundspeed
; /*< [m/s*5] Groundspeed*/
25 uint8_t windspeed
; /*< [m/s*5] Windspeed*/
26 uint8_t wind_heading
; /*< [deg/2] Wind heading*/
27 uint8_t eph
; /*< [dm] Maximum error horizontal position since last message*/
28 uint8_t epv
; /*< [dm] Maximum error vertical position since last message*/
29 int8_t temperature_air
; /*< [degC] Air temperature from airspeed sensor*/
30 int8_t climb_rate
; /*< [dm/s] Maximum climb rate magnitude since last message*/
31 int8_t battery
; /*< [%] Battery level (-1 if field not provided).*/
32 int8_t custom0
; /*< Field for custom payload.*/
33 int8_t custom1
; /*< Field for custom payload.*/
34 int8_t custom2
; /*< Field for custom payload.*/
35 } mavlink_high_latency2_t
;
37 #define MAVLINK_MSG_ID_HIGH_LATENCY2_LEN 42
38 #define MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN 42
39 #define MAVLINK_MSG_ID_235_LEN 42
40 #define MAVLINK_MSG_ID_235_MIN_LEN 42
42 #define MAVLINK_MSG_ID_HIGH_LATENCY2_CRC 179
43 #define MAVLINK_MSG_ID_235_CRC 179
47 #if MAVLINK_COMMAND_24BIT
48 #define MAVLINK_MESSAGE_INFO_HIGH_LATENCY2 { \
52 { { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency2_t, timestamp) }, \
53 { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_high_latency2_t, type) }, \
54 { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_high_latency2_t, autopilot) }, \
55 { "custom_mode", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_high_latency2_t, custom_mode) }, \
56 { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency2_t, latitude) }, \
57 { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency2_t, longitude) }, \
58 { "altitude", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_high_latency2_t, altitude) }, \
59 { "target_altitude", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_high_latency2_t, target_altitude) }, \
60 { "heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency2_t, heading) }, \
61 { "target_heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency2_t, target_heading) }, \
62 { "target_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_high_latency2_t, target_distance) }, \
63 { "throttle", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_high_latency2_t, throttle) }, \
64 { "airspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_high_latency2_t, airspeed) }, \
65 { "airspeed_sp", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_high_latency2_t, airspeed_sp) }, \
66 { "groundspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_high_latency2_t, groundspeed) }, \
67 { "windspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_high_latency2_t, windspeed) }, \
68 { "wind_heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_high_latency2_t, wind_heading) }, \
69 { "eph", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_high_latency2_t, eph) }, \
70 { "epv", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_high_latency2_t, epv) }, \
71 { "temperature_air", NULL, MAVLINK_TYPE_INT8_T, 0, 36, offsetof(mavlink_high_latency2_t, temperature_air) }, \
72 { "climb_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 37, offsetof(mavlink_high_latency2_t, climb_rate) }, \
73 { "battery", NULL, MAVLINK_TYPE_INT8_T, 0, 38, offsetof(mavlink_high_latency2_t, battery) }, \
74 { "wp_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_high_latency2_t, wp_num) }, \
75 { "failure_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_high_latency2_t, failure_flags) }, \
76 { "custom0", NULL, MAVLINK_TYPE_INT8_T, 0, 39, offsetof(mavlink_high_latency2_t, custom0) }, \
77 { "custom1", NULL, MAVLINK_TYPE_INT8_T, 0, 40, offsetof(mavlink_high_latency2_t, custom1) }, \
78 { "custom2", NULL, MAVLINK_TYPE_INT8_T, 0, 41, offsetof(mavlink_high_latency2_t, custom2) }, \
82 #define MAVLINK_MESSAGE_INFO_HIGH_LATENCY2 { \
85 { { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency2_t, timestamp) }, \
86 { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_high_latency2_t, type) }, \
87 { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_high_latency2_t, autopilot) }, \
88 { "custom_mode", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_high_latency2_t, custom_mode) }, \
89 { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency2_t, latitude) }, \
90 { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency2_t, longitude) }, \
91 { "altitude", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_high_latency2_t, altitude) }, \
92 { "target_altitude", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_high_latency2_t, target_altitude) }, \
93 { "heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency2_t, heading) }, \
94 { "target_heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency2_t, target_heading) }, \
95 { "target_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_high_latency2_t, target_distance) }, \
96 { "throttle", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_high_latency2_t, throttle) }, \
97 { "airspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_high_latency2_t, airspeed) }, \
98 { "airspeed_sp", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_high_latency2_t, airspeed_sp) }, \
99 { "groundspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_high_latency2_t, groundspeed) }, \
100 { "windspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_high_latency2_t, windspeed) }, \
101 { "wind_heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_high_latency2_t, wind_heading) }, \
102 { "eph", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_high_latency2_t, eph) }, \
103 { "epv", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_high_latency2_t, epv) }, \
104 { "temperature_air", NULL, MAVLINK_TYPE_INT8_T, 0, 36, offsetof(mavlink_high_latency2_t, temperature_air) }, \
105 { "climb_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 37, offsetof(mavlink_high_latency2_t, climb_rate) }, \
106 { "battery", NULL, MAVLINK_TYPE_INT8_T, 0, 38, offsetof(mavlink_high_latency2_t, battery) }, \
107 { "wp_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_high_latency2_t, wp_num) }, \
108 { "failure_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_high_latency2_t, failure_flags) }, \
109 { "custom0", NULL, MAVLINK_TYPE_INT8_T, 0, 39, offsetof(mavlink_high_latency2_t, custom0) }, \
110 { "custom1", NULL, MAVLINK_TYPE_INT8_T, 0, 40, offsetof(mavlink_high_latency2_t, custom1) }, \
111 { "custom2", NULL, MAVLINK_TYPE_INT8_T, 0, 41, offsetof(mavlink_high_latency2_t, custom2) }, \
117 * @brief Pack a high_latency2 message
118 * @param system_id ID of this system
119 * @param component_id ID of this component (e.g. 200 for IMU)
120 * @param msg The MAVLink message to compress the data into
122 * @param timestamp [ms] Timestamp (milliseconds since boot or Unix epoch)
123 * @param type Type of the MAV (quadrotor, helicopter, etc.)
124 * @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
125 * @param custom_mode A bitfield for use for autopilot-specific flags (2 byte version).
126 * @param latitude [degE7] Latitude
127 * @param longitude [degE7] Longitude
128 * @param altitude [m] Altitude above mean sea level
129 * @param target_altitude [m] Altitude setpoint
130 * @param heading [deg/2] Heading
131 * @param target_heading [deg/2] Heading setpoint
132 * @param target_distance [dam] Distance to target waypoint or position
133 * @param throttle [%] Throttle
134 * @param airspeed [m/s*5] Airspeed
135 * @param airspeed_sp [m/s*5] Airspeed setpoint
136 * @param groundspeed [m/s*5] Groundspeed
137 * @param windspeed [m/s*5] Windspeed
138 * @param wind_heading [deg/2] Wind heading
139 * @param eph [dm] Maximum error horizontal position since last message
140 * @param epv [dm] Maximum error vertical position since last message
141 * @param temperature_air [degC] Air temperature from airspeed sensor
142 * @param climb_rate [dm/s] Maximum climb rate magnitude since last message
143 * @param battery [%] Battery level (-1 if field not provided).
144 * @param wp_num Current waypoint number
145 * @param failure_flags Bitmap of failure flags.
146 * @param custom0 Field for custom payload.
147 * @param custom1 Field for custom payload.
148 * @param custom2 Field for custom payload.
149 * @return length of the message in bytes (excluding serial stream start sign)
151 static inline uint16_t mavlink_msg_high_latency2_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
152 uint32_t timestamp
, uint8_t type
, uint8_t autopilot
, uint16_t custom_mode
, int32_t latitude
, int32_t longitude
, int16_t altitude
, int16_t target_altitude
, uint8_t heading
, uint8_t target_heading
, uint16_t target_distance
, uint8_t throttle
, uint8_t airspeed
, uint8_t airspeed_sp
, uint8_t groundspeed
, uint8_t windspeed
, uint8_t wind_heading
, uint8_t eph
, uint8_t epv
, int8_t temperature_air
, int8_t climb_rate
, int8_t battery
, uint16_t wp_num
, uint16_t failure_flags
, int8_t custom0
, int8_t custom1
, int8_t custom2
)
154 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
155 char buf
[MAVLINK_MSG_ID_HIGH_LATENCY2_LEN
];
156 _mav_put_uint32_t(buf
, 0, timestamp
);
157 _mav_put_int32_t(buf
, 4, latitude
);
158 _mav_put_int32_t(buf
, 8, longitude
);
159 _mav_put_uint16_t(buf
, 12, custom_mode
);
160 _mav_put_int16_t(buf
, 14, altitude
);
161 _mav_put_int16_t(buf
, 16, target_altitude
);
162 _mav_put_uint16_t(buf
, 18, target_distance
);
163 _mav_put_uint16_t(buf
, 20, wp_num
);
164 _mav_put_uint16_t(buf
, 22, failure_flags
);
165 _mav_put_uint8_t(buf
, 24, type
);
166 _mav_put_uint8_t(buf
, 25, autopilot
);
167 _mav_put_uint8_t(buf
, 26, heading
);
168 _mav_put_uint8_t(buf
, 27, target_heading
);
169 _mav_put_uint8_t(buf
, 28, throttle
);
170 _mav_put_uint8_t(buf
, 29, airspeed
);
171 _mav_put_uint8_t(buf
, 30, airspeed_sp
);
172 _mav_put_uint8_t(buf
, 31, groundspeed
);
173 _mav_put_uint8_t(buf
, 32, windspeed
);
174 _mav_put_uint8_t(buf
, 33, wind_heading
);
175 _mav_put_uint8_t(buf
, 34, eph
);
176 _mav_put_uint8_t(buf
, 35, epv
);
177 _mav_put_int8_t(buf
, 36, temperature_air
);
178 _mav_put_int8_t(buf
, 37, climb_rate
);
179 _mav_put_int8_t(buf
, 38, battery
);
180 _mav_put_int8_t(buf
, 39, custom0
);
181 _mav_put_int8_t(buf
, 40, custom1
);
182 _mav_put_int8_t(buf
, 41, custom2
);
184 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN
);
186 mavlink_high_latency2_t packet
;
187 packet
.timestamp
= timestamp
;
188 packet
.latitude
= latitude
;
189 packet
.longitude
= longitude
;
190 packet
.custom_mode
= custom_mode
;
191 packet
.altitude
= altitude
;
192 packet
.target_altitude
= target_altitude
;
193 packet
.target_distance
= target_distance
;
194 packet
.wp_num
= wp_num
;
195 packet
.failure_flags
= failure_flags
;
197 packet
.autopilot
= autopilot
;
198 packet
.heading
= heading
;
199 packet
.target_heading
= target_heading
;
200 packet
.throttle
= throttle
;
201 packet
.airspeed
= airspeed
;
202 packet
.airspeed_sp
= airspeed_sp
;
203 packet
.groundspeed
= groundspeed
;
204 packet
.windspeed
= windspeed
;
205 packet
.wind_heading
= wind_heading
;
208 packet
.temperature_air
= temperature_air
;
209 packet
.climb_rate
= climb_rate
;
210 packet
.battery
= battery
;
211 packet
.custom0
= custom0
;
212 packet
.custom1
= custom1
;
213 packet
.custom2
= custom2
;
215 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN
);
218 msg
->msgid
= MAVLINK_MSG_ID_HIGH_LATENCY2
;
219 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN
, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN
, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC
);
223 * @brief Pack a high_latency2 message on a channel
224 * @param system_id ID of this system
225 * @param component_id ID of this component (e.g. 200 for IMU)
226 * @param chan The MAVLink channel this message will be sent over
227 * @param msg The MAVLink message to compress the data into
228 * @param timestamp [ms] Timestamp (milliseconds since boot or Unix epoch)
229 * @param type Type of the MAV (quadrotor, helicopter, etc.)
230 * @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
231 * @param custom_mode A bitfield for use for autopilot-specific flags (2 byte version).
232 * @param latitude [degE7] Latitude
233 * @param longitude [degE7] Longitude
234 * @param altitude [m] Altitude above mean sea level
235 * @param target_altitude [m] Altitude setpoint
236 * @param heading [deg/2] Heading
237 * @param target_heading [deg/2] Heading setpoint
238 * @param target_distance [dam] Distance to target waypoint or position
239 * @param throttle [%] Throttle
240 * @param airspeed [m/s*5] Airspeed
241 * @param airspeed_sp [m/s*5] Airspeed setpoint
242 * @param groundspeed [m/s*5] Groundspeed
243 * @param windspeed [m/s*5] Windspeed
244 * @param wind_heading [deg/2] Wind heading
245 * @param eph [dm] Maximum error horizontal position since last message
246 * @param epv [dm] Maximum error vertical position since last message
247 * @param temperature_air [degC] Air temperature from airspeed sensor
248 * @param climb_rate [dm/s] Maximum climb rate magnitude since last message
249 * @param battery [%] Battery level (-1 if field not provided).
250 * @param wp_num Current waypoint number
251 * @param failure_flags Bitmap of failure flags.
252 * @param custom0 Field for custom payload.
253 * @param custom1 Field for custom payload.
254 * @param custom2 Field for custom payload.
255 * @return length of the message in bytes (excluding serial stream start sign)
257 static inline uint16_t mavlink_msg_high_latency2_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
258 mavlink_message_t
* msg
,
259 uint32_t timestamp
,uint8_t type
,uint8_t autopilot
,uint16_t custom_mode
,int32_t latitude
,int32_t longitude
,int16_t altitude
,int16_t target_altitude
,uint8_t heading
,uint8_t target_heading
,uint16_t target_distance
,uint8_t throttle
,uint8_t airspeed
,uint8_t airspeed_sp
,uint8_t groundspeed
,uint8_t windspeed
,uint8_t wind_heading
,uint8_t eph
,uint8_t epv
,int8_t temperature_air
,int8_t climb_rate
,int8_t battery
,uint16_t wp_num
,uint16_t failure_flags
,int8_t custom0
,int8_t custom1
,int8_t custom2
)
261 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
262 char buf
[MAVLINK_MSG_ID_HIGH_LATENCY2_LEN
];
263 _mav_put_uint32_t(buf
, 0, timestamp
);
264 _mav_put_int32_t(buf
, 4, latitude
);
265 _mav_put_int32_t(buf
, 8, longitude
);
266 _mav_put_uint16_t(buf
, 12, custom_mode
);
267 _mav_put_int16_t(buf
, 14, altitude
);
268 _mav_put_int16_t(buf
, 16, target_altitude
);
269 _mav_put_uint16_t(buf
, 18, target_distance
);
270 _mav_put_uint16_t(buf
, 20, wp_num
);
271 _mav_put_uint16_t(buf
, 22, failure_flags
);
272 _mav_put_uint8_t(buf
, 24, type
);
273 _mav_put_uint8_t(buf
, 25, autopilot
);
274 _mav_put_uint8_t(buf
, 26, heading
);
275 _mav_put_uint8_t(buf
, 27, target_heading
);
276 _mav_put_uint8_t(buf
, 28, throttle
);
277 _mav_put_uint8_t(buf
, 29, airspeed
);
278 _mav_put_uint8_t(buf
, 30, airspeed_sp
);
279 _mav_put_uint8_t(buf
, 31, groundspeed
);
280 _mav_put_uint8_t(buf
, 32, windspeed
);
281 _mav_put_uint8_t(buf
, 33, wind_heading
);
282 _mav_put_uint8_t(buf
, 34, eph
);
283 _mav_put_uint8_t(buf
, 35, epv
);
284 _mav_put_int8_t(buf
, 36, temperature_air
);
285 _mav_put_int8_t(buf
, 37, climb_rate
);
286 _mav_put_int8_t(buf
, 38, battery
);
287 _mav_put_int8_t(buf
, 39, custom0
);
288 _mav_put_int8_t(buf
, 40, custom1
);
289 _mav_put_int8_t(buf
, 41, custom2
);
291 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN
);
293 mavlink_high_latency2_t packet
;
294 packet
.timestamp
= timestamp
;
295 packet
.latitude
= latitude
;
296 packet
.longitude
= longitude
;
297 packet
.custom_mode
= custom_mode
;
298 packet
.altitude
= altitude
;
299 packet
.target_altitude
= target_altitude
;
300 packet
.target_distance
= target_distance
;
301 packet
.wp_num
= wp_num
;
302 packet
.failure_flags
= failure_flags
;
304 packet
.autopilot
= autopilot
;
305 packet
.heading
= heading
;
306 packet
.target_heading
= target_heading
;
307 packet
.throttle
= throttle
;
308 packet
.airspeed
= airspeed
;
309 packet
.airspeed_sp
= airspeed_sp
;
310 packet
.groundspeed
= groundspeed
;
311 packet
.windspeed
= windspeed
;
312 packet
.wind_heading
= wind_heading
;
315 packet
.temperature_air
= temperature_air
;
316 packet
.climb_rate
= climb_rate
;
317 packet
.battery
= battery
;
318 packet
.custom0
= custom0
;
319 packet
.custom1
= custom1
;
320 packet
.custom2
= custom2
;
322 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN
);
325 msg
->msgid
= MAVLINK_MSG_ID_HIGH_LATENCY2
;
326 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN
, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN
, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC
);
330 * @brief Encode a high_latency2 struct
332 * @param system_id ID of this system
333 * @param component_id ID of this component (e.g. 200 for IMU)
334 * @param msg The MAVLink message to compress the data into
335 * @param high_latency2 C-struct to read the message contents from
337 static inline uint16_t mavlink_msg_high_latency2_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
, const mavlink_high_latency2_t
* high_latency2
)
339 return mavlink_msg_high_latency2_pack(system_id
, component_id
, msg
, high_latency2
->timestamp
, high_latency2
->type
, high_latency2
->autopilot
, high_latency2
->custom_mode
, high_latency2
->latitude
, high_latency2
->longitude
, high_latency2
->altitude
, high_latency2
->target_altitude
, high_latency2
->heading
, high_latency2
->target_heading
, high_latency2
->target_distance
, high_latency2
->throttle
, high_latency2
->airspeed
, high_latency2
->airspeed_sp
, high_latency2
->groundspeed
, high_latency2
->windspeed
, high_latency2
->wind_heading
, high_latency2
->eph
, high_latency2
->epv
, high_latency2
->temperature_air
, high_latency2
->climb_rate
, high_latency2
->battery
, high_latency2
->wp_num
, high_latency2
->failure_flags
, high_latency2
->custom0
, high_latency2
->custom1
, high_latency2
->custom2
);
343 * @brief Encode a high_latency2 struct on a channel
345 * @param system_id ID of this system
346 * @param component_id ID of this component (e.g. 200 for IMU)
347 * @param chan The MAVLink channel this message will be sent over
348 * @param msg The MAVLink message to compress the data into
349 * @param high_latency2 C-struct to read the message contents from
351 static inline uint16_t mavlink_msg_high_latency2_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_high_latency2_t
* high_latency2
)
353 return mavlink_msg_high_latency2_pack_chan(system_id
, component_id
, chan
, msg
, high_latency2
->timestamp
, high_latency2
->type
, high_latency2
->autopilot
, high_latency2
->custom_mode
, high_latency2
->latitude
, high_latency2
->longitude
, high_latency2
->altitude
, high_latency2
->target_altitude
, high_latency2
->heading
, high_latency2
->target_heading
, high_latency2
->target_distance
, high_latency2
->throttle
, high_latency2
->airspeed
, high_latency2
->airspeed_sp
, high_latency2
->groundspeed
, high_latency2
->windspeed
, high_latency2
->wind_heading
, high_latency2
->eph
, high_latency2
->epv
, high_latency2
->temperature_air
, high_latency2
->climb_rate
, high_latency2
->battery
, high_latency2
->wp_num
, high_latency2
->failure_flags
, high_latency2
->custom0
, high_latency2
->custom1
, high_latency2
->custom2
);
357 * @brief Send a high_latency2 message
358 * @param chan MAVLink channel to send the message
360 * @param timestamp [ms] Timestamp (milliseconds since boot or Unix epoch)
361 * @param type Type of the MAV (quadrotor, helicopter, etc.)
362 * @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
363 * @param custom_mode A bitfield for use for autopilot-specific flags (2 byte version).
364 * @param latitude [degE7] Latitude
365 * @param longitude [degE7] Longitude
366 * @param altitude [m] Altitude above mean sea level
367 * @param target_altitude [m] Altitude setpoint
368 * @param heading [deg/2] Heading
369 * @param target_heading [deg/2] Heading setpoint
370 * @param target_distance [dam] Distance to target waypoint or position
371 * @param throttle [%] Throttle
372 * @param airspeed [m/s*5] Airspeed
373 * @param airspeed_sp [m/s*5] Airspeed setpoint
374 * @param groundspeed [m/s*5] Groundspeed
375 * @param windspeed [m/s*5] Windspeed
376 * @param wind_heading [deg/2] Wind heading
377 * @param eph [dm] Maximum error horizontal position since last message
378 * @param epv [dm] Maximum error vertical position since last message
379 * @param temperature_air [degC] Air temperature from airspeed sensor
380 * @param climb_rate [dm/s] Maximum climb rate magnitude since last message
381 * @param battery [%] Battery level (-1 if field not provided).
382 * @param wp_num Current waypoint number
383 * @param failure_flags Bitmap of failure flags.
384 * @param custom0 Field for custom payload.
385 * @param custom1 Field for custom payload.
386 * @param custom2 Field for custom payload.
388 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
390 static inline void mavlink_msg_high_latency2_send(mavlink_channel_t chan
, uint32_t timestamp
, uint8_t type
, uint8_t autopilot
, uint16_t custom_mode
, int32_t latitude
, int32_t longitude
, int16_t altitude
, int16_t target_altitude
, uint8_t heading
, uint8_t target_heading
, uint16_t target_distance
, uint8_t throttle
, uint8_t airspeed
, uint8_t airspeed_sp
, uint8_t groundspeed
, uint8_t windspeed
, uint8_t wind_heading
, uint8_t eph
, uint8_t epv
, int8_t temperature_air
, int8_t climb_rate
, int8_t battery
, uint16_t wp_num
, uint16_t failure_flags
, int8_t custom0
, int8_t custom1
, int8_t custom2
)
392 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
393 char buf
[MAVLINK_MSG_ID_HIGH_LATENCY2_LEN
];
394 _mav_put_uint32_t(buf
, 0, timestamp
);
395 _mav_put_int32_t(buf
, 4, latitude
);
396 _mav_put_int32_t(buf
, 8, longitude
);
397 _mav_put_uint16_t(buf
, 12, custom_mode
);
398 _mav_put_int16_t(buf
, 14, altitude
);
399 _mav_put_int16_t(buf
, 16, target_altitude
);
400 _mav_put_uint16_t(buf
, 18, target_distance
);
401 _mav_put_uint16_t(buf
, 20, wp_num
);
402 _mav_put_uint16_t(buf
, 22, failure_flags
);
403 _mav_put_uint8_t(buf
, 24, type
);
404 _mav_put_uint8_t(buf
, 25, autopilot
);
405 _mav_put_uint8_t(buf
, 26, heading
);
406 _mav_put_uint8_t(buf
, 27, target_heading
);
407 _mav_put_uint8_t(buf
, 28, throttle
);
408 _mav_put_uint8_t(buf
, 29, airspeed
);
409 _mav_put_uint8_t(buf
, 30, airspeed_sp
);
410 _mav_put_uint8_t(buf
, 31, groundspeed
);
411 _mav_put_uint8_t(buf
, 32, windspeed
);
412 _mav_put_uint8_t(buf
, 33, wind_heading
);
413 _mav_put_uint8_t(buf
, 34, eph
);
414 _mav_put_uint8_t(buf
, 35, epv
);
415 _mav_put_int8_t(buf
, 36, temperature_air
);
416 _mav_put_int8_t(buf
, 37, climb_rate
);
417 _mav_put_int8_t(buf
, 38, battery
);
418 _mav_put_int8_t(buf
, 39, custom0
);
419 _mav_put_int8_t(buf
, 40, custom1
);
420 _mav_put_int8_t(buf
, 41, custom2
);
422 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIGH_LATENCY2
, buf
, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN
, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN
, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC
);
424 mavlink_high_latency2_t packet
;
425 packet
.timestamp
= timestamp
;
426 packet
.latitude
= latitude
;
427 packet
.longitude
= longitude
;
428 packet
.custom_mode
= custom_mode
;
429 packet
.altitude
= altitude
;
430 packet
.target_altitude
= target_altitude
;
431 packet
.target_distance
= target_distance
;
432 packet
.wp_num
= wp_num
;
433 packet
.failure_flags
= failure_flags
;
435 packet
.autopilot
= autopilot
;
436 packet
.heading
= heading
;
437 packet
.target_heading
= target_heading
;
438 packet
.throttle
= throttle
;
439 packet
.airspeed
= airspeed
;
440 packet
.airspeed_sp
= airspeed_sp
;
441 packet
.groundspeed
= groundspeed
;
442 packet
.windspeed
= windspeed
;
443 packet
.wind_heading
= wind_heading
;
446 packet
.temperature_air
= temperature_air
;
447 packet
.climb_rate
= climb_rate
;
448 packet
.battery
= battery
;
449 packet
.custom0
= custom0
;
450 packet
.custom1
= custom1
;
451 packet
.custom2
= custom2
;
453 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIGH_LATENCY2
, (const char *)&packet
, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN
, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN
, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC
);
458 * @brief Send a high_latency2 message
459 * @param chan MAVLink channel to send the message
460 * @param struct The MAVLink struct to serialize
462 static inline void mavlink_msg_high_latency2_send_struct(mavlink_channel_t chan
, const mavlink_high_latency2_t
* high_latency2
)
464 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
465 mavlink_msg_high_latency2_send(chan
, high_latency2
->timestamp
, high_latency2
->type
, high_latency2
->autopilot
, high_latency2
->custom_mode
, high_latency2
->latitude
, high_latency2
->longitude
, high_latency2
->altitude
, high_latency2
->target_altitude
, high_latency2
->heading
, high_latency2
->target_heading
, high_latency2
->target_distance
, high_latency2
->throttle
, high_latency2
->airspeed
, high_latency2
->airspeed_sp
, high_latency2
->groundspeed
, high_latency2
->windspeed
, high_latency2
->wind_heading
, high_latency2
->eph
, high_latency2
->epv
, high_latency2
->temperature_air
, high_latency2
->climb_rate
, high_latency2
->battery
, high_latency2
->wp_num
, high_latency2
->failure_flags
, high_latency2
->custom0
, high_latency2
->custom1
, high_latency2
->custom2
);
467 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIGH_LATENCY2
, (const char *)high_latency2
, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN
, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN
, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC
);
471 #if MAVLINK_MSG_ID_HIGH_LATENCY2_LEN <= MAVLINK_MAX_PAYLOAD_LEN
473 This varient of _send() can be used to save stack space by re-using
474 memory from the receive buffer. The caller provides a
475 mavlink_message_t which is the size of a full mavlink message. This
476 is usually the receive buffer for the channel, and allows a reply to an
477 incoming message with minimum stack space usage.
479 static inline void mavlink_msg_high_latency2_send_buf(mavlink_message_t
*msgbuf
, mavlink_channel_t chan
, uint32_t timestamp
, uint8_t type
, uint8_t autopilot
, uint16_t custom_mode
, int32_t latitude
, int32_t longitude
, int16_t altitude
, int16_t target_altitude
, uint8_t heading
, uint8_t target_heading
, uint16_t target_distance
, uint8_t throttle
, uint8_t airspeed
, uint8_t airspeed_sp
, uint8_t groundspeed
, uint8_t windspeed
, uint8_t wind_heading
, uint8_t eph
, uint8_t epv
, int8_t temperature_air
, int8_t climb_rate
, int8_t battery
, uint16_t wp_num
, uint16_t failure_flags
, int8_t custom0
, int8_t custom1
, int8_t custom2
)
481 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
482 char *buf
= (char *)msgbuf
;
483 _mav_put_uint32_t(buf
, 0, timestamp
);
484 _mav_put_int32_t(buf
, 4, latitude
);
485 _mav_put_int32_t(buf
, 8, longitude
);
486 _mav_put_uint16_t(buf
, 12, custom_mode
);
487 _mav_put_int16_t(buf
, 14, altitude
);
488 _mav_put_int16_t(buf
, 16, target_altitude
);
489 _mav_put_uint16_t(buf
, 18, target_distance
);
490 _mav_put_uint16_t(buf
, 20, wp_num
);
491 _mav_put_uint16_t(buf
, 22, failure_flags
);
492 _mav_put_uint8_t(buf
, 24, type
);
493 _mav_put_uint8_t(buf
, 25, autopilot
);
494 _mav_put_uint8_t(buf
, 26, heading
);
495 _mav_put_uint8_t(buf
, 27, target_heading
);
496 _mav_put_uint8_t(buf
, 28, throttle
);
497 _mav_put_uint8_t(buf
, 29, airspeed
);
498 _mav_put_uint8_t(buf
, 30, airspeed_sp
);
499 _mav_put_uint8_t(buf
, 31, groundspeed
);
500 _mav_put_uint8_t(buf
, 32, windspeed
);
501 _mav_put_uint8_t(buf
, 33, wind_heading
);
502 _mav_put_uint8_t(buf
, 34, eph
);
503 _mav_put_uint8_t(buf
, 35, epv
);
504 _mav_put_int8_t(buf
, 36, temperature_air
);
505 _mav_put_int8_t(buf
, 37, climb_rate
);
506 _mav_put_int8_t(buf
, 38, battery
);
507 _mav_put_int8_t(buf
, 39, custom0
);
508 _mav_put_int8_t(buf
, 40, custom1
);
509 _mav_put_int8_t(buf
, 41, custom2
);
511 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIGH_LATENCY2
, buf
, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN
, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN
, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC
);
513 mavlink_high_latency2_t
*packet
= (mavlink_high_latency2_t
*)msgbuf
;
514 packet
->timestamp
= timestamp
;
515 packet
->latitude
= latitude
;
516 packet
->longitude
= longitude
;
517 packet
->custom_mode
= custom_mode
;
518 packet
->altitude
= altitude
;
519 packet
->target_altitude
= target_altitude
;
520 packet
->target_distance
= target_distance
;
521 packet
->wp_num
= wp_num
;
522 packet
->failure_flags
= failure_flags
;
524 packet
->autopilot
= autopilot
;
525 packet
->heading
= heading
;
526 packet
->target_heading
= target_heading
;
527 packet
->throttle
= throttle
;
528 packet
->airspeed
= airspeed
;
529 packet
->airspeed_sp
= airspeed_sp
;
530 packet
->groundspeed
= groundspeed
;
531 packet
->windspeed
= windspeed
;
532 packet
->wind_heading
= wind_heading
;
535 packet
->temperature_air
= temperature_air
;
536 packet
->climb_rate
= climb_rate
;
537 packet
->battery
= battery
;
538 packet
->custom0
= custom0
;
539 packet
->custom1
= custom1
;
540 packet
->custom2
= custom2
;
542 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIGH_LATENCY2
, (const char *)packet
, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN
, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN
, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC
);
549 // MESSAGE HIGH_LATENCY2 UNPACKING
553 * @brief Get field timestamp from high_latency2 message
555 * @return [ms] Timestamp (milliseconds since boot or Unix epoch)
557 static inline uint32_t mavlink_msg_high_latency2_get_timestamp(const mavlink_message_t
* msg
)
559 return _MAV_RETURN_uint32_t(msg
, 0);
563 * @brief Get field type from high_latency2 message
565 * @return Type of the MAV (quadrotor, helicopter, etc.)
567 static inline uint8_t mavlink_msg_high_latency2_get_type(const mavlink_message_t
* msg
)
569 return _MAV_RETURN_uint8_t(msg
, 24);
573 * @brief Get field autopilot from high_latency2 message
575 * @return Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
577 static inline uint8_t mavlink_msg_high_latency2_get_autopilot(const mavlink_message_t
* msg
)
579 return _MAV_RETURN_uint8_t(msg
, 25);
583 * @brief Get field custom_mode from high_latency2 message
585 * @return A bitfield for use for autopilot-specific flags (2 byte version).
587 static inline uint16_t mavlink_msg_high_latency2_get_custom_mode(const mavlink_message_t
* msg
)
589 return _MAV_RETURN_uint16_t(msg
, 12);
593 * @brief Get field latitude from high_latency2 message
595 * @return [degE7] Latitude
597 static inline int32_t mavlink_msg_high_latency2_get_latitude(const mavlink_message_t
* msg
)
599 return _MAV_RETURN_int32_t(msg
, 4);
603 * @brief Get field longitude from high_latency2 message
605 * @return [degE7] Longitude
607 static inline int32_t mavlink_msg_high_latency2_get_longitude(const mavlink_message_t
* msg
)
609 return _MAV_RETURN_int32_t(msg
, 8);
613 * @brief Get field altitude from high_latency2 message
615 * @return [m] Altitude above mean sea level
617 static inline int16_t mavlink_msg_high_latency2_get_altitude(const mavlink_message_t
* msg
)
619 return _MAV_RETURN_int16_t(msg
, 14);
623 * @brief Get field target_altitude from high_latency2 message
625 * @return [m] Altitude setpoint
627 static inline int16_t mavlink_msg_high_latency2_get_target_altitude(const mavlink_message_t
* msg
)
629 return _MAV_RETURN_int16_t(msg
, 16);
633 * @brief Get field heading from high_latency2 message
635 * @return [deg/2] Heading
637 static inline uint8_t mavlink_msg_high_latency2_get_heading(const mavlink_message_t
* msg
)
639 return _MAV_RETURN_uint8_t(msg
, 26);
643 * @brief Get field target_heading from high_latency2 message
645 * @return [deg/2] Heading setpoint
647 static inline uint8_t mavlink_msg_high_latency2_get_target_heading(const mavlink_message_t
* msg
)
649 return _MAV_RETURN_uint8_t(msg
, 27);
653 * @brief Get field target_distance from high_latency2 message
655 * @return [dam] Distance to target waypoint or position
657 static inline uint16_t mavlink_msg_high_latency2_get_target_distance(const mavlink_message_t
* msg
)
659 return _MAV_RETURN_uint16_t(msg
, 18);
663 * @brief Get field throttle from high_latency2 message
665 * @return [%] Throttle
667 static inline uint8_t mavlink_msg_high_latency2_get_throttle(const mavlink_message_t
* msg
)
669 return _MAV_RETURN_uint8_t(msg
, 28);
673 * @brief Get field airspeed from high_latency2 message
675 * @return [m/s*5] Airspeed
677 static inline uint8_t mavlink_msg_high_latency2_get_airspeed(const mavlink_message_t
* msg
)
679 return _MAV_RETURN_uint8_t(msg
, 29);
683 * @brief Get field airspeed_sp from high_latency2 message
685 * @return [m/s*5] Airspeed setpoint
687 static inline uint8_t mavlink_msg_high_latency2_get_airspeed_sp(const mavlink_message_t
* msg
)
689 return _MAV_RETURN_uint8_t(msg
, 30);
693 * @brief Get field groundspeed from high_latency2 message
695 * @return [m/s*5] Groundspeed
697 static inline uint8_t mavlink_msg_high_latency2_get_groundspeed(const mavlink_message_t
* msg
)
699 return _MAV_RETURN_uint8_t(msg
, 31);
703 * @brief Get field windspeed from high_latency2 message
705 * @return [m/s*5] Windspeed
707 static inline uint8_t mavlink_msg_high_latency2_get_windspeed(const mavlink_message_t
* msg
)
709 return _MAV_RETURN_uint8_t(msg
, 32);
713 * @brief Get field wind_heading from high_latency2 message
715 * @return [deg/2] Wind heading
717 static inline uint8_t mavlink_msg_high_latency2_get_wind_heading(const mavlink_message_t
* msg
)
719 return _MAV_RETURN_uint8_t(msg
, 33);
723 * @brief Get field eph from high_latency2 message
725 * @return [dm] Maximum error horizontal position since last message
727 static inline uint8_t mavlink_msg_high_latency2_get_eph(const mavlink_message_t
* msg
)
729 return _MAV_RETURN_uint8_t(msg
, 34);
733 * @brief Get field epv from high_latency2 message
735 * @return [dm] Maximum error vertical position since last message
737 static inline uint8_t mavlink_msg_high_latency2_get_epv(const mavlink_message_t
* msg
)
739 return _MAV_RETURN_uint8_t(msg
, 35);
743 * @brief Get field temperature_air from high_latency2 message
745 * @return [degC] Air temperature from airspeed sensor
747 static inline int8_t mavlink_msg_high_latency2_get_temperature_air(const mavlink_message_t
* msg
)
749 return _MAV_RETURN_int8_t(msg
, 36);
753 * @brief Get field climb_rate from high_latency2 message
755 * @return [dm/s] Maximum climb rate magnitude since last message
757 static inline int8_t mavlink_msg_high_latency2_get_climb_rate(const mavlink_message_t
* msg
)
759 return _MAV_RETURN_int8_t(msg
, 37);
763 * @brief Get field battery from high_latency2 message
765 * @return [%] Battery level (-1 if field not provided).
767 static inline int8_t mavlink_msg_high_latency2_get_battery(const mavlink_message_t
* msg
)
769 return _MAV_RETURN_int8_t(msg
, 38);
773 * @brief Get field wp_num from high_latency2 message
775 * @return Current waypoint number
777 static inline uint16_t mavlink_msg_high_latency2_get_wp_num(const mavlink_message_t
* msg
)
779 return _MAV_RETURN_uint16_t(msg
, 20);
783 * @brief Get field failure_flags from high_latency2 message
785 * @return Bitmap of failure flags.
787 static inline uint16_t mavlink_msg_high_latency2_get_failure_flags(const mavlink_message_t
* msg
)
789 return _MAV_RETURN_uint16_t(msg
, 22);
793 * @brief Get field custom0 from high_latency2 message
795 * @return Field for custom payload.
797 static inline int8_t mavlink_msg_high_latency2_get_custom0(const mavlink_message_t
* msg
)
799 return _MAV_RETURN_int8_t(msg
, 39);
803 * @brief Get field custom1 from high_latency2 message
805 * @return Field for custom payload.
807 static inline int8_t mavlink_msg_high_latency2_get_custom1(const mavlink_message_t
* msg
)
809 return _MAV_RETURN_int8_t(msg
, 40);
813 * @brief Get field custom2 from high_latency2 message
815 * @return Field for custom payload.
817 static inline int8_t mavlink_msg_high_latency2_get_custom2(const mavlink_message_t
* msg
)
819 return _MAV_RETURN_int8_t(msg
, 41);
823 * @brief Decode a high_latency2 message into a struct
825 * @param msg The message to decode
826 * @param high_latency2 C-struct to decode the message contents into
828 static inline void mavlink_msg_high_latency2_decode(const mavlink_message_t
* msg
, mavlink_high_latency2_t
* high_latency2
)
830 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
831 high_latency2
->timestamp
= mavlink_msg_high_latency2_get_timestamp(msg
);
832 high_latency2
->latitude
= mavlink_msg_high_latency2_get_latitude(msg
);
833 high_latency2
->longitude
= mavlink_msg_high_latency2_get_longitude(msg
);
834 high_latency2
->custom_mode
= mavlink_msg_high_latency2_get_custom_mode(msg
);
835 high_latency2
->altitude
= mavlink_msg_high_latency2_get_altitude(msg
);
836 high_latency2
->target_altitude
= mavlink_msg_high_latency2_get_target_altitude(msg
);
837 high_latency2
->target_distance
= mavlink_msg_high_latency2_get_target_distance(msg
);
838 high_latency2
->wp_num
= mavlink_msg_high_latency2_get_wp_num(msg
);
839 high_latency2
->failure_flags
= mavlink_msg_high_latency2_get_failure_flags(msg
);
840 high_latency2
->type
= mavlink_msg_high_latency2_get_type(msg
);
841 high_latency2
->autopilot
= mavlink_msg_high_latency2_get_autopilot(msg
);
842 high_latency2
->heading
= mavlink_msg_high_latency2_get_heading(msg
);
843 high_latency2
->target_heading
= mavlink_msg_high_latency2_get_target_heading(msg
);
844 high_latency2
->throttle
= mavlink_msg_high_latency2_get_throttle(msg
);
845 high_latency2
->airspeed
= mavlink_msg_high_latency2_get_airspeed(msg
);
846 high_latency2
->airspeed_sp
= mavlink_msg_high_latency2_get_airspeed_sp(msg
);
847 high_latency2
->groundspeed
= mavlink_msg_high_latency2_get_groundspeed(msg
);
848 high_latency2
->windspeed
= mavlink_msg_high_latency2_get_windspeed(msg
);
849 high_latency2
->wind_heading
= mavlink_msg_high_latency2_get_wind_heading(msg
);
850 high_latency2
->eph
= mavlink_msg_high_latency2_get_eph(msg
);
851 high_latency2
->epv
= mavlink_msg_high_latency2_get_epv(msg
);
852 high_latency2
->temperature_air
= mavlink_msg_high_latency2_get_temperature_air(msg
);
853 high_latency2
->climb_rate
= mavlink_msg_high_latency2_get_climb_rate(msg
);
854 high_latency2
->battery
= mavlink_msg_high_latency2_get_battery(msg
);
855 high_latency2
->custom0
= mavlink_msg_high_latency2_get_custom0(msg
);
856 high_latency2
->custom1
= mavlink_msg_high_latency2_get_custom1(msg
);
857 high_latency2
->custom2
= mavlink_msg_high_latency2_get_custom2(msg
);
859 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_HIGH_LATENCY2_LEN
? msg
->len
: MAVLINK_MSG_ID_HIGH_LATENCY2_LEN
;
860 memset(high_latency2
, 0, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN
);
861 memcpy(high_latency2
, _MAV_PAYLOAD(msg
), len
);