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
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
#pragma once
// MESSAGE SENS_POWER_BOARD PACKING
 
#define MAVLINK_MSG_ID_SENS_POWER_BOARD 8013
 
 
typedef struct __mavlink_sens_power_board_t {
 uint64_t timestamp; /*< [us] Timestamp*/
 float pwr_brd_system_volt; /*< [V] Power board system voltage*/
 float pwr_brd_servo_volt; /*< [V] Power board servo voltage*/
 float pwr_brd_digital_volt; /*< [V] Power board digital voltage*/
 float pwr_brd_mot_l_amp; /*< [A] Power board left motor current sensor*/
 float pwr_brd_mot_r_amp; /*< [A] Power board right motor current sensor*/
 float pwr_brd_analog_amp; /*< [A] Power board analog current sensor*/
 float pwr_brd_digital_amp; /*< [A] Power board digital current sensor*/
 float pwr_brd_ext_amp; /*< [A] Power board extension current sensor*/
 float pwr_brd_aux_amp; /*< [A] Power board aux current sensor*/
 uint8_t pwr_brd_status; /*<  Power board status register*/
 uint8_t pwr_brd_led_status; /*<  Power board leds status*/
} mavlink_sens_power_board_t;
 
#define MAVLINK_MSG_ID_SENS_POWER_BOARD_LEN 46
#define MAVLINK_MSG_ID_SENS_POWER_BOARD_MIN_LEN 46
#define MAVLINK_MSG_ID_8013_LEN 46
#define MAVLINK_MSG_ID_8013_MIN_LEN 46
 
#define MAVLINK_MSG_ID_SENS_POWER_BOARD_CRC 222
#define MAVLINK_MSG_ID_8013_CRC 222
 
 
 
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_SENS_POWER_BOARD { \
    8013, \
    "SENS_POWER_BOARD", \
    12, \
    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_sens_power_board_t, timestamp) }, \
         { "pwr_brd_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_sens_power_board_t, pwr_brd_status) }, \
         { "pwr_brd_led_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 45, offsetof(mavlink_sens_power_board_t, pwr_brd_led_status) }, \
         { "pwr_brd_system_volt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sens_power_board_t, pwr_brd_system_volt) }, \
         { "pwr_brd_servo_volt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sens_power_board_t, pwr_brd_servo_volt) }, \
         { "pwr_brd_digital_volt", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sens_power_board_t, pwr_brd_digital_volt) }, \
         { "pwr_brd_mot_l_amp", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sens_power_board_t, pwr_brd_mot_l_amp) }, \
         { "pwr_brd_mot_r_amp", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sens_power_board_t, pwr_brd_mot_r_amp) }, \
         { "pwr_brd_analog_amp", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sens_power_board_t, pwr_brd_analog_amp) }, \
         { "pwr_brd_digital_amp", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sens_power_board_t, pwr_brd_digital_amp) }, \
         { "pwr_brd_ext_amp", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sens_power_board_t, pwr_brd_ext_amp) }, \
         { "pwr_brd_aux_amp", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sens_power_board_t, pwr_brd_aux_amp) }, \
         } \
}
#else
#define MAVLINK_MESSAGE_INFO_SENS_POWER_BOARD { \
    "SENS_POWER_BOARD", \
    12, \
    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_sens_power_board_t, timestamp) }, \
         { "pwr_brd_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_sens_power_board_t, pwr_brd_status) }, \
         { "pwr_brd_led_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 45, offsetof(mavlink_sens_power_board_t, pwr_brd_led_status) }, \
         { "pwr_brd_system_volt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sens_power_board_t, pwr_brd_system_volt) }, \
         { "pwr_brd_servo_volt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sens_power_board_t, pwr_brd_servo_volt) }, \
         { "pwr_brd_digital_volt", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sens_power_board_t, pwr_brd_digital_volt) }, \
         { "pwr_brd_mot_l_amp", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sens_power_board_t, pwr_brd_mot_l_amp) }, \
         { "pwr_brd_mot_r_amp", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sens_power_board_t, pwr_brd_mot_r_amp) }, \
         { "pwr_brd_analog_amp", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sens_power_board_t, pwr_brd_analog_amp) }, \
         { "pwr_brd_digital_amp", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sens_power_board_t, pwr_brd_digital_amp) }, \
         { "pwr_brd_ext_amp", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sens_power_board_t, pwr_brd_ext_amp) }, \
         { "pwr_brd_aux_amp", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sens_power_board_t, pwr_brd_aux_amp) }, \
         } \
}
#endif
 
