-
Notifications
You must be signed in to change notification settings - Fork 0
/
MAVLinkPacket.java
747 lines (711 loc) · 43 KB
/
MAVLinkPacket.java
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
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
/* AUTO-GENERATED FILE. DO NOT MODIFY.
*
* This class was automatically generated by the
* java mavlink generator tool. It should not be modified by hand.
*/
package com.MAVLink;
import java.io.Serializable;
import com.MAVLink.Messages.MAVLinkPayload;
import com.MAVLink.Messages.MAVLinkMessage;
import com.MAVLink.ras_a.CRC;
import com.MAVLink.ras_a.*;
import com.MAVLink.development.*;
import com.MAVLink.common.*;
import com.MAVLink.standard.*;
import com.MAVLink.minimal.*;
/**
* Common interface for all MAVLink Messages
* Packet Anatomy
* This is the anatomy of one packet. It is inspired by the CAN and SAE AS-4 standards.
*
* MAVLink 1 Packet Format
*
* Byte Index Content Value Explanation
* 0 Packet start sign v1.0: 0xFE Indicates the start of a new packet. (v0.9: 0x55; v1.0: 0xFE; v2.0 0xFD)
* 1 Payload length 0 - 255 Indicates length of the following payload.
* 2 Packet sequence 0 - 255 Each component counts up its send sequence. Allows to detect packet loss
* 3 System ID 1 - 255 ID of the SENDING system. Allows to differentiate different MAVs on the same network.
* 4 Component ID 0 - 255 ID of the SENDING component. Allows to differentiate different components of the same system, e.g. the IMU and the autopilot.
* 5 Message ID 0 - 255 ID of the message - the id defines what the payload means and how it should be correctly decoded.
* 6 to (n+6) Payload 0 - 255 Data of the message, depends on the message id.
* (n+7)to(n+8) Checksum (low byte, high byte) CRC16/MCRF4XX hash, excluding packet start sign, so bytes 1..(n+6) Note: The checksum also includes MAVLINK_CRC_EXTRA (Number computed from message fields. Protects the packet from decoding a different version of the same packet but with different variables).
*
* The checksum is the CRC16/MCRF4XX. Please see the MAVLink source code for a documented C-implementation of it. LINK TO CHECKSUM
* The minimum packet length is 8 bytes for acknowledgement packets without payload
* The maximum packet length is 263 bytes for full payload
*
*
* MAVLink 2 Packet Format
*
* Byte Index Content Value Explanation
* 0 Packet start sign v2.0: 0xFD Indicates the start of a new packet. (v0.9: 0x55; v1.0: 0xFE; v2.0 0xFD)
* 1 Payload length 0 - 255 Indicates length of the following payload.
* 2 Incompatible Flags 0 - 255 Flags that must be understood
* 3 Compatible Flags 0 - 255 Flags that can be ignored if not understood
* 4 Packet sequence 0 - 255 Each component counts up its send sequence. Allows to detect packet loss
* 5 System ID 1 - 255 ID of the SENDING system. Allows to differentiate different MAVs on the same network.
* 6 Component ID 0 - 255 ID of the SENDING component. Allows to differentiate different components of the same system, e.g. the IMU and the autopilot.
* 7 to 9 Message ID 0 - 16777216 ID of the message - the id defines what the payload means and how it should be correctly decoded.
* 10 Target System ID 1 - 255 (OPTIONAL) ID of the TARGET system. Only used for point-to-point mode
* 11 Target Component ID 0 - 255 (OPTIONAL) ID of the TARGET component. Only used for point-to-point mode
* 12 to (n+12) Payload 0 - 255 Data of the message, depends on the message id.
* (n+13)to(n+14) Checksum (low byte, high byte) CRC16/MCRF4XX hash, excluding packet start sign, so bytes 1..(n+6) Note: The checksum also includes MAVLINK_CRC_EXTRA (Number computed from message fields. Protects the packet from decoding a different version of the same packet but with different variables).
* (n+15)to(n+27) Signature (typeid, timestamp, sha256) (OPTIONAL) Signature which allows ensuring that the link is tamper-proof; 13 bytes containing typeid (1 byte), timestamp (6 bytes), and last 6 bytes of SHA256 hash
*
* The signature is a combination of a typeid, timestamp, and SHA256 hash.
* OPTIONAL fields mean that, if they are not used, they do not exist in the MAVLink frame at all. Typically target sysid and target compid are not used, and signature is only used if signing is set up between both ends.
*
* @see <a href="https://mavlink.io">mavlink.io</a> for more documentation on the MAVLink protocol
*/
public class MAVLinkPacket implements Serializable {
private static final long serialVersionUID = 2095947771227815314L;
public static final int MAVLINK_STX_MAVLINK1 = 0xFE; // 254
public static final int MAVLINK_STX_MAVLINK2 = 0xFD; // 253
public static final int MAVLINK1_HEADER_LEN = 6;
public static final int MAVLINK2_HEADER_LEN = 10;
public static final int MAVLINK1_NONPAYLOAD_LEN = MAVLINK1_HEADER_LEN + 2;
public static final int MAVLINK2_NONPAYLOAD_LEN = MAVLINK2_HEADER_LEN + 2;
static final boolean V = false;
static void logv(String str) {
if(V) System.out.println(String.format("MAVLinkPacket: %s", str));
}
/**
* Payload length
*/
public final int len;
/**
* Message sequence
*/
public int seq;
/**
* ID of the SENDING system. Allows to differentiate different MAVs on the
* same network.
*/
public int sysid;
/**
* ID of the SENDING component. Allows to differentiate different components
* of the same system, e.g. the IMU and the autopilot.
*/
public int compid;
/**
* ID of the message - the id defines what the payload means and how it
* should be correctly decoded.
*/
public int msgid;
/**
* Data of the message, depends on the message id.
*/
public MAVLinkPayload payload;
/**
* CRC-16/MCRF4XX hash, excluding packet start sign, so bytes 1..(n+HEADER-LENGTH)
* Note: The checksum also includes MAVLINK_CRC_EXTRA (Number computed from
* message fields. Protects the packet from decoding a different version of
* the same packet but with different variables).
*/
public CRC crc;
// MAVLink 2.0 fields
/**
* Flag to indicate which MAVLink version this packet is
*/
public boolean isMavlink2;
/**
* Flags that must be understood
*/
public int incompatFlags;
/**
* Flags that can be ignored if not understood
*/
public int compatFlags;
public MAVLinkPacket(int payloadLength) {
this(payloadLength, false);
}
public MAVLinkPacket(final int payloadLength, final boolean isMavlink2) {
len = payloadLength;
payload = new MAVLinkPayload();
this.isMavlink2 = isMavlink2;
}
/**
* Check if the size of the Payload is equal to the "len" byte
*/
public boolean payloadIsFilled() {
return payload.size() >= len;
}
/**
* Update CRC for this packet.
* @return boolean True if the CRC was successfully updated. Otherwise false
*/
public boolean generateCRC(final int payloadSize) {
if (crc == null) {
crc = new CRC();
} else {
crc.start_checksum();
}
if (isMavlink2) {
crc.update_checksum(payloadSize);
crc.update_checksum(incompatFlags);
crc.update_checksum(compatFlags);
crc.update_checksum(seq);
crc.update_checksum(sysid);
crc.update_checksum(compid);
crc.update_checksum(msgid);
crc.update_checksum(msgid >>> 8);
crc.update_checksum(msgid >>> 16);
} else {
crc.update_checksum(payloadSize);
crc.update_checksum(seq);
crc.update_checksum(sysid);
crc.update_checksum(compid);
crc.update_checksum(msgid);
}
payload.resetIndex();
for (int i = 0; i < payloadSize; i++) {
crc.update_checksum(payload.getByte());
}
return crc.finish_checksum(msgid);
}
/**
* Return length of actual data after trimming zeros at the end.
* @param payload
* @return minimum length of valid data
*/
private int mavTrimPayload(final byte[] payload)
{
int length = payload.length;
while (length > 1 && payload[length-1] == 0) {
length--;
}
return length;
}
/**
* Encode this packet for transmission.
*
* @return Array with bytes to be transmitted
*/
public byte[] encodePacket() {
final int bufLen;
final int payloadSize;
if (isMavlink2) {
payloadSize = mavTrimPayload(payload.payload.array());
bufLen = MAVLINK2_HEADER_LEN + payloadSize + 2;
} else {
payloadSize = payload.size();
bufLen = MAVLINK1_HEADER_LEN + payloadSize + 2;
}
byte[] buffer = new byte[bufLen];
int i = 0;
if (isMavlink2) {
buffer[i++] = (byte) MAVLINK_STX_MAVLINK2;
buffer[i++] = (byte) payloadSize;
buffer[i++] = (byte) incompatFlags;
buffer[i++] = (byte) compatFlags;
buffer[i++] = (byte) seq;
buffer[i++] = (byte) sysid;
buffer[i++] = (byte) compid;
buffer[i++] = (byte) (msgid & 0XFF);
buffer[i++] = (byte) ((msgid >>> 8) & 0XFF);
buffer[i++] = (byte) ((msgid >>> 16) & 0XFF);
} else {
buffer[i++] = (byte) MAVLINK_STX_MAVLINK1;
buffer[i++] = (byte) payloadSize;
buffer[i++] = (byte) seq;
buffer[i++] = (byte) sysid;
buffer[i++] = (byte) compid;
buffer[i++] = (byte) msgid;
}
for (int j = 0; j < payloadSize; ++j) {
buffer[i++] = payload.payload.get(j);
}
generateCRC(payloadSize);
buffer[i++] = (byte) (crc.getLSB());
buffer[i++] = (byte) (crc.getMSB());
logv(String.format("encode: isMavlink2=%s msgid=%d", isMavlink2, msgid));
return buffer;
}
/**
* Unpack the data in this packet and return a MAVLink message
*
* @return MAVLink message decoded from this packet
*/
public MAVLinkMessage unpack() {
switch (msgid) {
case msg_heartbeat.MAVLINK_MSG_ID_HEARTBEAT:
return new msg_heartbeat(this);
case msg_sys_status.MAVLINK_MSG_ID_SYS_STATUS:
return new msg_sys_status(this);
case msg_system_time.MAVLINK_MSG_ID_SYSTEM_TIME:
return new msg_system_time(this);
case msg_ping.MAVLINK_MSG_ID_PING:
return new msg_ping(this);
case msg_change_operator_control.MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL:
return new msg_change_operator_control(this);
case msg_change_operator_control_ack.MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK:
return new msg_change_operator_control_ack(this);
case msg_auth_key.MAVLINK_MSG_ID_AUTH_KEY:
return new msg_auth_key(this);
case msg_link_node_status.MAVLINK_MSG_ID_LINK_NODE_STATUS:
return new msg_link_node_status(this);
case msg_set_mode.MAVLINK_MSG_ID_SET_MODE:
return new msg_set_mode(this);
case msg_param_ack_transaction.MAVLINK_MSG_ID_PARAM_ACK_TRANSACTION:
return new msg_param_ack_transaction(this);
case msg_param_request_read.MAVLINK_MSG_ID_PARAM_REQUEST_READ:
return new msg_param_request_read(this);
case msg_param_request_list.MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
return new msg_param_request_list(this);
case msg_param_value.MAVLINK_MSG_ID_PARAM_VALUE:
return new msg_param_value(this);
case msg_param_set.MAVLINK_MSG_ID_PARAM_SET:
return new msg_param_set(this);
case msg_gps_raw_int.MAVLINK_MSG_ID_GPS_RAW_INT:
return new msg_gps_raw_int(this);
case msg_gps_status.MAVLINK_MSG_ID_GPS_STATUS:
return new msg_gps_status(this);
case msg_scaled_imu.MAVLINK_MSG_ID_SCALED_IMU:
return new msg_scaled_imu(this);
case msg_raw_imu.MAVLINK_MSG_ID_RAW_IMU:
return new msg_raw_imu(this);
case msg_raw_pressure.MAVLINK_MSG_ID_RAW_PRESSURE:
return new msg_raw_pressure(this);
case msg_scaled_pressure.MAVLINK_MSG_ID_SCALED_PRESSURE:
return new msg_scaled_pressure(this);
case msg_attitude.MAVLINK_MSG_ID_ATTITUDE:
return new msg_attitude(this);
case msg_attitude_quaternion.MAVLINK_MSG_ID_ATTITUDE_QUATERNION:
return new msg_attitude_quaternion(this);
case msg_local_position_ned.MAVLINK_MSG_ID_LOCAL_POSITION_NED:
return new msg_local_position_ned(this);
case msg_global_position_int.MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
return new msg_global_position_int(this);
case msg_rc_channels_scaled.MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
return new msg_rc_channels_scaled(this);
case msg_rc_channels_raw.MAVLINK_MSG_ID_RC_CHANNELS_RAW:
return new msg_rc_channels_raw(this);
case msg_servo_output_raw.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
return new msg_servo_output_raw(this);
case msg_mission_request_partial_list.MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST:
return new msg_mission_request_partial_list(this);
case msg_mission_write_partial_list.MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST:
return new msg_mission_write_partial_list(this);
case msg_mission_item.MAVLINK_MSG_ID_MISSION_ITEM:
return new msg_mission_item(this);
case msg_mission_request.MAVLINK_MSG_ID_MISSION_REQUEST:
return new msg_mission_request(this);
case msg_mission_set_current.MAVLINK_MSG_ID_MISSION_SET_CURRENT:
return new msg_mission_set_current(this);
case msg_mission_current.MAVLINK_MSG_ID_MISSION_CURRENT:
return new msg_mission_current(this);
case msg_mission_request_list.MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
return new msg_mission_request_list(this);
case msg_mission_count.MAVLINK_MSG_ID_MISSION_COUNT:
return new msg_mission_count(this);
case msg_mission_clear_all.MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
return new msg_mission_clear_all(this);
case msg_mission_item_reached.MAVLINK_MSG_ID_MISSION_ITEM_REACHED:
return new msg_mission_item_reached(this);
case msg_mission_ack.MAVLINK_MSG_ID_MISSION_ACK:
return new msg_mission_ack(this);
case msg_set_gps_global_origin.MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN:
return new msg_set_gps_global_origin(this);
case msg_gps_global_origin.MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
return new msg_gps_global_origin(this);
case msg_param_map_rc.MAVLINK_MSG_ID_PARAM_MAP_RC:
return new msg_param_map_rc(this);
case msg_mission_request_int.MAVLINK_MSG_ID_MISSION_REQUEST_INT:
return new msg_mission_request_int(this);
case msg_safety_set_allowed_area.MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA:
return new msg_safety_set_allowed_area(this);
case msg_safety_allowed_area.MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA:
return new msg_safety_allowed_area(this);
case msg_attitude_quaternion_cov.MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV:
return new msg_attitude_quaternion_cov(this);
case msg_nav_controller_output.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
return new msg_nav_controller_output(this);
case msg_global_position_int_cov.MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV:
return new msg_global_position_int_cov(this);
case msg_local_position_ned_cov.MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV:
return new msg_local_position_ned_cov(this);
case msg_rc_channels.MAVLINK_MSG_ID_RC_CHANNELS:
return new msg_rc_channels(this);
case msg_request_data_stream.MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
return new msg_request_data_stream(this);
case msg_data_stream.MAVLINK_MSG_ID_DATA_STREAM:
return new msg_data_stream(this);
case msg_manual_control.MAVLINK_MSG_ID_MANUAL_CONTROL:
return new msg_manual_control(this);
case msg_rc_channels_override.MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE:
return new msg_rc_channels_override(this);
case msg_mission_item_int.MAVLINK_MSG_ID_MISSION_ITEM_INT:
return new msg_mission_item_int(this);
case msg_vfr_hud.MAVLINK_MSG_ID_VFR_HUD:
return new msg_vfr_hud(this);
case msg_command_int.MAVLINK_MSG_ID_COMMAND_INT:
return new msg_command_int(this);
case msg_command_long.MAVLINK_MSG_ID_COMMAND_LONG:
return new msg_command_long(this);
case msg_command_ack.MAVLINK_MSG_ID_COMMAND_ACK:
return new msg_command_ack(this);
case msg_command_cancel.MAVLINK_MSG_ID_COMMAND_CANCEL:
return new msg_command_cancel(this);
case msg_manual_setpoint.MAVLINK_MSG_ID_MANUAL_SETPOINT:
return new msg_manual_setpoint(this);
case msg_set_attitude_target.MAVLINK_MSG_ID_SET_ATTITUDE_TARGET:
return new msg_set_attitude_target(this);
case msg_attitude_target.MAVLINK_MSG_ID_ATTITUDE_TARGET:
return new msg_attitude_target(this);
case msg_set_position_target_local_ned.MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:
return new msg_set_position_target_local_ned(this);
case msg_position_target_local_ned.MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED:
return new msg_position_target_local_ned(this);
case msg_set_position_target_global_int.MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT:
return new msg_set_position_target_global_int(this);
case msg_position_target_global_int.MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT:
return new msg_position_target_global_int(this);
case msg_local_position_ned_system_global_offset.MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET:
return new msg_local_position_ned_system_global_offset(this);
case msg_hil_state.MAVLINK_MSG_ID_HIL_STATE:
return new msg_hil_state(this);
case msg_hil_controls.MAVLINK_MSG_ID_HIL_CONTROLS:
return new msg_hil_controls(this);
case msg_hil_rc_inputs_raw.MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW:
return new msg_hil_rc_inputs_raw(this);
case msg_hil_actuator_controls.MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS:
return new msg_hil_actuator_controls(this);
case msg_optical_flow.MAVLINK_MSG_ID_OPTICAL_FLOW:
return new msg_optical_flow(this);
case msg_global_vision_position_estimate.MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE:
return new msg_global_vision_position_estimate(this);
case msg_vision_position_estimate.MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE:
return new msg_vision_position_estimate(this);
case msg_vision_speed_estimate.MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE:
return new msg_vision_speed_estimate(this);
case msg_vicon_position_estimate.MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE:
return new msg_vicon_position_estimate(this);
case msg_highres_imu.MAVLINK_MSG_ID_HIGHRES_IMU:
return new msg_highres_imu(this);
case msg_optical_flow_rad.MAVLINK_MSG_ID_OPTICAL_FLOW_RAD:
return new msg_optical_flow_rad(this);
case msg_hil_sensor.MAVLINK_MSG_ID_HIL_SENSOR:
return new msg_hil_sensor(this);
case msg_sim_state.MAVLINK_MSG_ID_SIM_STATE:
return new msg_sim_state(this);
case msg_radio_status.MAVLINK_MSG_ID_RADIO_STATUS:
return new msg_radio_status(this);
case msg_file_transfer_protocol.MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
return new msg_file_transfer_protocol(this);
case msg_timesync.MAVLINK_MSG_ID_TIMESYNC:
return new msg_timesync(this);
case msg_camera_trigger.MAVLINK_MSG_ID_CAMERA_TRIGGER:
return new msg_camera_trigger(this);
case msg_hil_gps.MAVLINK_MSG_ID_HIL_GPS:
return new msg_hil_gps(this);
case msg_hil_optical_flow.MAVLINK_MSG_ID_HIL_OPTICAL_FLOW:
return new msg_hil_optical_flow(this);
case msg_hil_state_quaternion.MAVLINK_MSG_ID_HIL_STATE_QUATERNION:
return new msg_hil_state_quaternion(this);
case msg_scaled_imu2.MAVLINK_MSG_ID_SCALED_IMU2:
return new msg_scaled_imu2(this);
case msg_log_request_list.MAVLINK_MSG_ID_LOG_REQUEST_LIST:
return new msg_log_request_list(this);
case msg_log_entry.MAVLINK_MSG_ID_LOG_ENTRY:
return new msg_log_entry(this);
case msg_log_request_data.MAVLINK_MSG_ID_LOG_REQUEST_DATA:
return new msg_log_request_data(this);
case msg_log_data.MAVLINK_MSG_ID_LOG_DATA:
return new msg_log_data(this);
case msg_log_erase.MAVLINK_MSG_ID_LOG_ERASE:
return new msg_log_erase(this);
case msg_log_request_end.MAVLINK_MSG_ID_LOG_REQUEST_END:
return new msg_log_request_end(this);
case msg_gps_inject_data.MAVLINK_MSG_ID_GPS_INJECT_DATA:
return new msg_gps_inject_data(this);
case msg_gps2_raw.MAVLINK_MSG_ID_GPS2_RAW:
return new msg_gps2_raw(this);
case msg_power_status.MAVLINK_MSG_ID_POWER_STATUS:
return new msg_power_status(this);
case msg_serial_control.MAVLINK_MSG_ID_SERIAL_CONTROL:
return new msg_serial_control(this);
case msg_gps_rtk.MAVLINK_MSG_ID_GPS_RTK:
return new msg_gps_rtk(this);
case msg_gps2_rtk.MAVLINK_MSG_ID_GPS2_RTK:
return new msg_gps2_rtk(this);
case msg_scaled_imu3.MAVLINK_MSG_ID_SCALED_IMU3:
return new msg_scaled_imu3(this);
case msg_data_transmission_handshake.MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
return new msg_data_transmission_handshake(this);
case msg_encapsulated_data.MAVLINK_MSG_ID_ENCAPSULATED_DATA:
return new msg_encapsulated_data(this);
case msg_distance_sensor.MAVLINK_MSG_ID_DISTANCE_SENSOR:
return new msg_distance_sensor(this);
case msg_terrain_request.MAVLINK_MSG_ID_TERRAIN_REQUEST:
return new msg_terrain_request(this);
case msg_terrain_data.MAVLINK_MSG_ID_TERRAIN_DATA:
return new msg_terrain_data(this);
case msg_terrain_check.MAVLINK_MSG_ID_TERRAIN_CHECK:
return new msg_terrain_check(this);
case msg_terrain_report.MAVLINK_MSG_ID_TERRAIN_REPORT:
return new msg_terrain_report(this);
case msg_scaled_pressure2.MAVLINK_MSG_ID_SCALED_PRESSURE2:
return new msg_scaled_pressure2(this);
case msg_att_pos_mocap.MAVLINK_MSG_ID_ATT_POS_MOCAP:
return new msg_att_pos_mocap(this);
case msg_set_actuator_control_target.MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET:
return new msg_set_actuator_control_target(this);
case msg_actuator_control_target.MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET:
return new msg_actuator_control_target(this);
case msg_altitude.MAVLINK_MSG_ID_ALTITUDE:
return new msg_altitude(this);
case msg_resource_request.MAVLINK_MSG_ID_RESOURCE_REQUEST:
return new msg_resource_request(this);
case msg_scaled_pressure3.MAVLINK_MSG_ID_SCALED_PRESSURE3:
return new msg_scaled_pressure3(this);
case msg_follow_target.MAVLINK_MSG_ID_FOLLOW_TARGET:
return new msg_follow_target(this);
case msg_control_system_state.MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE:
return new msg_control_system_state(this);
case msg_battery_status.MAVLINK_MSG_ID_BATTERY_STATUS:
return new msg_battery_status(this);
case msg_autopilot_version.MAVLINK_MSG_ID_AUTOPILOT_VERSION:
return new msg_autopilot_version(this);
case msg_landing_target.MAVLINK_MSG_ID_LANDING_TARGET:
return new msg_landing_target(this);
case msg_fence_status.MAVLINK_MSG_ID_FENCE_STATUS:
return new msg_fence_status(this);
case msg_mag_cal_report.MAVLINK_MSG_ID_MAG_CAL_REPORT:
return new msg_mag_cal_report(this);
case msg_efi_status.MAVLINK_MSG_ID_EFI_STATUS:
return new msg_efi_status(this);
case msg_estimator_status.MAVLINK_MSG_ID_ESTIMATOR_STATUS:
return new msg_estimator_status(this);
case msg_wind_cov.MAVLINK_MSG_ID_WIND_COV:
return new msg_wind_cov(this);
case msg_gps_input.MAVLINK_MSG_ID_GPS_INPUT:
return new msg_gps_input(this);
case msg_gps_rtcm_data.MAVLINK_MSG_ID_GPS_RTCM_DATA:
return new msg_gps_rtcm_data(this);
case msg_high_latency.MAVLINK_MSG_ID_HIGH_LATENCY:
return new msg_high_latency(this);
case msg_high_latency2.MAVLINK_MSG_ID_HIGH_LATENCY2:
return new msg_high_latency2(this);
case msg_vibration.MAVLINK_MSG_ID_VIBRATION:
return new msg_vibration(this);
case msg_home_position.MAVLINK_MSG_ID_HOME_POSITION:
return new msg_home_position(this);
case msg_set_home_position.MAVLINK_MSG_ID_SET_HOME_POSITION:
return new msg_set_home_position(this);
case msg_message_interval.MAVLINK_MSG_ID_MESSAGE_INTERVAL:
return new msg_message_interval(this);
case msg_extended_sys_state.MAVLINK_MSG_ID_EXTENDED_SYS_STATE:
return new msg_extended_sys_state(this);
case msg_adsb_vehicle.MAVLINK_MSG_ID_ADSB_VEHICLE:
return new msg_adsb_vehicle(this);
case msg_collision.MAVLINK_MSG_ID_COLLISION:
return new msg_collision(this);
case msg_v2_extension.MAVLINK_MSG_ID_V2_EXTENSION:
return new msg_v2_extension(this);
case msg_memory_vect.MAVLINK_MSG_ID_MEMORY_VECT:
return new msg_memory_vect(this);
case msg_debug_vect.MAVLINK_MSG_ID_DEBUG_VECT:
return new msg_debug_vect(this);
case msg_named_value_float.MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
return new msg_named_value_float(this);
case msg_named_value_int.MAVLINK_MSG_ID_NAMED_VALUE_INT:
return new msg_named_value_int(this);
case msg_statustext.MAVLINK_MSG_ID_STATUSTEXT:
return new msg_statustext(this);
case msg_debug.MAVLINK_MSG_ID_DEBUG:
return new msg_debug(this);
case msg_setup_signing.MAVLINK_MSG_ID_SETUP_SIGNING:
return new msg_setup_signing(this);
case msg_button_change.MAVLINK_MSG_ID_BUTTON_CHANGE:
return new msg_button_change(this);
case msg_play_tune.MAVLINK_MSG_ID_PLAY_TUNE:
return new msg_play_tune(this);
case msg_camera_information.MAVLINK_MSG_ID_CAMERA_INFORMATION:
return new msg_camera_information(this);
case msg_camera_settings.MAVLINK_MSG_ID_CAMERA_SETTINGS:
return new msg_camera_settings(this);
case msg_storage_information.MAVLINK_MSG_ID_STORAGE_INFORMATION:
return new msg_storage_information(this);
case msg_camera_capture_status.MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS:
return new msg_camera_capture_status(this);
case msg_camera_image_captured.MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED:
return new msg_camera_image_captured(this);
case msg_flight_information.MAVLINK_MSG_ID_FLIGHT_INFORMATION:
return new msg_flight_information(this);
case msg_mount_orientation.MAVLINK_MSG_ID_MOUNT_ORIENTATION:
return new msg_mount_orientation(this);
case msg_logging_data.MAVLINK_MSG_ID_LOGGING_DATA:
return new msg_logging_data(this);
case msg_logging_data_acked.MAVLINK_MSG_ID_LOGGING_DATA_ACKED:
return new msg_logging_data_acked(this);
case msg_logging_ack.MAVLINK_MSG_ID_LOGGING_ACK:
return new msg_logging_ack(this);
case msg_video_stream_information.MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION:
return new msg_video_stream_information(this);
case msg_video_stream_status.MAVLINK_MSG_ID_VIDEO_STREAM_STATUS:
return new msg_video_stream_status(this);
case msg_camera_fov_status.MAVLINK_MSG_ID_CAMERA_FOV_STATUS:
return new msg_camera_fov_status(this);
case msg_camera_tracking_image_status.MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS:
return new msg_camera_tracking_image_status(this);
case msg_camera_tracking_geo_status.MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS:
return new msg_camera_tracking_geo_status(this);
case msg_gimbal_manager_information.MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION:
return new msg_gimbal_manager_information(this);
case msg_gimbal_manager_status.MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS:
return new msg_gimbal_manager_status(this);
case msg_gimbal_manager_set_attitude.MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE:
return new msg_gimbal_manager_set_attitude(this);
case msg_gimbal_device_information.MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION:
return new msg_gimbal_device_information(this);
case msg_gimbal_device_set_attitude.MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE:
return new msg_gimbal_device_set_attitude(this);
case msg_gimbal_device_attitude_status.MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS:
return new msg_gimbal_device_attitude_status(this);
case msg_autopilot_state_for_gimbal_device.MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE:
return new msg_autopilot_state_for_gimbal_device(this);
case msg_gimbal_manager_set_pitchyaw.MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW:
return new msg_gimbal_manager_set_pitchyaw(this);
case msg_gimbal_manager_set_manual_control.MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL:
return new msg_gimbal_manager_set_manual_control(this);
case msg_esc_info.MAVLINK_MSG_ID_ESC_INFO:
return new msg_esc_info(this);
case msg_esc_status.MAVLINK_MSG_ID_ESC_STATUS:
return new msg_esc_status(this);
case msg_airspeed.MAVLINK_MSG_ID_AIRSPEED:
return new msg_airspeed(this);
case msg_wifi_network_info.MAVLINK_MSG_ID_WIFI_NETWORK_INFO:
return new msg_wifi_network_info(this);
case msg_wifi_config_ap.MAVLINK_MSG_ID_WIFI_CONFIG_AP:
return new msg_wifi_config_ap(this);
case msg_protocol_version.MAVLINK_MSG_ID_PROTOCOL_VERSION:
return new msg_protocol_version(this);
case msg_ais_vessel.MAVLINK_MSG_ID_AIS_VESSEL:
return new msg_ais_vessel(this);
case msg_uavcan_node_status.MAVLINK_MSG_ID_UAVCAN_NODE_STATUS:
return new msg_uavcan_node_status(this);
case msg_uavcan_node_info.MAVLINK_MSG_ID_UAVCAN_NODE_INFO:
return new msg_uavcan_node_info(this);
case msg_param_ext_request_read.MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ:
return new msg_param_ext_request_read(this);
case msg_param_ext_request_list.MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST:
return new msg_param_ext_request_list(this);
case msg_param_ext_value.MAVLINK_MSG_ID_PARAM_EXT_VALUE:
return new msg_param_ext_value(this);
case msg_param_ext_set.MAVLINK_MSG_ID_PARAM_EXT_SET:
return new msg_param_ext_set(this);
case msg_param_ext_ack.MAVLINK_MSG_ID_PARAM_EXT_ACK:
return new msg_param_ext_ack(this);
case msg_obstacle_distance.MAVLINK_MSG_ID_OBSTACLE_DISTANCE:
return new msg_obstacle_distance(this);
case msg_odometry.MAVLINK_MSG_ID_ODOMETRY:
return new msg_odometry(this);
case msg_trajectory_representation_waypoints.MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS:
return new msg_trajectory_representation_waypoints(this);
case msg_trajectory_representation_bezier.MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER:
return new msg_trajectory_representation_bezier(this);
case msg_cellular_status.MAVLINK_MSG_ID_CELLULAR_STATUS:
return new msg_cellular_status(this);
case msg_isbd_link_status.MAVLINK_MSG_ID_ISBD_LINK_STATUS:
return new msg_isbd_link_status(this);
case msg_cellular_config.MAVLINK_MSG_ID_CELLULAR_CONFIG:
return new msg_cellular_config(this);
case msg_raw_rpm.MAVLINK_MSG_ID_RAW_RPM:
return new msg_raw_rpm(this);
case msg_utm_global_position.MAVLINK_MSG_ID_UTM_GLOBAL_POSITION:
return new msg_utm_global_position(this);
case msg_debug_float_array.MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY:
return new msg_debug_float_array(this);
case msg_orbit_execution_status.MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS:
return new msg_orbit_execution_status(this);
case msg_figure_eight_execution_status.MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS:
return new msg_figure_eight_execution_status(this);
case msg_battery_status_v2.MAVLINK_MSG_ID_BATTERY_STATUS_V2:
return new msg_battery_status_v2(this);
case msg_smart_battery_info.MAVLINK_MSG_ID_SMART_BATTERY_INFO:
return new msg_smart_battery_info(this);
case msg_generator_status.MAVLINK_MSG_ID_GENERATOR_STATUS:
return new msg_generator_status(this);
case msg_actuator_output_status.MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS:
return new msg_actuator_output_status(this);
case msg_time_estimate_to_target.MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET:
return new msg_time_estimate_to_target(this);
case msg_tunnel.MAVLINK_MSG_ID_TUNNEL:
return new msg_tunnel(this);
case msg_can_frame.MAVLINK_MSG_ID_CAN_FRAME:
return new msg_can_frame(this);
case msg_canfd_frame.MAVLINK_MSG_ID_CANFD_FRAME:
return new msg_canfd_frame(this);
case msg_can_filter_modify.MAVLINK_MSG_ID_CAN_FILTER_MODIFY:
return new msg_can_filter_modify(this);
case msg_onboard_computer_status.MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS:
return new msg_onboard_computer_status(this);
case msg_component_information.MAVLINK_MSG_ID_COMPONENT_INFORMATION:
return new msg_component_information(this);
case msg_component_information_basic.MAVLINK_MSG_ID_COMPONENT_INFORMATION_BASIC:
return new msg_component_information_basic(this);
case msg_component_metadata.MAVLINK_MSG_ID_COMPONENT_METADATA:
return new msg_component_metadata(this);
case msg_play_tune_v2.MAVLINK_MSG_ID_PLAY_TUNE_V2:
return new msg_play_tune_v2(this);
case msg_supported_tunes.MAVLINK_MSG_ID_SUPPORTED_TUNES:
return new msg_supported_tunes(this);
case msg_event.MAVLINK_MSG_ID_EVENT:
return new msg_event(this);
case msg_current_event_sequence.MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE:
return new msg_current_event_sequence(this);
case msg_request_event.MAVLINK_MSG_ID_REQUEST_EVENT:
return new msg_request_event(this);
case msg_response_event_error.MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR:
return new msg_response_event_error(this);
case msg_group_start.MAVLINK_MSG_ID_GROUP_START:
return new msg_group_start(this);
case msg_group_end.MAVLINK_MSG_ID_GROUP_END:
return new msg_group_end(this);
case msg_available_modes.MAVLINK_MSG_ID_AVAILABLE_MODES:
return new msg_available_modes(this);
case msg_current_mode.MAVLINK_MSG_ID_CURRENT_MODE:
return new msg_current_mode(this);
case msg_available_modes_monitor.MAVLINK_MSG_ID_AVAILABLE_MODES_MONITOR:
return new msg_available_modes_monitor(this);
case msg_target_absolute.MAVLINK_MSG_ID_TARGET_ABSOLUTE:
return new msg_target_absolute(this);
case msg_target_relative.MAVLINK_MSG_ID_TARGET_RELATIVE:
return new msg_target_relative(this);
case msg_wheel_distance.MAVLINK_MSG_ID_WHEEL_DISTANCE:
return new msg_wheel_distance(this);
case msg_winch_status.MAVLINK_MSG_ID_WINCH_STATUS:
return new msg_winch_status(this);
case msg_open_drone_id_basic_id.MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID:
return new msg_open_drone_id_basic_id(this);
case msg_open_drone_id_location.MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION:
return new msg_open_drone_id_location(this);
case msg_open_drone_id_authentication.MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION:
return new msg_open_drone_id_authentication(this);
case msg_open_drone_id_self_id.MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID:
return new msg_open_drone_id_self_id(this);
case msg_open_drone_id_system.MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM:
return new msg_open_drone_id_system(this);
case msg_open_drone_id_operator_id.MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID:
return new msg_open_drone_id_operator_id(this);
case msg_open_drone_id_message_pack.MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK:
return new msg_open_drone_id_message_pack(this);
case msg_open_drone_id_arm_status.MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS:
return new msg_open_drone_id_arm_status(this);
case msg_open_drone_id_system_update.MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE:
return new msg_open_drone_id_system_update(this);
case msg_hygrometer_sensor.MAVLINK_MSG_ID_HYGROMETER_SENSOR:
return new msg_hygrometer_sensor(this);
case msg_poi_report.MAVLINK_MSG_ID_POI_REPORT:
return new msg_poi_report(this);
case msg_exploration_status.MAVLINK_MSG_ID_EXPLORATION_STATUS:
return new msg_exploration_status(this);
case msg_exploration_info.MAVLINK_MSG_ID_EXPLORATION_INFO:
return new msg_exploration_info(this);
case msg_exploration_return_position.MAVLINK_MSG_ID_EXPLORATION_RETURN_POSITION:
return new msg_exploration_return_position(this);
default:
return null;
}
}
}