tarask
6 days ago 532005c6573d95199ce0ffbc33df4c7a0a4c3ef9
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
#pragma once
// MESSAGE FLIGHT_INFORMATION PACKING
 
#define MAVLINK_MSG_ID_FLIGHT_INFORMATION 264
 
 
typedef struct __mavlink_flight_information_t {
 uint64_t arming_time_utc; /*< [us] Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown*/
 uint64_t takeoff_time_utc; /*< [us] Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown*/
 uint64_t flight_uuid; /*<  Universally unique identifier (UUID) of flight, should correspond to name of log files*/
 uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
} mavlink_flight_information_t;
 
#define MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN 28
#define MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN 28
#define MAVLINK_MSG_ID_264_LEN 28
#define MAVLINK_MSG_ID_264_MIN_LEN 28
 
#define MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC 49
#define MAVLINK_MSG_ID_264_CRC 49
 
 
 
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_FLIGHT_INFORMATION { \
    264, \
    "FLIGHT_INFORMATION", \
    4, \
    {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_flight_information_t, time_boot_ms) }, \
         { "arming_time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_flight_information_t, arming_time_utc) }, \
         { "takeoff_time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_flight_information_t, takeoff_time_utc) }, \
         { "flight_uuid", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_flight_information_t, flight_uuid) }, \
         } \
}
#else
#define MAVLINK_MESSAGE_INFO_FLIGHT_INFORMATION { \
    "FLIGHT_INFORMATION", \
    4, \
    {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_flight_information_t, time_boot_ms) }, \
         { "arming_time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_flight_information_t, arming_time_utc) }, \
         { "takeoff_time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_flight_information_t, takeoff_time_utc) }, \
         { "flight_uuid", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_flight_information_t, flight_uuid) }, \
         } \
}
#endif
 
/**
 * @brief Pack a flight_information message
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 *
 * @param time_boot_ms [ms] Timestamp (time since system boot).
 * @param arming_time_utc [us] Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown
 * @param takeoff_time_utc [us] Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown
 * @param flight_uuid  Universally unique identifier (UUID) of flight, should correspond to name of log files
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_flight_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
                               uint32_t time_boot_ms, uint64_t arming_time_utc, uint64_t takeoff_time_utc, uint64_t flight_uuid)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN];
    _mav_put_uint64_t(buf, 0, arming_time_utc);
    _mav_put_uint64_t(buf, 8, takeoff_time_utc);
    _mav_put_uint64_t(buf, 16, flight_uuid);
    _mav_put_uint32_t(buf, 24, time_boot_ms);
 
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN);
#else
    mavlink_flight_information_t packet;
    packet.arming_time_utc = arming_time_utc;
    packet.takeoff_time_utc = takeoff_time_utc;
    packet.flight_uuid = flight_uuid;
    packet.time_boot_ms = time_boot_ms;
 
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN);
#endif
 
    msg->msgid = MAVLINK_MSG_ID_FLIGHT_INFORMATION;
    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC);
}
 
/**
 * @brief Pack a flight_information message on a channel
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param chan The MAVLink channel this message will be sent over
 * @param msg The MAVLink message to compress the data into
 * @param time_boot_ms [ms] Timestamp (time since system boot).
 * @param arming_time_utc [us] Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown
 * @param takeoff_time_utc [us] Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown
 * @param flight_uuid  Universally unique identifier (UUID) of flight, should correspond to name of log files
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_flight_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                               mavlink_message_t* msg,
                                   uint32_t time_boot_ms,uint64_t arming_time_utc,uint64_t takeoff_time_utc,uint64_t flight_uuid)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN];
    _mav_put_uint64_t(buf, 0, arming_time_utc);
    _mav_put_uint64_t(buf, 8, takeoff_time_utc);
    _mav_put_uint64_t(buf, 16, flight_uuid);
    _mav_put_uint32_t(buf, 24, time_boot_ms);
 
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN);
#else
    mavlink_flight_information_t packet;
    packet.arming_time_utc = arming_time_utc;
    packet.takeoff_time_utc = takeoff_time_utc;
    packet.flight_uuid = flight_uuid;
    packet.time_boot_ms = time_boot_ms;
 
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN);
#endif
 
    msg->msgid = MAVLINK_MSG_ID_FLIGHT_INFORMATION;
    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC);
}
 
/**
 * @brief Encode a flight_information struct
 *
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 * @param flight_information C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_flight_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flight_information_t* flight_information)
{
    return mavlink_msg_flight_information_pack(system_id, component_id, msg, flight_information->time_boot_ms, flight_information->arming_time_utc, flight_information->takeoff_time_utc, flight_information->flight_uuid);
}
 
/**
 * @brief Encode a flight_information struct on a channel
 *
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param chan The MAVLink channel this message will be sent over
 * @param msg The MAVLink message to compress the data into
 * @param flight_information C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_flight_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_flight_information_t* flight_information)
{
    return mavlink_msg_flight_information_pack_chan(system_id, component_id, chan, msg, flight_information->time_boot_ms, flight_information->arming_time_utc, flight_information->takeoff_time_utc, flight_information->flight_uuid);
}
 
/**
 * @brief Send a flight_information message
 * @param chan MAVLink channel to send the message
 *
 * @param time_boot_ms [ms] Timestamp (time since system boot).
 * @param arming_time_utc [us] Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown
 * @param takeoff_time_utc [us] Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown
 * @param flight_uuid  Universally unique identifier (UUID) of flight, should correspond to name of log files
 */
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_flight_information_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t arming_time_utc, uint64_t takeoff_time_utc, uint64_t flight_uuid)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN];
    _mav_put_uint64_t(buf, 0, arming_time_utc);
    _mav_put_uint64_t(buf, 8, takeoff_time_utc);
    _mav_put_uint64_t(buf, 16, flight_uuid);
    _mav_put_uint32_t(buf, 24, time_boot_ms);
 
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION, buf, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC);
#else
    mavlink_flight_information_t packet;
    packet.arming_time_utc = arming_time_utc;
    packet.takeoff_time_utc = takeoff_time_utc;
    packet.flight_uuid = flight_uuid;
    packet.time_boot_ms = time_boot_ms;
 
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC);
#endif
}
 