/**
 * @brief Pack a sens_power_board 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 timestamp [us] Timestamp
 * @param pwr_brd_status  Power board status register
 * @param pwr_brd_led_status  Power board leds status
 * @param pwr_brd_system_volt [V] Power board system voltage
 * @param pwr_brd_servo_volt [V] Power board servo voltage
 * @param pwr_brd_digital_volt [V] Power board digital voltage
 * @param pwr_brd_mot_l_amp [A] Power board left motor current sensor
 * @param pwr_brd_mot_r_amp [A] Power board right motor current sensor
 * @param pwr_brd_analog_amp [A] Power board analog current sensor
 * @param pwr_brd_digital_amp [A] Power board digital current sensor
 * @param pwr_brd_ext_amp [A] Power board extension current sensor
 * @param pwr_brd_aux_amp [A] Power board aux current sensor
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_sens_power_board_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
                               uint64_t timestamp, uint8_t pwr_brd_status, uint8_t pwr_brd_led_status, float pwr_brd_system_volt, float pwr_brd_servo_volt, float pwr_brd_digital_volt, float pwr_brd_mot_l_amp, float pwr_brd_mot_r_amp, float pwr_brd_analog_amp, float pwr_brd_digital_amp, float pwr_brd_ext_amp, float pwr_brd_aux_amp)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_SENS_POWER_BOARD_LEN];
    _mav_put_uint64_t(buf, 0, timestamp);
    _mav_put_float(buf, 8, pwr_brd_system_volt);
    _mav_put_float(buf, 12, pwr_brd_servo_volt);
    _mav_put_float(buf, 16, pwr_brd_digital_volt);
    _mav_put_float(buf, 20, pwr_brd_mot_l_amp);
    _mav_put_float(buf, 24, pwr_brd_mot_r_amp);
    _mav_put_float(buf, 28, pwr_brd_analog_amp);
    _mav_put_float(buf, 32, pwr_brd_digital_amp);
    _mav_put_float(buf, 36, pwr_brd_ext_amp);
    _mav_put_float(buf, 40, pwr_brd_aux_amp);
    _mav_put_uint8_t(buf, 44, pwr_brd_status);
    _mav_put_uint8_t(buf, 45, pwr_brd_led_status);
 
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENS_POWER_BOARD_LEN);
#else
    mavlink_sens_power_board_t packet;
    packet.timestamp = timestamp;
    packet.pwr_brd_system_volt = pwr_brd_system_volt;
    packet.pwr_brd_servo_volt = pwr_brd_servo_volt;
    packet.pwr_brd_digital_volt = pwr_brd_digital_volt;
    packet.pwr_brd_mot_l_amp = pwr_brd_mot_l_amp;
    packet.pwr_brd_mot_r_amp = pwr_brd_mot_r_amp;
    packet.pwr_brd_analog_amp = pwr_brd_analog_amp;
    packet.pwr_brd_digital_amp = pwr_brd_digital_amp;
    packet.pwr_brd_ext_amp = pwr_brd_ext_amp;
    packet.pwr_brd_aux_amp = pwr_brd_aux_amp;
    packet.pwr_brd_status = pwr_brd_status;
    packet.pwr_brd_led_status = pwr_brd_led_status;
 
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENS_POWER_BOARD_LEN);
#endif
 
    msg->msgid = MAVLINK_MSG_ID_SENS_POWER_BOARD;
    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SENS_POWER_BOARD_MIN_LEN, MAVLINK_MSG_ID_SENS_POWER_BOARD_LEN, MAVLINK_MSG_ID_SENS_POWER_BOARD_CRC);
}
 
/**
 * @brief Pack a sens_power_board 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 timestamp [us] Timestamp
 * @param pwr_brd_status  Power board status register
 * @param pwr_brd_led_status  Power board leds status
 * @param pwr_brd_system_volt [V] Power board system voltage
 * @param pwr_brd_servo_volt [V] Power board servo voltage
 * @param pwr_brd_digital_volt [V] Power board digital voltage
 * @param pwr_brd_mot_l_amp [A] Power board left motor current sensor
 * @param pwr_brd_mot_r_amp [A] Power board right motor current sensor
 * @param pwr_brd_analog_amp [A] Power board analog current sensor
 * @param pwr_brd_digital_amp [A] Power board digital current sensor
 * @param pwr_brd_ext_amp [A] Power board extension current sensor
 * @param pwr_brd_aux_amp [A] Power board aux current sensor
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_sens_power_board_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                               mavlink_message_t* msg,
                                   uint64_t timestamp,uint8_t pwr_brd_status,uint8_t pwr_brd_led_status,float pwr_brd_system_volt,float pwr_brd_servo_volt,float pwr_brd_digital_volt,float pwr_brd_mot_l_amp,float pwr_brd_mot_r_amp,float pwr_brd_analog_amp,float pwr_brd_digital_amp,float pwr_brd_ext_amp,float pwr_brd_aux_amp)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_SENS_POWER_BOARD_LEN];
    _mav_put_uint64_t(buf, 0, timestamp);
    _mav_put_float(buf, 8, pwr_brd_system_volt);
    _mav_put_float(buf, 12, pwr_brd_servo_volt);
    _mav_put_float(buf, 16, pwr_brd_digital_volt);
    _mav_put_float(buf, 20, pwr_brd_mot_l_amp);
    _mav_put_float(buf, 24, pwr_brd_mot_r_amp);
    _mav_put_float(buf, 28, pwr_brd_analog_amp);
    _mav_put_float(buf, 32, pwr_brd_digital_amp);
    _mav_put_float(buf, 36, pwr_brd_ext_amp);
    _mav_put_float(buf, 40, pwr_brd_aux_amp);
    _mav_put_uint8_t(buf, 44, pwr_brd_status);
    _mav_put_uint8_t(buf, 45, pwr_brd_led_status);
 
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENS_POWER_BOARD_LEN);
#else
    mavlink_sens_power_board_t packet;
    packet.timestamp = timestamp;
    packet.pwr_brd_system_volt = pwr_brd_system_volt;
    packet.pwr_brd_servo_volt = pwr_brd_servo_volt;
    packet.pwr_brd_digital_volt = pwr_brd_digital_volt;
    packet.pwr_brd_mot_l_amp = pwr_brd_mot_l_amp;
    packet.pwr_brd_mot_r_amp = pwr_brd_mot_r_amp;
    packet.pwr_brd_analog_amp = pwr_brd_analog_amp;
    packet.pwr_brd_digital_amp = pwr_brd_digital_amp;
    packet.pwr_brd_ext_amp = pwr_brd_ext_amp;
    packet.pwr_brd_aux_amp = pwr_brd_aux_amp;
    packet.pwr_brd_status = pwr_brd_status;
    packet.pwr_brd_led_status = pwr_brd_led_status;
 
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENS_POWER_BOARD_LEN);
#endif
 
    msg->msgid = MAVLINK_MSG_ID_SENS_POWER_BOARD;
    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SENS_POWER_BOARD_MIN_LEN, MAVLINK_MSG_ID_SENS_POWER_BOARD_LEN, MAVLINK_MSG_ID_SENS_POWER_BOARD_CRC);
}
 
/**
 * @brief Encode a sens_power_board 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 sens_power_board C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_sens_power_board_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sens_power_board_t* sens_power_board)
{
    return mavlink_msg_sens_power_board_pack(system_id, component_id, msg, sens_power_board->timestamp, sens_power_board->pwr_brd_status, sens_power_board->pwr_brd_led_status, sens_power_board->pwr_brd_system_volt, sens_power_board->pwr_brd_servo_volt, sens_power_board->pwr_brd_digital_volt, sens_power_board->pwr_brd_mot_l_amp, sens_power_board->pwr_brd_mot_r_amp, sens_power_board->pwr_brd_analog_amp, sens_power_board->pwr_brd_digital_amp, sens_power_board->pwr_brd_ext_amp, sens_power_board->pwr_brd_aux_amp);
}
 
/**
 * @brief Encode a sens_power_board 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 sens_power_board C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_sens_power_board_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sens_power_board_t* sens_power_board)
{
    return mavlink_msg_sens_power_board_pack_chan(system_id, component_id, chan, msg, sens_power_board->timestamp, sens_power_board->pwr_brd_status, sens_power_board->pwr_brd_led_status, sens_power_board->pwr_brd_system_volt, sens_power_board->pwr_brd_servo_volt, sens_power_board->pwr_brd_digital_volt, sens_power_board->pwr_brd_mot_l_amp, sens_power_board->pwr_brd_mot_r_amp, sens_power_board->pwr_brd_analog_amp, sens_power_board->pwr_brd_digital_amp, sens_power_board->pwr_brd_ext_amp, sens_power_board->pwr_brd_aux_amp);
}
 
/**
 * @brief Send a sens_power_board message
 * @param chan MAVLink channel to send the message
 *
 * @param timestamp [us] Timestamp
 * @param pwr_brd_status  Power board status register
 * @param pwr_brd_led_status  Power board leds status
 * @param pwr_brd_system_volt [V] Power board system voltage
 * @param pwr_brd_servo_volt [V] Power board servo voltage
 * @param pwr_brd_digital_volt [V] Power board digital voltage
 * @param pwr_brd_mot_l_amp [A] Power board left motor current sensor
 * @param pwr_brd_mot_r_amp [A] Power board right motor current sensor
 * @param pwr_brd_analog_amp [A] Power board analog current sensor
 * @param pwr_brd_digital_amp [A] Power board digital current sensor
 * @param pwr_brd_ext_amp [A] Power board extension current sensor
 * @param pwr_brd_aux_amp [A] Power board aux current sensor
 */
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_sens_power_board_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t pwr_brd_status, uint8_t pwr_brd_led_status, float pwr_brd_system_volt, float pwr_brd_servo_volt, float pwr_brd_digital_volt, float pwr_brd_mot_l_amp, float pwr_brd_mot_r_amp, float pwr_brd_analog_amp, float pwr_brd_digital_amp, float pwr_brd_ext_amp, float pwr_brd_aux_amp)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_SENS_POWER_BOARD_LEN];
    _mav_put_uint64_t(buf, 0, timestamp);
    _mav_put_float(buf, 8, pwr_brd_system_volt);
    _mav_put_float(buf, 12, pwr_brd_servo_volt);
    _mav_put_float(buf, 16, pwr_brd_digital_volt);
    _mav_put_float(buf, 20, pwr_brd_mot_l_amp);
    _mav_put_float(buf, 24, pwr_brd_mot_r_amp);
    _mav_put_float(buf, 28, pwr_brd_analog_amp);
    _mav_put_float(buf, 32, pwr_brd_digital_amp);
    _mav_put_float(buf, 36, pwr_brd_ext_amp);
    _mav_put_float(buf, 40, pwr_brd_aux_amp);
    _mav_put_uint8_t(buf, 44, pwr_brd_status);
    _mav_put_uint8_t(buf, 45, pwr_brd_led_status);
 
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENS_POWER_BOARD, buf, MAVLINK_MSG_ID_SENS_POWER_BOARD_MIN_LEN, MAVLINK_MSG_ID_SENS_POWER_BOARD_LEN, MAVLINK_MSG_ID_SENS_POWER_BOARD_CRC);
#else
    mavlink_sens_power_board_t packet;
    packet.timestamp = timestamp;
    packet.pwr_brd_system_volt = pwr_brd_system_volt;
    packet.pwr_brd_servo_volt = pwr_brd_servo_volt;
    packet.pwr_brd_digital_volt = pwr_brd_digital_volt;
    packet.pwr_brd_mot_l_amp = pwr_brd_mot_l_amp;
    packet.pwr_brd_mot_r_amp = pwr_brd_mot_r_amp;
    packet.pwr_brd_analog_amp = pwr_brd_analog_amp;
    packet.pwr_brd_digital_amp = pwr_brd_digital_amp;
    packet.pwr_brd_ext_amp = pwr_brd_ext_amp;
    packet.pwr_brd_aux_amp = pwr_brd_aux_amp;
    packet.pwr_brd_status = pwr_brd_status;
    packet.pwr_brd_led_status = pwr_brd_led_status;
 
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENS_POWER_BOARD, (const char *)&packet, MAVLINK_MSG_ID_SENS_POWER_BOARD_MIN_LEN, MAVLINK_MSG_ID_SENS_POWER_BOARD_LEN, MAVLINK_MSG_ID_SENS_POWER_BOARD_CRC);
#endif
}
 
