-
Notifications
You must be signed in to change notification settings - Fork 5
/
Globals.h
1919 lines (1742 loc) · 70.4 KB
/
Globals.h
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
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
// Prevent Visual Studio Intellisense from defining _WIN32 and _MSC_VER when we use
// Visual Studio to edit Linux or Borland C++ code.
#ifdef __linux__
# undef _WIN32
#endif // __linux__
#if defined(__GNUC__) || defined(__BORLANDC__)
# undef _MSC_VER
#endif // defined(__GNUC__) || defined(__BORLANDC__)
#ifndef GLOBALS_H
#define GLOBALS_H
#include "OSCriticalSection.h"
#include "OSThread.h"
#include "OSTimer.h"
#include "OSMisc.h"
#include "RS232Port.h"
#include "CoordSystem2Img.h"
#ifndef DISABLE_OPENCV_SUPPORT
#include "CvProc.h"
#ifdef ENABLE_CVKINECT2SDKHOOK
//#ifndef INCLUDE_HEADERS_OUTSIDE_CVKINECT2SDKHOOK
//#define INCLUDE_HEADERS_OUTSIDE_CVKINECT2SDKHOOK
//#endif // !INCLUDE_HEADERS_OUTSIDE_CVKINECT2SDKHOOK
//#include <Kinect.h>
#include "CvKinect2SDKHook.h"
#else
#ifdef ENABLE_CVCLEYESDKHOOK
#ifndef INCLUDE_HEADERS_OUTSIDE_CVCLEYESDKHOOK
#define INCLUDE_HEADERS_OUTSIDE_CVCLEYESDKHOOK
#endif // !INCLUDE_HEADERS_OUTSIDE_CVCLEYESDKHOOK
#include "CLEyeMulticam.h"
#include "CvCLEyeSDKHook.h"
#endif // ENABLE_CVCLEYESDKHOOK
#endif // ENABLE_CVKINECT2SDKHOOK
#endif // !DISABLE_OPENCV_SUPPORT
#ifdef _WIN32
#ifdef _MSC_VER
// Disable some Visual Studio warnings.
#pragma warning(disable : 4201)
#endif // _MSC_VER
#include "MMSystem.h"
#ifdef _MSC_VER
// Restore the Visual Studio warnings previously disabled.
#pragma warning(default : 4201)
#endif // _MSC_VER
#endif // _WIN32
#include "rmatrix.h"
#include <deque>
// Need to be undefined at the end of the file...
// min and max might cause incompatibilities...
#ifndef max
#define max(a,b) (((a) > (b)) ? (a) : (b))
#endif // !max
#ifndef min
#define min(a,b) (((a) < (b)) ? (a) : (b))
#endif // !min
#ifdef _MSC_VER
// Disable some Visual Studio warnings.
#pragma warning(disable : 4459)
#endif // _MSC_VER
// Robot id masks.
#define SUBMARINE_ROBID_MASK 0x000000FF
#define SURFACE_ROBID_MASK 0x0000FF00
#define GROUND_ROBID_MASK 0x00FF0000
#define AERIAL_ROBID_MASK 0xFF000000
#define SAUCISSE_CLASS_ROBID_MASK 0x0000000E
#define MOTORBOAT_CLASS_ROBID_MASK 0x00000E00
#define SAILBOAT_CLASS_ROBID_MASK 0x0000E000
#define COPTER_CLASS_ROBID_MASK 0x0E000000
#define PLANE_CLASS_ROBID_MASK 0xE0000000
#define SIMULATOR_ROBID_MASK 0x11111111
// Simulators id.
#define SUBMARINE_SIMULATOR_ROBID 0x00000001
#define MOTORBOAT_SIMULATOR_ROBID 0x00000100
#define SAILBOAT_SIMULATOR_ROBID 0x00001000
#define TANK_SIMULATOR_ROBID 0x00010000
#define BUGGY_SIMULATOR_ROBID 0x00100000
#define QUADRO_SIMULATOR_ROBID 0x01000000
// Robots should have an even id.
#define SAUCISSE_ROBID 0x00000002
#define SARDINE_ROBID 0x00000004
#define CISCREA_ROBID 0x00000020
#define BLUEROV_ROBID 0x00000040
#define LIRMIA3_ROBID 0x00000080
#define BUBBLE_ROBID 0x00000200
#define MOTORBOAT_ROBID 0x00000400
#define SPEBOT_ROBID 0x00000800
#define VAIMOS_ROBID 0x00002000
#define SAILBOAT_ROBID 0x00004000
#define SAILBOAT2_ROBID 0x00008000
#define ETAS_WHEEL_ROBID 0x00020000
#define BUGGY_ROBID 0x00200000
#define COPTER_ROBID 0x02000000
#define ARDUCOPTER_ROBID 0x04000000
//#define NAE_ROBID 0x08000000
//#define PLANE_ROBID 0x20000000
//#define ARDUPLANE_ROBID 0x40000000
//#define UAUV_ROBID 0x80000000
enum KEYS
{
FWD_KEY,
BWD_KEY,
LEFT_KEY,
RIGHT_KEY,
LAT_LEFT_KEY,
LAT_RIGHT_KEY,
BRAKE_KEY,
DEPTHCONTROL_KEY,
ALTITUDEAGLCONTROL_KEY,
NB_CONFIGURABLE_KEYS
};
typedef enum KEYS KEYS;
#define LOG_FOLDER "log/"
#define PIC_FOLDER "pic/"
#define VID_FOLDER "vid/"
#define AUD_FOLDER "aud/"
#define MAX_UNCERTAINTY 10000
#define MAX_NB_LABELS 1024
#define MAX_NB_PROCEDURES 256
#define MAX_NB_REGISTERS 32
#define MAX_NB_OPENCVGUI 5
#define MAX_NB_VIDEO 5
#define MAX_NB_BLUEVIEW 2
#define MAX_NB_NMEADEVICE 2
#define MAX_NB_UBLOX 3
#define MAX_NB_MAVLINKDEVICE 3
#define MAX_NB_POLOLU 3
#define MAX_NB_ROBOTEQ 2
#define MAX_NB_BALL 8
#define MAX_NB_EXTERNALPROGRAMTRIGGER 8
#define MAX_NB_WP 1024
#define MAX_CFGFILE_SIZE 16384
#define MISSION_RESUME_DISABLED 0
#define MISSION_RESUME_NEXT 1
#define MISSION_RESUME_STARTUP 2
#define OBJTYPE_BALL 0
#define OBJTYPE_PIPELINE 1
#define OBJTYPE_PINGER 2
#define OBJTYPE_VISUALOBSTACLE 3
#define OBJTYPE_CARDS 4
// GNSS accuracy levels.
#define GNSS_ACC_LEVEL_GNSS_NO_FIX 0
#define GNSS_ACC_LEVEL_GNSS_FIX_UNREL 1
#define GNSS_ACC_LEVEL_GNSS_FIX_LOW 2
#define GNSS_ACC_LEVEL_GNSS_FIX_MED 3
#define GNSS_ACC_LEVEL_GNSS_FIX_HIGH 4
#define GNSS_ACC_LEVEL_RTK_UNREL 5
#define GNSS_ACC_LEVEL_RTK_FLOAT 6
#define GNSS_ACC_LEVEL_RTK_FIXED 7
// Raw GNSS quality indicator.
#define GNSS_NO_FIX 0
#define AUTONOMOUS_GNSS_FIX 1
#define DIFFERENTIAL_GNSS_FIX 2
#define RTK_FIXED 4
#define RTK_FLOAT 5
#define GNSS_ESTIMATED_FIX 6
// Sonar image flags.
#define SONAR_IMG_TYPE_SHIFT 0
#define SONAR_IMG_DISTANCES_SHIFT 4
#define SONAR_IMG_CORRECTIONS_SHIFT 8
#define SONAR_IMG_TYPE_MASK 0x0000000F
#define SONAR_IMG_DISTANCES_MASK 0x000000F0
#define SONAR_IMG_CORRECTIONS_MASK 0x0000FF00
#define SONAR_IMG_NORMAL 0x00000001
#define SONAR_IMG_WATERFALL 0x00000002
#define SONAR_IMG_FIRST_DISTANCES 0x00000010
#define SONAR_IMG_ALL_DISTANCES 0x00000020
#define SONAR_IMG_LEVER_ARMS 0x00000100
#define SONAR_IMG_LEVER_ARMS_PSI 0x00000200
#define SONAR_IMG_LEVER_ARMS_PSI_POS 0x00000400
#define SONAR_IMG_LEVER_ARMS_HIST_PSI 0x00000800
#define SONAR_IMG_LEVER_ARMS_HIST_PSI_POS 0x00001000
enum HEADING_AND_LATERAL_CONTROL_MODES
{
PURE_HEADING_CONTROL_MODE,
PURE_LATERAL_CONTROL_MODE,
HEADING_AND_LATERAL_CONTROL_MODE
};
typedef enum HEADING_AND_LATERAL_CONTROL_MODES HEADING_AND_LATERAL_CONTROL_MODES;
// Acoustic modem messages.
enum ACOUSTIC_MODEM_MESSAGES
{
RNG_MSG = 1,
SENDXY_MSG = 6,
RECVXY_MSG = 7,
SENDASK_MSG = 12,
RECVASK_MSG = 13,
SENDSPWT_MSG = 36,
RECVSPWT_MSG = 37,
RECVANYSENDXY_MSG = 1019,
SENDOPI_MSG,
RECVOPI_MSG,
WAITRECVOPI_MSG,
SENDSHH_MSG,
RECVSHH_MSG,
RECVXY_RNG_MSG
};
typedef enum ACOUSTIC_MODEM_MESSAGES ACOUSTIC_MODEM_MESSAGES;
// Sailboat supervisor states.
enum STATE
{
INVALID_STATE = -1,
DIRECT_TRAJECTORY, // Suivi direct.
STARBOARD_TACK_TRAJECTORY, // Bateau au près avec vent de tribord.
PORT_TACK_TRAJECTORY // Bateau au près avec vent de babord.
};
typedef enum STATE STATE;
// Follow Me targets.
enum FOLLOWME_TARGETS
{
SWARMONDEVICE0_TARGET = 0,
MAVLINKDEVICE0_TARGET,
MAVLINKDEVICE1_TARGET,
MAVLINKDEVICE2_TARGET,
MDM0_TARGET
};
typedef enum FOLLOWME_TARGETS FOLLOWME_TARGETS;
// Observer variables.
extern interval xhat, yhat, zhat, phihat, thetahat, psihat, vrxhat, vryhat, vrzhat, omegaxhat, omegayhat, omegazhat, accrxhat, accryhat, accrzhat;
extern interval vchat, psichat, hwhat;
extern interval vtwindhat, psitwindhat;
//extern interval alphahat, dhat;
// Controller variables.
// u > 0 to go forward, uw > 0 to turn in positive direction, uv > 0 to go up.
extern double u, uw, uv, ul, up, ur, wx, wy, wz, wphi, wtheta, wpsi, wd, wu;
extern double u_ovrid, uw_ovrid, uv_ovrid, ul_ovrid, up_ovrid, ur_ovrid,
u_max_ovrid, uw_max_ovrid;
extern double u_f, uw_f, uv_f, ul_f, up_f, ur_f;
extern double wxa, wya, wza, wxb, wyb, wzb;
extern deque<double> wx_vector, wy_vector, wz_vector;
extern double wagl; // Altitude Above Ground Level.
extern double lat_home, long_home, alt_home;
extern int gcs_mission_count;
extern double wpstmplat[MAX_NB_WP];
extern double wpstmplong[MAX_NB_WP];
extern double wpstmpalt[MAX_NB_WP];
extern int nbwpstmp;
extern double wpslat[MAX_NB_WP];
extern double wpslong[MAX_NB_WP];
extern double wpsalt[MAX_NB_WP];
extern int nbWPs, CurWP;
extern BOOL bGenerateLineToFirst, bAutoStation;
// Measurements.
extern interval x_gps, y_gps, z_gps, cog_gps;
extern interval phi_ahrs, theta_ahrs, psi_ahrs, omegax_ahrs, omegay_ahrs, omegaz_ahrs, accrx_ahrs, accry_ahrs, accrz_ahrs;
extern interval psi_dvl, vrx_dvl, vry_dvl, vrz_dvl;
extern interval vrx_of, vry_of, vrz_of;
extern interval vx_ned, vy_ned, vz_ned;
extern interval z_pressure;
// Objects to track, distance control...
extern double dist;
// GPS.
extern double sog, xte, utc;
#define MAX_NB_BYTES_RTCM_PARTS 8192
//#define MAX_NB_RTCM_PARTS 1024
//extern vector< deque<unsigned char*> > RTCMuserslist;
extern vector< deque<unsigned char> > RTCMuserslist;
//extern deque<unsigned char*> RTCMusers[MAX_NB_UBLOX]; // replace with deque< vector<unsigned char> > to get data and datalen? Or deque<unsigned char>, for each data byte...
extern deque<unsigned char> RTCMusers[MAX_NB_UBLOX];
// Barometer, pressure sensor...
extern double pressure_mes;
// Wind/air/water current sensor...
extern double fluiddira, fluidspeeda, fluiddir, fluidspeed;
// Weather station.
extern double vtwind, psitwind, vawind, psiawind;
// Sonar.
extern double alpha_mes, d_mes;
extern vector<interval> d_all_mes;
extern deque<double> alpha_mes_vector;
extern deque<double> d_mes_vector;
extern deque< vector<interval> > d_all_mes_vector;
extern deque<double> t_history_vector;
extern deque<interval> xhat_history_vector;
extern deque<interval> yhat_history_vector;
extern deque<interval> psihat_history_vector;
extern deque<interval> vrxhat_history_vector;
// Up vertical telemeter.
extern double distance_above;
// Echosounder.
extern double altitude_AGL;
// Modem.
extern double acousticmodem_x, acousticmodem_y, acousticmodem_z, acousticmodem_r;
extern int opi_id;
extern double opi_x, opi_y;
// Equivalent thusters.
// u1 : right, u2 : left, u3 : bottom.
extern double u1, u2, u3, u4, u5, u6, u7, u8, u9, u10, u11, u12, u13, u14;
extern double lights, cameratilt;
extern unsigned int joystick_buttons;
extern unsigned int rc_aux3_sw;
extern BOOL rc_ail_sw;
extern BOOL rc_gear_sw;
extern BOOL rc_ele_sw;
extern BOOL rc_rud_sw;
extern double rudderminangle, ruddermidangle, ruddermaxangle;
extern double EPU1, EPU2;
#pragma region General parameters
extern int robid;
extern double roblength, robwidth, robheight;
extern int nbopencvgui, videoimgwidth, videoimgheight, captureperiod, HorizontalBeam, VerticalBeam;
extern BOOL bUseRawImgPtrVideo;
extern BOOL bCropOnResize;
extern char szVideoRecordCodec[5];
extern BOOL bEnableOpenCVGUIs[MAX_NB_OPENCVGUI];
extern BOOL bShowVideoOpenCVGUIs[MAX_NB_OPENCVGUI];
extern BOOL bShowSonarOpenCVGUIs[MAX_NB_OPENCVGUI];
extern int opencvguiimgwidth[MAX_NB_OPENCVGUI];
extern int opencvguiimgheight[MAX_NB_OPENCVGUI];
extern int opencvguiperiod;
extern int ExitOnErrorCount;
extern int AutoResumeMissionMode;
extern BOOL bDisablelogstate;
extern BOOL bDisablelognav;
extern BOOL bStdOutDetailedInfo;
extern BOOL bCommandPrompt;
extern BOOL bEcho;
extern BOOL bDetachCommandsThread;
extern int WaitForGNSSLevel;
extern int WaitForGNSSTimeout;
extern BOOL bSetEnvOriginFromGNSS;
extern BOOL bDisableExternalVisualLocalization;
extern BOOL bDisableWall;
extern BOOL bDisableBall;
extern BOOL bDisablePinger;
extern BOOL bDisableExternalProgramTrigger;
extern BOOL bDisableFollowMe;
#pragma endregion
#pragma region Interfaces parameters
extern BOOL bMAVLinkInterface;
extern char szMAVLinkInterfacePath[MAX_BUF_LEN];
extern int MAVLinkInterfaceBaudRate;
extern int MAVLinkInterfaceTimeout;
extern int MAVLinkInterface_mavlink_comm;
extern int MAVLinkInterface_system_id;
extern int MAVLinkInterface_component_id;
extern int MAVLinkInterface_target_system;
extern int MAVLinkInterface_target_component;
extern int MAVLinkInterface_data_stream;
extern BOOL bForceDefaultMAVLink1MAVLinkInterface;
extern BOOL bDisableMAVLinkInterfaceIN;
extern int MAVLinkInterface_rc_override_time;
extern int MAVLinkInterface_overridechan;
extern BOOL MAVLinkInterface_bDefaultDisablePWMOverride;
extern int MAVLinkInterface_forceoverrideinputschan;
extern BOOL MAVLinkInterface_bDefaultForceOverrideInputs;
extern BOOL MAVLinkInterface_bDisabletlog;
extern BOOL bNMEAInterface;
extern char szNMEAInterfacePath[MAX_BUF_LEN];
extern int NMEAInterfaceBaudRate;
extern int NMEAInterfaceTimeout;
extern int NMEAInterfacePeriod;
extern BOOL bEnable_NMEAInterface_GPGGA;
extern BOOL bEnable_NMEAInterface_GPRMC;
extern BOOL bEnable_NMEAInterface_GPGLL;
extern BOOL bEnable_NMEAInterface_GPVTG;
extern BOOL bEnable_NMEAInterface_GPHDG;
extern BOOL bEnable_NMEAInterface_GPHDM;
extern BOOL bEnable_NMEAInterface_GPHDT;
extern BOOL bEnable_NMEAInterface_HCHDG;
extern BOOL bEnable_NMEAInterface_HCHDM;
extern BOOL bEnable_NMEAInterface_HEHDT;
extern BOOL bEnable_NMEAInterface_HEROT;
extern BOOL bEnable_NMEAInterface_TIROT;
extern BOOL bEnable_NMEAInterface_WIMWV;
extern BOOL bEnable_NMEAInterface_WIMWD;
extern BOOL bEnable_NMEAInterface_WIMDA;
extern BOOL bEnable_NMEAInterface_PRDID;
extern BOOL bEnable_NMEAInterface_PHTRO;
extern BOOL bEnable_NMEAInterface_PHTRH;
extern BOOL bEnable_NMEAInterface_IIRSA;
extern BOOL bEnable_NMEAInterface_SDDBT;
extern int NMEAInterfaceSendPeriod;
extern BOOL bDisableNMEAInterfaceIN;
extern BOOL bRazorAHRSInterface;
extern char szRazorAHRSInterfacePath[MAX_BUF_LEN];
extern int RazorAHRSInterfaceBaudRate;
extern int RazorAHRSInterfaceTimeout;
extern BOOL bROSMode_RazorAHRSInterface;
extern BOOL bSBGInterface;
extern char szSBGInterfacePath[MAX_BUF_LEN];
extern int SBGInterfaceBaudRate;
extern int SBGInterfaceTimeout;
extern BOOL bVectorNavInterface;
extern char szVectorNavInterfacePath[MAX_BUF_LEN];
extern int VectorNavInterfaceBaudRate;
extern int VectorNavInterfaceTimeout;
extern BOOL bSSC32Interface;
extern char szSSC32InterfacePath[MAX_BUF_LEN];
extern int SSC32InterfaceBaudRate;
extern int SSC32InterfaceTimeout;
extern BOOL bPololuInterface;
extern char szPololuInterfacePath[MAX_BUF_LEN];
extern int PololuInterfaceBaudRate;
extern int PololuInterfaceTimeout;
extern int PololuType_PololuInterface;
extern int DeviceNumber_PololuInterface;
extern BOOL bRoboteqInterface;
extern char szRoboteqInterfacePath[MAX_BUF_LEN];
extern int RoboteqInterfaceBaudRate;
extern int RoboteqInterfaceTimeout;
extern BOOL bVideoInterface;
extern char szVideoInterfacePath[MAX_BUF_LEN];
extern int videoimgwidth_VideoInterface, videoimgheight_VideoInterface, captureperiod_VideoInterface;
extern int VideoInterfaceTimeout;
extern BOOL bForceSoftwareResizeScale_VideoInterface;
extern int guiid_VideoInterface;
extern int videoid_VideoInterface;
extern int encodequality_VideoInterface;
#pragma endregion
#pragma region Devices parameters
extern BOOL bDisableVideo[MAX_NB_VIDEO];
extern BOOL bDisablegpControl;
extern BOOL bDisablePathfinderDVL;
extern BOOL bDisableNortekDVL;
extern BOOL bDisableMES;
extern BOOL bDisableMDM;
extern BOOL bDisableSeanet;
extern BOOL bDisableBlueView[MAX_NB_BLUEVIEW];
extern BOOL bDisableHokuyo;
extern BOOL bDisableRPLIDAR;
extern BOOL bDisableSRF02;
extern BOOL bDisableArduinoPressureSensor;
extern BOOL bDisableMS580314BA;
extern BOOL bDisableMS5837;
extern BOOL bDisableP33x;
extern BOOL bDisableRazorAHRS;
extern BOOL bDisableMT;
extern BOOL bDisableSBG;
extern BOOL bDisableNMEADevice[MAX_NB_NMEADEVICE];
extern BOOL bDisableublox[MAX_NB_UBLOX];
extern BOOL bDisableMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern BOOL bDisableSwarmonDevice;
extern BOOL bDisableUE9A;
extern BOOL bDisableSSC32;
extern BOOL bDisablePololu[MAX_NB_POLOLU];
extern BOOL bDisableMiniSSC;
extern BOOL bDisableRoboteq[MAX_NB_ROBOTEQ];
extern BOOL bDisableIM483I;
extern BOOL bDisableOntrak;
#pragma endregion
#pragma region Controller parameters
extern double u_max, uw_max, u_coef, uw_coef;
extern double Kp, Ki, Kd1, Kd2; // For heading PID.
extern double uw_derivative_max;
extern double uw_integral_max; // Max influence of the integral part of the heading PID.
extern double cosdelta_angle_threshold; // For heading PID.
extern double wdradius; // Accuracy of the distance control in m.
extern double vrxmax; // Max submarine speed in rad/s.
extern double omegazmax; // Max submarine rotation speed in rad/s.
extern double Kp_z, Kd_z, Ki_z, up_max_z, ud_max_z, ui_max_z,
u_min_z, u_max_z, error_min_z, error_max_z, dz_max_z;
extern double Kp_y, Kd_y, Ki_y, up_max_y, ud_max_y, ui_max_y,
u_min_y, u_max_y, error_min_y, error_max_y, dy_max_y;
extern double Kp_wy, Kd_wy, Ki_wy, up_max_wy, ud_max_wy, ui_max_wy,
u_min_wy, u_max_wy, error_min_wy, error_max_wy, omega_max_wy;
extern double Kp_wx, Kd_wx, Ki_wx, up_max_wx, ud_max_wx, ui_max_wx,
u_min_wx, u_max_wx, error_min_wx, error_max_wx, omega_max_wx;
extern double gamma_infinite; // Angle to go towards the line when far, for line following in rad.
extern double radius; // Accuracy of line/waypoint following in m.
extern double betaside;
extern double betarear;
extern double zeta;
extern double check_strategy_period;
extern double sail_update_period;
extern int sailboattacktype;
extern int sailformulatype;
extern BOOL bCheckRudder;
extern BOOL bCalibrateSail;
extern double sail_calibration_period;
extern double max_distance_around;
extern double min_distance_around;
extern double min_distance_around_full_speed;
extern double amplitude_avoid;
extern double etalement_avoid;
extern BOOL bLat_avoid;
extern BOOL bEnableFluxMotorboat;
extern BOOL bEnableBackwardsMotorboat;
extern int controllerperiod;
#pragma endregion
#pragma region Observer parameters
extern int psi_source, theta_phi_source, x_y_source, z_source;
extern double z_pressure_acc;
extern double dvl_acc;
extern double of_acc;
extern double acousticmodem_acc;
extern double phi_ahrs_acc, theta_ahrs_acc, psi_ahrs_acc,
accrx_ahrs_acc, accry_ahrs_acc, accrz_ahrs_acc,
omegax_ahrs_acc, omegay_ahrs_acc, omegaz_ahrs_acc;
extern double alpha_max_err, d_max_err;
extern interval alphavrxhat, alphaomegazhat, alphafvrxhat, alphafomegazhat, alphazhat, vzuphat,
alphashat, omegashat,
xdotnoise, ydotnoise, zdotnoise, phidotnoise, thetadotnoise, psidotnoise,
vrxdotnoise, vrydotnoise, vrzdotnoise, omegaxdotnoise, omegaydotnoise, omegazdotnoise;
extern double RTK_fixed_acc, RTK_float_acc;
extern double GPS_high_acc, GPS_high_acc_HDOP;
extern int GPS_high_acc_nbsat;
extern double GPS_med_acc, GPS_med_acc_HDOP;
extern int GPS_med_acc_nbsat;
extern double GPS_low_acc, GPS_low_acc_HDOP;
extern int GPS_low_acc_nbsat;
extern int GPS_min_sat_signal;
extern double GPS_submarine_depth_limit;
extern double GPS_SOG_for_valid_COG;
extern int rangescale, sdir;
extern int nb_outliers;
extern double dynamicsonarlocalization_period;
extern int observerperiod;
#pragma endregion
#pragma region Wind, current and waves
extern double vtwind_med, vtwind_var, psitwind_med, psitwind_var, wind_filter_coef;
extern double vc_med, vc_var, psic_med, psic_var, hw_var;
#pragma endregion
#pragma region Power consumption
extern double P_electronics_1, P_electronics_2, P_electronics_3, P_electronics_4;
extern double P_actuators_1, P_actuators_2, P_actuators_3, P_actuators_4;
extern double bat_filter_coef;
#pragma endregion
#pragma region Simulator initial state
extern double x_0, y_0, z_0, phi_0, theta_0, psi_0, vrx_0, vry_0, vrz_0, omegax_0, omegay_0, omegaz_0;
extern double alpha_0, d_0;
#pragma endregion
#pragma region Simulator physical parameters
extern double
x_max_rand_err, x_bias_err,
y_max_rand_err, y_bias_err,
z_max_rand_err, z_bias_err,
phi_max_rand_err, phi_bias_err,
theta_max_rand_err, theta_bias_err,
psi_max_rand_err, psi_bias_err,
vrx_max_rand_err, vrx_bias_err,
vry_max_rand_err, vry_bias_err,
vrz_max_rand_err, vrz_bias_err,
omegaz_max_rand_err, omegaz_bias_err,
alpha_max_rand_err, alpha_bias_err,
d_max_rand_err, d_bias_err,
alphavrx, alphaomegaz, alphafvrx, alphafomegaz, alphaz, vzup,
alphas, omegas;
extern double outliers_ratio;
extern BOOL bNoSimGNSSInsideObstacles;
extern BOOL bRawSimStateInMAVLinkInterface;
extern BOOL bDisablelogsimu;
extern int simulatorperiod;
#pragma endregion
// Environment parameters.
extern double angle_env, lat_env, long_env, alt_env;
extern double MagneticDeclination, AirPressure, WaterVelocityOfSound, WaterFloorAltitude;
extern int nb_circles, nb_walls;
extern vector<double> circles_x, circles_y, circles_r;
extern vector<double> walls_xa, walls_ya, walls_xb, walls_yb;
extern box box_env;
// Environment variables.
extern COORDSYSTEM csMap;
// Simulator variables.
extern double x_sim, y_sim, z_sim, phi_sim, theta_sim, psi_sim, vrx_sim, vry_sim, vrz_sim, vx_sim, vy_sim, vz_sim, omegax_sim, omegay_sim, omegaz_sim;
extern double alpha_sim, d_sim;
// SonarAltitudeEstimation variables.
extern BOOL bSonarAltitudeEstimation;
extern CRITICAL_SECTION SonarAltitudeEstimationCS;
extern double dmin_sonaraltitudeestimation, ratio_sonaraltitudeestimation;
#ifndef DISABLE_OPENCV_SUPPORT
// ExternalVisualLocalization variables.
extern BOOL bExternalVisualLocalization;
extern CRITICAL_SECTION ExternalVisualLocalizationCS;
extern CRITICAL_SECTION ExternalVisualLocalizationOverlayImgCS;
extern IplImage* ExternalVisualLocalizationOverlayImg;
#ifndef USE_OPENCV_HIGHGUI_CPP_API
#else
extern cv::Mat ExternalVisualLocalizationOverlayImgMat;
#endif // !USE_OPENCV_HIGHGUI_CPP_API
extern int hmin_externalvisuallocalization, hmax_externalvisuallocalization, smin_externalvisuallocalization, smax_externalvisuallocalization, vlmin_externalvisuallocalization, vlmax_externalvisuallocalization;
extern BOOL bHExclusive_externalvisuallocalization, bSExclusive_externalvisuallocalization, bVLExclusive_externalvisuallocalization;
extern int r_selpix_externalvisuallocalization, g_selpix_externalvisuallocalization, b_selpix_externalvisuallocalization;
extern int colormodel_externalvisuallocalization;
extern double objMinRadiusRatio_externalvisuallocalization, objRealRadius_externalvisuallocalization, objMinDetectionRatio_externalvisuallocalization, objDetectionRatioDuration_externalvisuallocalization;
extern rmatrix T_externalvisuallocalization;
extern double coef1_angle_externalvisuallocalization, coef2_angle_externalvisuallocalization;
extern double xerr_externalvisuallocalization, yerr_externalvisuallocalization, zerr_externalvisuallocalization, psierr_externalvisuallocalization;
extern int videoid_externalvisuallocalization;
extern double x_externalvisuallocalization, y_externalvisuallocalization, z_externalvisuallocalization;
extern double psi_externalvisuallocalization;
extern double lat_externalvisuallocalization, long_externalvisuallocalization, alt_externalvisuallocalization;
extern double heading_externalvisuallocalization;
extern double detectratio_externalvisuallocalization;
extern BOOL bExternalVisualLocalizationFound;
#endif // !DISABLE_OPENCV_SUPPORT
#pragma region MISSIONS
#ifndef DISABLE_OPENCV_SUPPORT
// Wall variables.
extern BOOL bWallDetection;
extern BOOL bWallTrackingControl;
extern BOOL bWallAvoidanceControl;
extern CRITICAL_SECTION WallCS;
extern CRITICAL_SECTION WallOverlayImgCS;
extern IplImage* WallOverlayImg;
#ifndef USE_OPENCV_HIGHGUI_CPP_API
#else
extern cv::Mat WallOverlayImgMat;
#endif // !USE_OPENCV_HIGHGUI_CPP_API
extern double d0_wall, beta_wall, delta_wall, dmin_wall, dmax_wall, gamma_infinite_wall, r_wall;
extern int bLat_wall;
extern int bBrake_wall;
extern int procid_wall;
extern double u_wall;
extern double d_wall, psi_wall;
// Ball variables.
extern BOOL bBallTrackingControl[MAX_NB_BALL];
extern CRITICAL_SECTION BallCS[MAX_NB_BALL];
extern CRITICAL_SECTION BallOverlayImgCS[MAX_NB_BALL];
extern IplImage* BallOverlayImg[MAX_NB_BALL];
#ifndef USE_OPENCV_HIGHGUI_CPP_API
#else
extern cv::Mat BallOverlayImgMat[MAX_NB_BALL];
#endif // !USE_OPENCV_HIGHGUI_CPP_API
extern int hmin_ball[MAX_NB_BALL], hmax_ball[MAX_NB_BALL], smin_ball[MAX_NB_BALL], smax_ball[MAX_NB_BALL], vlmin_ball[MAX_NB_BALL], vlmax_ball[MAX_NB_BALL];
extern BOOL bHExclusive_ball[MAX_NB_BALL], bSExclusive_ball[MAX_NB_BALL], bVLExclusive_ball[MAX_NB_BALL];
extern int r_selpix_ball[MAX_NB_BALL], g_selpix_ball[MAX_NB_BALL], b_selpix_ball[MAX_NB_BALL];
extern int colormodel_ball[MAX_NB_BALL];
extern double objMinRadiusRatio_ball[MAX_NB_BALL], objRealRadius_ball[MAX_NB_BALL], objMinDetectionRatio_ball[MAX_NB_BALL], objDetectionRatioDuration_ball[MAX_NB_BALL], d0_ball[MAX_NB_BALL];
extern double kh_ball[MAX_NB_BALL], kv_ball[MAX_NB_BALL];
extern int lightMin_ball[MAX_NB_BALL];
extern double lightPixRatio_ball[MAX_NB_BALL];
extern int bAcoustic_ball[MAX_NB_BALL];
extern int bDepth_ball[MAX_NB_BALL];
extern int camdir_ball[MAX_NB_BALL];
extern BOOL bDisableControl_ball[MAX_NB_BALL];
extern BOOL bBrake_ball[MAX_NB_BALL];
extern int objtype_ball[MAX_NB_BALL];
extern double mindistproc_ball[MAX_NB_BALL];
extern int procid_ball[MAX_NB_BALL];
extern int videoid_ball[MAX_NB_BALL];
extern double u_ball[MAX_NB_BALL];
extern double x_ball[MAX_NB_BALL], y_ball[MAX_NB_BALL], z_ball[MAX_NB_BALL];
extern double psi_ball[MAX_NB_BALL];
extern double lat_ball[MAX_NB_BALL], long_ball[MAX_NB_BALL], alt_ball[MAX_NB_BALL];
extern double heading_ball[MAX_NB_BALL];
extern double detectratio_ball[MAX_NB_BALL];
extern BOOL bBallFound[MAX_NB_BALL];
extern int lightStatus_ball[MAX_NB_BALL];
// Surface visual obstacle variables.
extern BOOL bSurfaceVisualObstacleDetection;
extern BOOL bSurfaceVisualObstacleAvoidanceControl;
extern CRITICAL_SECTION SurfaceVisualObstacleCS;
extern CRITICAL_SECTION SurfaceVisualObstacleOverlayImgCS;
extern IplImage* SurfaceVisualObstacleOverlayImg;
#ifndef USE_OPENCV_HIGHGUI_CPP_API
#else
extern cv::Mat SurfaceVisualObstacleOverlayImgMat;
#endif // !USE_OPENCV_HIGHGUI_CPP_API
extern char weather_surfacevisualobstacle;
extern int boatsize_surfacevisualobstacle;
extern double obsMinDetectionRatio_surfacevisualobstacle, obsDetectionRatioDuration_surfacevisualobstacle;
extern int bBrake_surfacevisualobstacle;
extern int procid_surfacevisualobstacle;
extern int videoid_surfacevisualobstacle;
extern double u_surfacevisualobstacle;
extern double detectratio_surfacevisualobstacle;
// Obstacle variables.
extern CRITICAL_SECTION ObstacleCS;
extern CRITICAL_SECTION ObstacleOverlayImgCS;
extern IplImage* ObstacleOverlayImg;
#ifndef USE_OPENCV_HIGHGUI_CPP_API
#else
extern cv::Mat ObstacleOverlayImgMat;
#endif // !USE_OPENCV_HIGHGUI_CPP_API
// Pinger variables.
extern BOOL bPingerTrackingControl;
extern CRITICAL_SECTION PingerCS;
extern CRITICAL_SECTION PingerOverlayImgCS;
extern IplImage* PingerOverlayImg;
#ifndef USE_OPENCV_HIGHGUI_CPP_API
#else
extern cv::Mat PingerOverlayImgMat;
#endif // !USE_OPENCV_HIGHGUI_CPP_API
extern double pulsefreq_pinger, pulselen_pinger, pulsepersec_pinger, hyddist_pinger, hydorient_pinger, preferreddir_pinger;
extern int bUseFile_pinger;
extern double u_pinger;
extern BOOL bPingerFound;
#endif // !DISABLE_OPENCV_SUPPORT
// ExternalProgramTrigger variables.
extern BOOL bExternalProgramTrigger[MAX_NB_EXTERNALPROGRAMTRIGGER];
extern CRITICAL_SECTION ExternalProgramTriggerCS[MAX_NB_EXTERNALPROGRAMTRIGGER];
extern char ExternalProgramTriggerFileName[MAX_NB_EXTERNALPROGRAMTRIGGER][MAX_BUF_LEN];
extern int period_externalprogramtrigger[MAX_NB_EXTERNALPROGRAMTRIGGER];
extern int retrydelay_externalprogramtrigger[MAX_NB_EXTERNALPROGRAMTRIGGER];
extern int nbretries_externalprogramtrigger[MAX_NB_EXTERNALPROGRAMTRIGGER];
extern int procid_externalprogramtrigger[MAX_NB_EXTERNALPROGRAMTRIGGER];
extern BOOL bExternalProgramTriggerDetected[MAX_NB_EXTERNALPROGRAMTRIGGER];
// Follow me variables.
extern BOOL bFollowMeTrackingControl;
extern CRITICAL_SECTION FollowMeCS;
extern double dmin_followme, dmax_followme;
extern double uidle_followme, umin_followme, umax_followme;
extern double spaceperiod_followme;
extern double forbidlat_followme, forbidlong_followme, forbidalt_followme, forbidradius_followme;
extern int target_followme, mode_followme, bDepth_followme;
extern double xtarget_followme, ytarget_followme, ztarget_followme;
extern double forbidx_followme, forbidy_followme, forbidz_followme;
#pragma endregion
// Simulator variables.
extern double alpha_mes_simulator, d_mes_simulator;
extern vector<interval> d_all_mes_simulator;
extern deque<double> alpha_mes_simulator_vector;
extern deque<double> d_mes_simulator_vector;
extern deque< vector<interval> > d_all_mes_simulator_vector;
extern deque<double> t_simulator_history_vector;
extern deque<interval> xhat_simulator_history_vector;
extern deque<interval> yhat_simulator_history_vector;
extern deque<interval> psihat_simulator_history_vector;
extern deque<interval> vrxhat_simulator_history_vector;
extern int GNSSqualitySimulator;
extern BOOL bEnableSimulatedGNSS;
extern BOOL bEnableSimulatedDVL;
// CISCREA variables.
extern BOOL bPauseCISCREA, bRestartCISCREA;
// LIRMIA3 variables.
extern BOOL bPauseLIRMIA3, bRestartLIRMIA3;
#pragma region DEVICES
// gpControl variables.
extern BOOL bPausegpControl, bRestartgpControl;
// PathfinderDVL variables.
extern BOOL bPausePathfinderDVL, bRestartPathfinderDVL;
// NortekDVL variables.
extern BOOL bPauseNortekDVL, bRestartNortekDVL;
// MES variables.
extern BOOL bPauseMES, bRestartMES;
// MDM variables.
extern CRITICAL_SECTION MDMCS;
extern int AcousticCommandMDM;
extern BOOL bPauseMDM, bRestartMDM;
// Seanet variables.
extern int fSeanetOverlayImg;
extern CRITICAL_SECTION SeanetOverlayImgCS;
#ifndef DISABLE_OPENCV_SUPPORT
extern IplImage* SeanetOverlayImg;
#ifndef USE_OPENCV_HIGHGUI_CPP_API
#else
extern cv::Mat SeanetOverlayImgMat;
#endif // !USE_OPENCV_HIGHGUI_CPP_API
#endif // !DISABLE_OPENCV_SUPPORT
extern double alpha_mes_seanet, d_mes_seanet;
extern vector<interval> d_all_mes_seanet;
extern deque<double> alpha_mes_seanet_vector;
extern deque<double> d_mes_seanet_vector;
extern deque< vector<interval> > d_all_mes_seanet_vector;
extern deque<double> t_seanet_history_vector;
extern deque<interval> xhat_seanet_history_vector;
extern deque<interval> yhat_seanet_history_vector;
extern deque<interval> psihat_seanet_history_vector;
extern deque<interval> vrxhat_seanet_history_vector;
extern BOOL bSeanetFromFile;
extern FILE* seanetfile;
extern int seanetfilenextlinecmd;
extern BOOL bPauseSeanet, bRestartSeanet;
// BlueView variables.
extern double alpha_mes_blueview[MAX_NB_BLUEVIEW], d_mes_blueview[MAX_NB_BLUEVIEW];
extern vector<interval> d_all_mes_blueview[MAX_NB_BLUEVIEW];
extern deque<double> alpha_mes_blueview_vector[MAX_NB_BLUEVIEW];
extern deque<double> d_mes_blueview_vector[MAX_NB_BLUEVIEW];
extern deque< vector<interval> > d_all_mes_blueview_vector[MAX_NB_BLUEVIEW];
extern deque<double> t_blueview_history_vector[MAX_NB_BLUEVIEW];
extern deque<interval> xhat_blueview_history_vector[MAX_NB_BLUEVIEW];
extern deque<interval> yhat_blueview_history_vector[MAX_NB_BLUEVIEW];
extern deque<interval> psihat_blueview_history_vector[MAX_NB_BLUEVIEW];
extern deque<interval> vrxhat_blueview_history_vector[MAX_NB_BLUEVIEW];
extern BOOL bPauseBlueView[MAX_NB_BLUEVIEW];
extern BOOL bRestartBlueView[MAX_NB_BLUEVIEW];
// Hokuyo variables.
extern double alpha_mes_hokuyo, d_mes_hokuyo;
extern vector<interval> d_all_mes_hokuyo;
extern deque<double> alpha_mes_hokuyo_vector;
extern deque<double> d_mes_hokuyo_vector;
extern deque< vector<interval> > d_all_mes_hokuyo_vector;
extern deque<double> t_hokuyo_history_vector;
extern deque<interval> xhat_hokuyo_history_vector;
extern deque<interval> yhat_hokuyo_history_vector;
extern deque<interval> psihat_hokuyo_history_vector;
extern deque<interval> vrxhat_hokuyo_history_vector;
extern BOOL bPauseHokuyo, bRestartHokuyo;
// RPLIDAR variables.
extern double alpha_mes_rplidar, d_mes_rplidar;
extern vector<interval> d_all_mes_rplidar;
extern deque<double> alpha_mes_rplidar_vector;
extern deque<double> d_mes_rplidar_vector;
extern deque< vector<interval> > d_all_mes_rplidar_vector;
extern deque<double> t_rplidar_history_vector;
extern deque<interval> xhat_rplidar_history_vector;
extern deque<interval> yhat_rplidar_history_vector;
extern deque<interval> psihat_rplidar_history_vector;
extern deque<interval> vrxhat_rplidar_history_vector;
extern BOOL bPauseRPLIDAR, bRestartRPLIDAR;
// SRF02 variables.
extern double alpha_mes_srf02, d_mes_srf02;
extern vector<interval> d_all_mes_srf02;
extern deque<double> alpha_mes_srf02_vector;
extern deque<double> d_mes_srf02_vector;
extern deque< vector<interval> > d_all_mes_srf02_vector;
extern deque<double> t_srf02_history_vector;
extern deque<interval> xhat_srf02_history_vector;
extern deque<interval> yhat_srf02_history_vector;
extern deque<interval> psihat_srf02_history_vector;
extern deque<interval> vrxhat_srf02_history_vector;
extern BOOL bPauseSRF02, bRestartSRF02;
// ArduinoPressureSensor variables.
extern BOOL bPauseArduinoPressureSensor, bRestartArduinoPressureSensor;
// MS580314BA variables.
extern BOOL bPauseMS580314BA, bRestartMS580314BA;
// MS5837 variables.
extern BOOL bPauseMS5837, bRestartMS5837;
// P33x variables.
extern BOOL bPauseP33x, bRestartP33x;
// RazorAHRS variables.
extern BOOL bPauseRazorAHRS, bRestartRazorAHRS;
// MT variables.
extern BOOL GNSSqualityMT;
extern BOOL bPauseMT, bRestartMT;
// SBG variables.
extern int GNSSqualitySBG;
extern BOOL bPauseSBG, bRestartSBG;
// NMEADevice variables.
extern int GNSSqualityNMEADevice[MAX_NB_NMEADEVICE];
extern BOOL bPauseNMEADevice[MAX_NB_NMEADEVICE];
extern BOOL bRestartNMEADevice[MAX_NB_NMEADEVICE];
// ublox variables.
extern int GNSSqualityublox[MAX_NB_UBLOX];
extern BOOL bPauseublox[MAX_NB_UBLOX];
extern BOOL bRestartublox[MAX_NB_UBLOX];
// MAVLinkDevice variables.
extern BOOL bEnableMAVLinkDeviceIN[MAX_NB_MAVLINKDEVICE];
extern BOOL bDisplayStatusTextMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern int custom_modeMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern int iArmMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern int setattitudetargetperiodMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern int setattitudetargettypeMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern double setattitudetargetrollMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern double setattitudetargetpitchMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern double setattitudetargetyawMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern double setattitudetargetroll_rateMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern double setattitudetargetpitch_rateMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern double setattitudetargetyaw_rateMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern double setattitudetargetthrustMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern BOOL bTakeoffMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern double takeoff_altitudeMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern BOOL bLandMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern double land_yawMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern double land_latitudeMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern double land_longitudeMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern double land_altitudeMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern double u1_servo_out_MAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern double u2_servo_out_MAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern double u3_servo_out_MAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern double u4_servo_out_MAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern double u5_servo_out_MAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern double u6_servo_out_MAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern double u7_servo_out_MAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern double u8_servo_out_MAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern int GNSSqualityMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern BOOL bPauseMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
extern BOOL bRestartMAVLinkDevice[MAX_NB_MAVLINKDEVICE];
// SwarmonDevice variables.
extern BOOL bPauseSwarmonDevice, bRestartSwarmonDevice;
// UE9A variables.
extern BOOL bPauseUE9A, bRestartUE9A;
// SSC32 variables.
extern BOOL bPauseSSC32, bRestartSSC32;
// Pololu variables.
extern double alpha_mes_pololu[MAX_NB_POLOLU], d_mes_pololu[MAX_NB_POLOLU];
extern vector<interval> d_all_mes_pololu[MAX_NB_POLOLU];
extern deque<double> alpha_mes_pololu_vector[MAX_NB_POLOLU];
extern deque<double> d_mes_pololu_vector[MAX_NB_POLOLU];
extern deque< vector<interval> > d_all_mes_pololu_vector[MAX_NB_POLOLU];
extern deque<double> t_pololu_history_vector[MAX_NB_POLOLU];
extern deque<interval> xhat_pololu_history_vector[MAX_NB_POLOLU];
extern deque<interval> yhat_pololu_history_vector[MAX_NB_POLOLU];
extern deque<interval> psihat_pololu_history_vector[MAX_NB_POLOLU];
extern deque<interval> vrxhat_pololu_history_vector[MAX_NB_POLOLU];
extern int ShowGetPositionMaestroPololu[MAX_NB_POLOLU];
extern int SetPositionMaestroPololu[MAX_NB_POLOLU];
extern BOOL bPausePololu[MAX_NB_POLOLU];
extern BOOL bRestartPololu[MAX_NB_POLOLU];
// MiniSSC variables.
extern BOOL bPauseMiniSSC, bRestartMiniSSC;
// Roboteq variables.
extern BOOL bPauseRoboteq[MAX_NB_ROBOTEQ];
extern BOOL bRestartRoboteq[MAX_NB_ROBOTEQ];
// IM483I variables.
extern BOOL bPauseIM483I, bRestartIM483I;
// Ontrak variables.
extern BOOL bPauseOntrak, bRestartOntrak;
// Video variables.
extern CRITICAL_SECTION imgsCS[MAX_NB_VIDEO];
#ifndef DISABLE_OPENCV_SUPPORT
extern IplImage* imgs[MAX_NB_VIDEO];
extern IplImage* imgsbak[MAX_NB_VIDEO];
#ifndef USE_OPENCV_HIGHGUI_CPP_API
#else
extern cv::Mat imgmats[MAX_NB_VIDEO];
extern cv::Mat imgmatsbak[MAX_NB_VIDEO];
#endif // !USE_OPENCV_HIGHGUI_CPP_API
#endif // !DISABLE_OPENCV_SUPPORT
extern double alpha_mes_video[MAX_NB_VIDEO], d_mes_video[MAX_NB_VIDEO];
extern vector<interval> d_all_mes_video[MAX_NB_VIDEO];
extern deque<double> alpha_mes_video_vector[MAX_NB_VIDEO];
extern deque<double> d_mes_video_vector[MAX_NB_VIDEO];
extern deque< vector<interval> > d_all_mes_video_vector[MAX_NB_VIDEO];
extern deque<double> t_video_history_vector[MAX_NB_VIDEO];
extern deque<interval> xhat_video_history_vector[MAX_NB_VIDEO];
extern deque<interval> yhat_video_history_vector[MAX_NB_VIDEO];
extern deque<interval> psihat_video_history_vector[MAX_NB_VIDEO];