/**
 * @brief Send a flight_information message
 * @param chan MAVLink channel to send the message
 * @param struct The MAVLink struct to serialize
 */
static inline void mavlink_msg_flight_information_send_struct(mavlink_channel_t chan, const mavlink_flight_information_t* flight_information)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    mavlink_msg_flight_information_send(chan, flight_information->time_boot_ms, flight_information->arming_time_utc, flight_information->takeoff_time_utc, flight_information->flight_uuid);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION, (const char *)flight_information, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC);
#endif
}
 
#if MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
  This variant of _send() can be used to save stack space by re-using
  memory from the receive buffer.  The caller provides a
  mavlink_message_t which is the size of a full mavlink message. This
  is usually the receive buffer for the channel, and allows a reply to an
  incoming message with minimum stack space usage.
 */
static inline void mavlink_msg_flight_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, uint64_t arming_time_utc, uint64_t takeoff_time_utc, uint64_t flight_uuid)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char *buf = (char *)msgbuf;
    _mav_put_uint64_t(buf, 0, arming_time_utc);
    _mav_put_uint64_t(buf, 8, takeoff_time_utc);
    _mav_put_uint64_t(buf, 16, flight_uuid);
    _mav_put_uint32_t(buf, 24, time_boot_ms);
 
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION, buf, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC);
#else
    mavlink_flight_information_t *packet = (mavlink_flight_information_t *)msgbuf;
    packet->arming_time_utc = arming_time_utc;
    packet->takeoff_time_utc = takeoff_time_utc;
    packet->flight_uuid = flight_uuid;
    packet->time_boot_ms = time_boot_ms;
 
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC);
#endif
}
#endif
 
#endif
 
// MESSAGE FLIGHT_INFORMATION UNPACKING
 
 
/**
 * @brief Get field time_boot_ms from flight_information message
 *
 * @return [ms] Timestamp (time since system boot).
 */
static inline uint32_t mavlink_msg_flight_information_get_time_boot_ms(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint32_t(msg,  24);
}
 
/**
 * @brief Get field arming_time_utc from flight_information message
 *
 * @return [us] Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown
 */
static inline uint64_t mavlink_msg_flight_information_get_arming_time_utc(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint64_t(msg,  0);
}
 
/**
 * @brief Get field takeoff_time_utc from flight_information message
 *
 * @return [us] Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown
 */
static inline uint64_t mavlink_msg_flight_information_get_takeoff_time_utc(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint64_t(msg,  8);
}
 
/**
 * @brief Get field flight_uuid from flight_information message
 *
 * @return  Universally unique identifier (UUID) of flight, should correspond to name of log files
 */
static inline uint64_t mavlink_msg_flight_information_get_flight_uuid(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint64_t(msg,  16);
}
 
/**
 * @brief Decode a flight_information message into a struct
 *
 * @param msg The message to decode
 * @param flight_information C-struct to decode the message contents into
 */
static inline void mavlink_msg_flight_information_decode(const mavlink_message_t* msg, mavlink_flight_information_t* flight_information)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    flight_information->arming_time_utc = mavlink_msg_flight_information_get_arming_time_utc(msg);
    flight_information->takeoff_time_utc = mavlink_msg_flight_information_get_takeoff_time_utc(msg);
    flight_information->flight_uuid = mavlink_msg_flight_information_get_flight_uuid(msg);
    flight_information->time_boot_ms = mavlink_msg_flight_information_get_time_boot_ms(msg);
#else
        uint8_t len = msg->len < MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN;
        memset(flight_information, 0, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN);
    memcpy(flight_information, _MAV_PAYLOAD(msg), len);
#endif
}