/**
 * @brief Send a sens_power_board message
 * @param chan MAVLink channel to send the message
 * @param struct The MAVLink struct to serialize
 */
static inline void mavlink_msg_sens_power_board_send_struct(mavlink_channel_t chan, const mavlink_sens_power_board_t* sens_power_board)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    mavlink_msg_sens_power_board_send(chan, sens_power_board->timestamp, sens_power_board->pwr_brd_status, sens_power_board->pwr_brd_led_status, sens_power_board->pwr_brd_system_volt, sens_power_board->pwr_brd_servo_volt, sens_power_board->pwr_brd_digital_volt, sens_power_board->pwr_brd_mot_l_amp, sens_power_board->pwr_brd_mot_r_amp, sens_power_board->pwr_brd_analog_amp, sens_power_board->pwr_brd_digital_amp, sens_power_board->pwr_brd_ext_amp, sens_power_board->pwr_brd_aux_amp);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENS_POWER_BOARD, (const char *)sens_power_board, MAVLINK_MSG_ID_SENS_POWER_BOARD_MIN_LEN, MAVLINK_MSG_ID_SENS_POWER_BOARD_LEN, MAVLINK_MSG_ID_SENS_POWER_BOARD_CRC);
#endif
}
 
#if MAVLINK_MSG_ID_SENS_POWER_BOARD_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_sens_power_board_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t pwr_brd_status, uint8_t pwr_brd_led_status, float pwr_brd_system_volt, float pwr_brd_servo_volt, float pwr_brd_digital_volt, float pwr_brd_mot_l_amp, float pwr_brd_mot_r_amp, float pwr_brd_analog_amp, float pwr_brd_digital_amp, float pwr_brd_ext_amp, float pwr_brd_aux_amp)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char *buf = (char *)msgbuf;
    _mav_put_uint64_t(buf, 0, timestamp);
    _mav_put_float(buf, 8, pwr_brd_system_volt);
    _mav_put_float(buf, 12, pwr_brd_servo_volt);
    _mav_put_float(buf, 16, pwr_brd_digital_volt);
    _mav_put_float(buf, 20, pwr_brd_mot_l_amp);
    _mav_put_float(buf, 24, pwr_brd_mot_r_amp);
    _mav_put_float(buf, 28, pwr_brd_analog_amp);
    _mav_put_float(buf, 32, pwr_brd_digital_amp);
    _mav_put_float(buf, 36, pwr_brd_ext_amp);
    _mav_put_float(buf, 40, pwr_brd_aux_amp);
    _mav_put_uint8_t(buf, 44, pwr_brd_status);
    _mav_put_uint8_t(buf, 45, pwr_brd_led_status);
 
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENS_POWER_BOARD, buf, MAVLINK_MSG_ID_SENS_POWER_BOARD_MIN_LEN, MAVLINK_MSG_ID_SENS_POWER_BOARD_LEN, MAVLINK_MSG_ID_SENS_POWER_BOARD_CRC);
#else
    mavlink_sens_power_board_t *packet = (mavlink_sens_power_board_t *)msgbuf;
    packet->timestamp = timestamp;
    packet->pwr_brd_system_volt = pwr_brd_system_volt;
    packet->pwr_brd_servo_volt = pwr_brd_servo_volt;
    packet->pwr_brd_digital_volt = pwr_brd_digital_volt;
    packet->pwr_brd_mot_l_amp = pwr_brd_mot_l_amp;
    packet->pwr_brd_mot_r_amp = pwr_brd_mot_r_amp;
    packet->pwr_brd_analog_amp = pwr_brd_analog_amp;
    packet->pwr_brd_digital_amp = pwr_brd_digital_amp;
    packet->pwr_brd_ext_amp = pwr_brd_ext_amp;
    packet->pwr_brd_aux_amp = pwr_brd_aux_amp;
    packet->pwr_brd_status = pwr_brd_status;
    packet->pwr_brd_led_status = pwr_brd_led_status;
 
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENS_POWER_BOARD, (const char *)packet, MAVLINK_MSG_ID_SENS_POWER_BOARD_MIN_LEN, MAVLINK_MSG_ID_SENS_POWER_BOARD_LEN, MAVLINK_MSG_ID_SENS_POWER_BOARD_CRC);
#endif
}
#endif
 
#endif
 
// MESSAGE SENS_POWER_BOARD UNPACKING
 
 
/**
 * @brief Get field timestamp from sens_power_board message
 *
 * @return [us] Timestamp
 */
static inline uint64_t mavlink_msg_sens_power_board_get_timestamp(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint64_t(msg,  0);
}
 
/**
 * @brief Get field pwr_brd_status from sens_power_board message
 *
 * @return  Power board status register
 */
static inline uint8_t mavlink_msg_sens_power_board_get_pwr_brd_status(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint8_t(msg,  44);
}
 
/**
 * @brief Get field pwr_brd_led_status from sens_power_board message
 *
 * @return  Power board leds status
 */
static inline uint8_t mavlink_msg_sens_power_board_get_pwr_brd_led_status(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint8_t(msg,  45);
}
 
/**
 * @brief Get field pwr_brd_system_volt from sens_power_board message
 *
 * @return [V] Power board system voltage
 */
static inline float mavlink_msg_sens_power_board_get_pwr_brd_system_volt(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  8);
}
 
/**
 * @brief Get field pwr_brd_servo_volt from sens_power_board message
 *
 * @return [V] Power board servo voltage
 */
static inline float mavlink_msg_sens_power_board_get_pwr_brd_servo_volt(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  12);
}
 
/**
 * @brief Get field pwr_brd_digital_volt from sens_power_board message
 *
 * @return [V] Power board digital voltage
 */
static inline float mavlink_msg_sens_power_board_get_pwr_brd_digital_volt(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  16);
}
 
/**
 * @brief Get field pwr_brd_mot_l_amp from sens_power_board message
 *
 * @return [A] Power board left motor current sensor
 */
static inline float mavlink_msg_sens_power_board_get_pwr_brd_mot_l_amp(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  20);
}
 
/**
 * @brief Get field pwr_brd_mot_r_amp from sens_power_board message
 *
 * @return [A] Power board right motor current sensor
 */
static inline float mavlink_msg_sens_power_board_get_pwr_brd_mot_r_amp(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  24);
}
 
/**
 * @brief Get field pwr_brd_analog_amp from sens_power_board message
 *
 * @return [A] Power board analog current sensor
 */
static inline float mavlink_msg_sens_power_board_get_pwr_brd_analog_amp(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  28);
}
 
/**
 * @brief Get field pwr_brd_digital_amp from sens_power_board message
 *
 * @return [A] Power board digital current sensor
 */
static inline float mavlink_msg_sens_power_board_get_pwr_brd_digital_amp(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  32);
}
 
/**
 * @brief Get field pwr_brd_ext_amp from sens_power_board message
 *
 * @return [A] Power board extension current sensor
 */
static inline float mavlink_msg_sens_power_board_get_pwr_brd_ext_amp(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  36);
}
 
/**
 * @brief Get field pwr_brd_aux_amp from sens_power_board message
 *
 * @return [A] Power board aux current sensor
 */
static inline float mavlink_msg_sens_power_board_get_pwr_brd_aux_amp(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  40);
}
 
/**
 * @brief Decode a sens_power_board message into a struct
 *
 * @param msg The message to decode
 * @param sens_power_board C-struct to decode the message contents into
 */
static inline void mavlink_msg_sens_power_board_decode(const mavlink_message_t* msg, mavlink_sens_power_board_t* sens_power_board)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    sens_power_board->timestamp = mavlink_msg_sens_power_board_get_timestamp(msg);
    sens_power_board->pwr_brd_system_volt = mavlink_msg_sens_power_board_get_pwr_brd_system_volt(msg);
    sens_power_board->pwr_brd_servo_volt = mavlink_msg_sens_power_board_get_pwr_brd_servo_volt(msg);
    sens_power_board->pwr_brd_digital_volt = mavlink_msg_sens_power_board_get_pwr_brd_digital_volt(msg);
    sens_power_board->pwr_brd_mot_l_amp = mavlink_msg_sens_power_board_get_pwr_brd_mot_l_amp(msg);
    sens_power_board->pwr_brd_mot_r_amp = mavlink_msg_sens_power_board_get_pwr_brd_mot_r_amp(msg);
    sens_power_board->pwr_brd_analog_amp = mavlink_msg_sens_power_board_get_pwr_brd_analog_amp(msg);
    sens_power_board->pwr_brd_digital_amp = mavlink_msg_sens_power_board_get_pwr_brd_digital_amp(msg);
    sens_power_board->pwr_brd_ext_amp = mavlink_msg_sens_power_board_get_pwr_brd_ext_amp(msg);
    sens_power_board->pwr_brd_aux_amp = mavlink_msg_sens_power_board_get_pwr_brd_aux_amp(msg);
    sens_power_board->pwr_brd_status = mavlink_msg_sens_power_board_get_pwr_brd_status(msg);
    sens_power_board->pwr_brd_led_status = mavlink_msg_sens_power_board_get_pwr_brd_led_status(msg);
#else
        uint8_t len = msg->len < MAVLINK_MSG_ID_SENS_POWER_BOARD_LEN? msg->len : MAVLINK_MSG_ID_SENS_POWER_BOARD_LEN;
        memset(sens_power_board, 0, MAVLINK_MSG_ID_SENS_POWER_BOARD_LEN);
    memcpy(sens_power_board, _MAV_PAYLOAD(msg), len);
#endif
}