Subversion Repositories Projects

Rev

Rev 2299 | Go to most recent revision | Details | Compare with Previous | Last modification | View Log | RSS feed

Rev Author Line No. Line
2287 - 1
using GMap.NET;
2
using GMap.NET.MapProviders;
3
using GMap.NET.WindowsPresentation;
4
using MKLiveView.GMapCustomMarkers;
5
using System;
6
using System.Collections.Generic;
7
using System.ComponentModel;
8
using System.Data;
9
using System.Diagnostics;
10
using System.IO;
11
using System.Linq;
12
using System.Linq.Expressions;
13
using System.Runtime.InteropServices;
14
using System.Text;
15
using System.Threading;
16
using System.Threading.Tasks;
17
using System.Windows;
18
using System.Windows.Controls;
19
using System.Windows.Data;
20
using System.Windows.Documents;
21
using System.Windows.Input;
22
using System.Windows.Interop;
23
using System.Windows.Media;
24
using System.Windows.Media.Animation;
25
using System.Windows.Media.Imaging;
26
using System.Windows.Navigation;
27
using System.Windows.Shapes;
28
using System.Windows.Threading;
29
 
30
namespace MKLiveView
31
{
32
    /// <summary>
33
    /// Interaktionslogik für MainWindow.xaml
34
    /// </summary>
35
    public partial class MainWindow : Window
36
    {
2304 - 37
        #region declarations
38
 
2287 - 39
        GMapMarker copter;
40
        GMapMarker home;
41
        PointLatLng start;
42
        PointLatLng end;
43
        PointLatLng pHome;
44
 
45
 
46
        String[] NC_Error = new string[44]
47
        {
48
            "No Error",
49
            "FC not compatible" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A1_.22FC_not_compatible_.22",
50
            "MK3Mag not compatible" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A2_.22MK3Mag_not_compatible_.22",
51
            "no FC communication" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A3_.22no_FC_communication_.22",
52
            "no compass communication" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A4_.22no_compass_communication_.22",
53
            "no GPS communication" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A5_.22no_GPS_communication_.22",
54
            "bad compass value" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A6_.22bad_compass_value.22",
55
            "RC Signal lost" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A7_.22RC_Signal_lost_.22",
56
            "FC spi rx error" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A8_.22FC_spi_rx_error_.22",
57
            "ERR: no NC communication" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A9:_.22ERR:_no_NC_communication.22",
58
            "ERR: FC Nick Gyro" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A10_.22ERR:_FC_Nick_Gyro.22",
59
            "ERR: FC Roll Gyro" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A11_.22ERR:_FC_Roll_Gyro.22",
60
            "ERR: FC Yaw Gyro" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A12_.22ERR:_FC_Yaw_Gyro.22",
61
            "ERR: FC Nick ACC" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A13_.22ERR:_FC_Nick_ACC.22",
62
            "ERR: FC Roll ACC" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A14_.22ERR:_FC_Roll_ACC.22",
63
            "ERR: FC Z-ACC" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A15_.22ERR:_FC_Z-ACC.22",
64
            "ERR: Pressure sensor" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A16_.22ERR:_Pressure_sensor.22",
65
            "ERR: FC I2C" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A17_.22ERR:_FC_I2C.22",
66
            "ERR: Bl Missing" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A18_.22ERR:_Bl_Missing.22",
67
            "Mixer Error" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A19_.22Mixer_Error.22",
68
            "FC: Carefree Error" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A20_.22FC:_Carefree_Error.22",
69
            "ERR: GPS lost" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A21_.22ERR:_GPS_lost.22",
70
            "ERR: Magnet Error" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A22_.22ERR:_Magnet_Error.22",
71
            "Motor restart" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A23_.22Motor_restart.22",
72
            "BL Limitation" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A24_.22BL_Limitation.22",
73
            "Waypoint range" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A25_.22Waypoint_range.22",
74
            "ERR:No SD-Card" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A26_.22ERR:No_SD-Card.22",
75
            "ERR:SD Logging aborted" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A27_.22ERR:SD_Logging_aborted.22",
76
            "ERR:Flying range!" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A28_.22ERR:Flying_range.21.22",
77
            "ERR:Max Altitude" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A29_.22ERR:Max_Altitude.22",
78
            "No GPS Fix" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A30_.22No_GPS_Fix.22",
79
            "compass not calibrated" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A31_.22compass_not_calibrated.22",
80
            "ERR:BL selftest" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A32_.22ERR:BL_selftest.22",
81
            "no ext. compass" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A33_.22no_ext._compass.22",
82
            "compass sensor" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A34_.22compass_sensor.22",
83
            "FAILSAFE pos.!" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A35_.22FAILSAFE_pos..21__.22",
84
            "ERR:Redundancy" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A36_.22ERR:Redundancy__.22",
85
            "Redundancy test" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A37_.22Redundancy_test_.22",
86
            "GPS Update rate" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A38_.22GPS_Update_rate.22",
87
            "ERR:Canbus" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A39_.22ERR:Canbus.22",
88
            "ERR: 5V RC-Supply" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A40_.22ERR:_5V_RC-Supply.22",
89
            "ERR:Power-Supply" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A41_.22ERR:Power-Supply.22",
90
            "ACC not calibr." + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A42_.22ACC_not_calibr..22",
91
            "ERR:Parachute!" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A43_.22ERR:Parachute.21.22"
92
        };
93
 
94
        [FlagsAttribute]
95
        enum NC_HWError0 : short
96
        {
97
            None = 0,
98
            SPI_RX = 1,
99
            COMPASS_RX = 2,
100
            FC_INCOMPATIBLE = 4,
101
            COMPASS_INCOMPATIBLE = 8,
102
            GPS_RX = 16,
103
            COMPASS_VALUE = 32
104
        };
105
        [FlagsAttribute]
106
        enum FC_HWError0 : short
107
        {
108
            None = 0,
109
            GYRO_NICK = 1,
110
            GYRO_ROLL = 2,
111
            GYRO_YAW = 4,
112
            ACC_NICK = 8,
113
            ACC_ROLL = 16,
114
            ACC_TOP = 32,
115
            PRESSURE = 64,
116
            CAREFREE = 128
117
        };
118
        [FlagsAttribute]
119
        enum FC_HWError1 : short
120
        {
121
            None = 0,
122
            I2C = 1,
123
            BL_MISSING = 2,
124
            SPI_RX = 4,
125
            PPM = 8,
126
            MIXER = 16,
127
            RC_VOLTAGE = 32,
128
            ACC_NOT_CAL = 64,
129
            RES3 = 128
130
        };
131
        public enum LogMsgType { Incoming, Outgoing, Normal, Warning, Error };
132
        // Various colors for logging info
133
        private Color[] LogMsgTypeColor = { Color.FromArgb(255, 43, 145, 175), Colors.Green, Colors.Black, Colors.Orange, Colors.Red };
134
 
135
        bool _bCBInit = true;
136
        bool _init = true;
137
        bool check_HWError = false;
138
 
139
        string filePath = Directory.GetCurrentDirectory();
140
        bool bReadContinously = false;
141
        bool _debugDataAutorefresh = true;
142
        bool _navCtrlDataAutorefresh = true;
143
        bool _blctrlDataAutorefresh = true;
144
        bool _OSDAutorefresh = true;
145
        bool _bErrorLog = false;
146
        bool _bConnErr = false;
147
        bool _bFollowCopter = false;
148
 
149
        bool _bSaveWinStateNormal = true;
150
        bool _bSaveWinStateFull = true;
151
 
152
        double scaleNormalAll = 1;
153
        double scaleNormalTopBar = 1;
154
        double scaleNormalMotors = 1;
155
        double scaleNormalOSD = 1;
156
        double scaleNormalLOG = 1;
157
        double scaleNormalHorizon = 1;
158
 
159
        double scaleFullAll = 1;
160
        double scaleFullTopBar = 1;
161
        double scaleFullMotors = 1;
162
        double scaleFullOSD = 1;
163
        double scaleFullLOG = 1;
164
        double scaleFullHorizon = 1;
165
 
166
        int _iCtrlAct = 0;
167
        int iOSDPage = 0;
168
        int iOSDMax = 0;
169
        int _iLifeCounter = 0;
170
        int crcError = 0;
171
 
2291 - 172
        bool _bSatFix = false;
173
        Storyboard stbSatFixLostAnim;
174
        bool _bAnimSatFixActive = false;
175
        bool _bVoiceSatFixActive = false;
176
        bool _bVoiceSatFixPlay = false;
177
        int _iSatsLast = 0;
178
        int _iSatsJitter = 0;
179
 
180
        bool _bMagneticFieldOK = false;
181
        Storyboard stbMagneticFieldAnim;
182
        bool _bAnimMagneticFieldActive = false;
183
        bool _bVoiceMagneticFieldActive = false;
184
        bool _bVoiceMagneticFieldPlay = false;
185
        int _iMagneticFieldLast = 0;
186
        int _iMagneticFieldJitter = 0;
187
 
188
        bool _bRCLevelOK = false;
189
        Storyboard stbRCLevelAnim;
190
        bool _bAnimRCLevelActive = false;
191
        bool _bVoiceRCLevelActive = false;
192
        bool _bVoiceRCLevelPlay = false;
193
        int _iRCLevelLast = 0;
194
        int _iRCLevelJitter = 0;
195
 
2287 - 196
        int _iMotors = 4;
197
        int _LipoCells = 4;
198
 
199
        double _dLipoVMax = 16.88;
200
        double _dLipoVMin = 12;
201
        double _dThresholdVoltageWarn = 0;
202
        double _dThresholdVoltageCrit = 0;
203
        Storyboard stbVoltageCritAnim;
204
        bool _bCritAnimVoltActive = false;
205
        bool _bCritVoiceVoltActive = false;
2291 - 206
        bool _bWarnVoiceVoltActive = false;
2287 - 207
        bool _bVoiceVoltPlay = false;
208
        double _dVoltLast = 0;
209
        int _iVoltJitter = 0;
210
 
2291 - 211
        double _dThresholdDistanceWarn = 100;
212
        Storyboard stbDistanceWarnAnim;
213
        bool _bAnimDistanceActive = false;
214
        bool _bVoiceDistanceActive = false;
215
        bool _bVoiceDistancePlay = false;
216
        double _dDistanceLast = 0;
217
        int _iDistanceJitter = 0;
218
 
219
        double _dThresholdDistanceMax = 1000;
220
        int _iThresholdRC = 160;
221
        int _iThresholdMagField = 15;
222
 
2295 - 223
        bool _bAutoHome = false;
224
        bool _bFirstSatFix = false;
225
        int _iFirstSatFix = 0;
2291 - 226
 
2287 - 227
        double _dTopHeight = 36;
228
 
229
        int[] serChan = new int[12] { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };
230
        int[] serChan_sub = new int[12] { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };
231
        string[] serChanTitle = new string[12];
232
 
233
        string[] sAnalogLabel = new string[32];
234
        string[] sAnalogData = new string[32];
235
 
236
        int[] iTimings = new int[] {100,150,200,250,300,350,400,450,500,550,600,650,700,750,800,850,900,950,1000,1100,1200,1300,1400,1500,1600,1700,1800,1900,2000 };
237
        int[] iMotors = new int[] {3,4,5,6,7,8,9,10,11,12 };
238
        string[] sLiPoCells = new string[] { "3s", "4s", "5s", "6s" };
239
        /// <summary>
240
        /// interval for sending debugdata (multiplied by 10ms)
241
        /// </summary>
242
        byte debugInterval = 10; //(=> 100ms)
243
        /// <summary>
244
        /// interval for sending BL-CTRL status (multiplied by 10ms)
245
        /// </summary>
246
        byte blctrlInterval = 75;
247
        /// <summary>
248
        /// interval for sending NAV-CTRL status (multiplied by 10ms)
249
        /// </summary>
250
        byte navctrlInterval = 80;
251
        /// <summary>
252
        /// interval for sending OSD page update (multiplied by 10ms)
253
        /// </summary>
254
        byte OSDInterval = 85;
255
        /// <summary>
256
        /// datatable for the debug data array - displayed on settings tabpage in datagridview
257
        /// </summary>
258
        DataTable dtAnalog = new DataTable();
259
        /// <summary>
260
        /// datatable for motordata (current,temp)
261
        /// </summary>
262
        DataTable dtMotors1 = new DataTable();
263
 
264
        DataTable dtWaypoints = new DataTable();
265
        static volatile int _iWP = -1;
266
        bool _bGetWP = false;
267
        static volatile bool _bGetWPCount = false;
268
 
269
        DispatcherTimer timer = new DispatcherTimer();
270
 
271
        /// <summary>
272
        /// stuff for enabeling touch zoom for the map
273
        /// </summary>
274
        Point pTouch1 = new Point(0,0), pTouch2 = new Point(0,0);
275
        int iFirstStylusID = -1;
276
        public string connectButtonText
277
        {
278
            get
279
            {
280
                return bReadContinously ? "stop polling data" + System.Environment.NewLine + "from copter" : "start polling data" + System.Environment.NewLine + "from copter";
281
            }
282
        }
283
 
284
        WinState winState = new WinState();
2304 - 285
        #endregion declarations
2287 - 286
        public MainWindow()
287
        {
288
            InitializeComponent();
289
            _initForm();
290
            _dataTablesInit();
291
            _setupMap();
292
            _init = false;
293
            timer.Tick += new EventHandler(timerEvent);
294
            timer.Interval = new TimeSpan(0, 0, 1);
295
            timer.Start();
296
        }
297
 
298
        #region init
299
        void _initForm()
300
        {
301
            _readIni();
302
            if (_bSaveWinStateNormal)
303
                _setScaleSliders(false);
304
            cBoxTimingsDebug.ItemsSource =
305
                cBoxTimingsNav.ItemsSource =
306
                cBoxTimingsBl.ItemsSource =
307
                cBoxTimingsOSD.ItemsSource =
308
                iTimings;
309
            cBoxLiPoCells.ItemsSource = sLiPoCells;
310
            cBoxLiPoCells.SelectedItem = _LipoCells.ToString() + "s";
311
            _LipoMinMax();
312
            sliderThresholdVoltageWarn.Value = _dThresholdVoltageWarn;
313
            sliderThresholdVoltageCrit.Value = _dThresholdVoltageCrit;
314
            checkBoxThresholdVoltageVoice.IsChecked = _bVoiceVoltPlay;
2291 - 315
            checkBoxSatfixLost.IsChecked = _bVoiceSatFixPlay;
316
            checkBoxMagneticField.IsChecked = _bVoiceMagneticFieldPlay;
317
            checkBoxThresholdDistanceVoice.IsChecked = _bVoiceDistancePlay;
318
            sliderThresholdDistanceWarn.Value = _dThresholdDistanceWarn;
319
            checkBoxRClevel.IsChecked = _bVoiceRCLevelPlay;
2287 - 320
 
2291 - 321
            sliderThresholdDistanceWarn.Maximum = _dThresholdDistanceMax;
322
 
2287 - 323
            cBoxMotors.ItemsSource = iMotors;
324
            cBoxMotors.SelectedItem = _iMotors;
325
 
326
            serialPortCtrl.PortClosed += serialPortCtrl_PortClosed;
327
            serialPortCtrl.PortOpened += serialPortCtrl_PortOpened;
328
            serialPortCtrl.DataReceived += processMessage;
329
 
330
            chkbAutoBL.IsChecked = _blctrlDataAutorefresh;
331
            chkbAutoDbg.IsChecked = _debugDataAutorefresh;
332
            chkbAutoNav.IsChecked = _navCtrlDataAutorefresh;
333
            chkbAutoOSD.IsChecked = _OSDAutorefresh;
334
 
335
            cBoxTimingsDebug.SelectedItem = debugInterval * 10;
336
            cBoxTimingsNav.SelectedItem = navctrlInterval * 10;
337
            cBoxTimingsBl.SelectedItem = blctrlInterval * 10;
338
            cBoxTimingsOSD.SelectedItem = OSDInterval * 10;
2295 - 339
            checkBoxAutoSetHP.IsChecked = _bAutoHome;
2287 - 340
            checkBoxFollowCopter.IsChecked = _bFollowCopter;
341
 
342
 
343
        }
344
        /// <summary>
345
        /// initialize the datatables
346
        /// with columnnames etc
347
        /// </summary>
348
        void _dataTablesInit()
349
        {
350
            //dtAnalog.Columns.Add("ID");
351
            //dtAnalog.Columns.Add("Value");
352
         //   dataGridView1.DataSource = dtAnalog;
353
 
354
            dtMotors1.Columns.Add("#");
355
            if (Thread.CurrentThread.CurrentUICulture.Name == "")
356
                dtMotors1.Columns.Add("Current");
357
            else
358
                dtMotors1.Columns.Add("Strom");
359
            dtMotors1.Columns.Add("Temp");
360
            //dtMotors2.Columns.Add("#");
361
            //if (Thread.CurrentThread.CurrentUICulture.Name == "")
362
            //    dtMotors2.Columns.Add("Current");
363
            //else
364
            //    dtMotors2.Columns.Add("Strom");
365
            //dtMotors2.Columns.Add("Temp");
366
            dgvMotors1.DataContext = dtMotors1.DefaultView;
367
            //dgvMotors2.DataContext = dtMotors2.DefaultView;
368
            _initDTMotors();
369
            //dgvMotors1.Columns[0].Width = 24;
370
            //dgvMotors1.Columns[1].Width = 74;
371
            //dgvMotors1.Columns[2].Width = 74;
372
            //dgvMotors2.Columns[0].Width = 24;
373
            //dgvMotors2.Columns[1].Width = 74;
374
            //dgvMotors2.Columns[2].Width = 74;
375
 
376
            dtWaypoints.Columns.Add("Index");
377
            dtWaypoints.Columns.Add("Type");
378
            dtWaypoints.Columns.Add("Name");
379
            dtWaypoints.Columns.Add("Latitude");
380
            dtWaypoints.Columns.Add("Longitude");
381
            dtWaypoints.Columns.Add("Altitude");
382
            dtWaypoints.Columns.Add("Heading");
383
            dtWaypoints.Columns.Add("Speed");
384
            dtWaypoints.Columns.Add("Altitude rate");
385
            dtWaypoints.Columns.Add("Tol radius");
386
            dtWaypoints.Columns.Add("Hold time");
387
            dtWaypoints.Columns.Add("AutoTrigger");
388
            dtWaypoints.Columns.Add("Cam angle");
389
            dtWaypoints.Columns.Add("Event");
390
            dtWaypoints.Columns.Add("Eventchan Val");
391
            dtWaypoints.Columns.Add("Status");
392
            dtWaypoints.PrimaryKey = new DataColumn[] { dtWaypoints.Columns["Index"] };
393
            dgvWP.DataContext = dtWaypoints.DefaultView;
394
            Setter setter = new Setter(ContentControl.PaddingProperty, new Thickness(5,0,5,0));
395
            Style style = new Style(typeof(System.Windows.Controls.Primitives.DataGridColumnHeader));
396
            style.Setters.Add(setter);
397
            setter = new Setter(ContentControl.BackgroundProperty, new SolidColorBrush(Colors.Transparent));
398
            style.Setters.Add(setter);
399
            setter = new Setter(ContentControl.ForegroundProperty, new SolidColorBrush(Colors.White));
400
            style.Setters.Add(setter);
401
            dgvWP.ColumnHeaderStyle = new Style();
402
            dgvWP.ColumnHeaderStyle = style;
403
        }
404
        /// <summary>
405
        /// initialize the 2 datatables for motor values
406
        /// dtMotors1 - motor 1 - 4
407
        /// dtMotors2 - motor 5 - 8
408
        /// DataGridView dgvMotors1/2 are bound to dtMotors1/2 
409
        /// </summary>
410
        void _initDTMotors()
411
        {
412
            for (int i = 0; i < 12; i++)
413
            {
414
                if (dtMotors1.Rows.Count < 12)
415
                    dtMotors1.Rows.Add((i + 1).ToString(), "NA", "NA");
416
                else
417
                {
418
                    dtMotors1.Rows[i].SetField(1, "NA");
419
                    dtMotors1.Rows[i].SetField(2, "NA");
420
                }
421
                //if (dtMotors2.Rows.Count < 4)
422
                //    dtMotors2.Rows.Add((i + 5).ToString(), "NA", "NA");
423
                //else
424
                //{
425
                //    dtMotors2.Rows[i].SetField(1, "NA");
426
                //    dtMotors2.Rows[i].SetField(2, "NA");
427
                //}
428
            }
429
           // Dispatcher.Invoke((Action)(() => dgvMotors1.UpdateLayout()));
430
            //dgvMotors2.Invoke((Action)(() => dgvMotors2.Refresh()));
431
        }
432
 
433
        #endregion init
434
 
435
        #region events
436
        private void serialPortCtrl_PortOpened()
437
        {
438
            Dispatcher.Invoke(() => imageWiFi.Source = new BitmapImage(new Uri("Images/WiFi_G.png", UriKind.Relative)));
439
            _getVersion();
440
            Thread.Sleep(100);
441
            //_OSDMenue(0);
442
            //Thread.Sleep(200);
443
            //_sendSerialData();
444
            _readCont(true);
445
        }
446
        private void serialPortCtrl_PortClosed()
447
        {
448
            Dispatcher.Invoke(() => imageWiFi.Source = new BitmapImage(new Uri("Images/WiFi_W.png", UriKind.Relative)));
449
            _readCont(false);
450
        }
451
        void timerEvent(object sender, EventArgs e)
452
        {
453
            if (bReadContinously)
454
            {
455
                if (_debugDataAutorefresh) { _readDebugData(true); Thread.Sleep(10); }
456
 
457
                if (_blctrlDataAutorefresh) { _readBLCtrl(true); Thread.Sleep(10); }
458
 
459
                if (_navCtrlDataAutorefresh && _iCtrlAct == 2) { _readNavData(true); Thread.Sleep(10); }
460
                check_HWError = true;
461
                _getVersion();
462
                Thread.Sleep(10);
463
                if (_OSDAutorefresh)
464
                {
465
                    if (iOSDMax == 0 | cbOSD.Items.Count != iOSDMax)
466
                        _initOSDCB();
467
                    _OSDMenueAutoRefresh();
468
                }
469
                if (_iLifeCounter > 0)
470
                {
471
                    Dispatcher.Invoke(() => imageConn.Source = new BitmapImage(new Uri("Images/Data_G.png", UriKind.Relative)));
472
                  //  Dispatcher.Invoke((Action)(() => rctConnection.Fill = Brushes.LightGreen));
473
                    _iLifeCounter = 0;
474
                    _bConnErr = false;
475
                }
476
                else
477
                {
478
                    if (!_bConnErr)
479
                    {
480
                        Log(LogMsgType.Error, "No communication to NC/FC!");
481
                        Dispatcher.Invoke(() => imageConn.Source = new BitmapImage(new Uri("Images/Data_R.png", UriKind.Relative)));
482
                       // Dispatcher.Invoke((Action)(() => rctConnection.Fill = Brushes.Red));
483
                        _bConnErr = true;
484
                    }
485
                }
486
            }
487
        }
488
 
489
        private void labelData_MouseDown(object sender, MouseButtonEventArgs e)
490
        {
491
            GridData.Visibility = GridData.Visibility == Visibility.Collapsed ? Visibility.Visible : Visibility.Collapsed;
492
            GridSettings.Visibility = GridWP.Visibility = Visibility.Collapsed;
493
        }
494
        private void labelMotorData_MouseDown(object sender, MouseButtonEventArgs e)
495
        {
496
            GridMotors.Visibility = GridMotors.Visibility == Visibility.Hidden ? Visibility.Visible : Visibility.Hidden;
497
            if (GridMotors.IsVisible)
498
                _setMotorGridSize();
499
        }
500
        private void labelSettings_MouseDown(object sender, MouseButtonEventArgs e)
501
        {
502
            GridData.Visibility = GridWP.Visibility = Visibility.Collapsed;
503
            GridSettings.Visibility = GridSettings.Visibility == Visibility.Collapsed ? Visibility.Visible : Visibility.Collapsed;
504
        }
505
        private void labelLog_MouseDown(object sender, MouseButtonEventArgs e)
506
        {
507
            GridLog.Visibility = GridLog.Visibility == Visibility.Collapsed ? Visibility.Visible : Visibility.Collapsed;
508
        }
509
        private void labelOSD_MouseDown(object sender, MouseButtonEventArgs e)
510
        {
511
            GridOSD.Visibility = GridOSD.Visibility == Visibility.Hidden ? Visibility.Visible : Visibility.Hidden;
512
        }
513
        private void labelWaypoints_MouseDown(object sender, MouseButtonEventArgs e)
514
        {
515
            GridData.Visibility = GridSettings.Visibility = Visibility.Collapsed;
516
            GridWP.Visibility = GridWP.Visibility == Visibility.Collapsed ? Visibility.Visible : Visibility.Collapsed;
517
        }
518
 
519
        private void btnGetWP_Click(object sender, RoutedEventArgs e)
520
        {
521
            Thread t = new Thread(new ThreadStart(_getWP));
522
            t.Start();
523
        }
524
        private void btnSendWPList_Click(object sender, RoutedEventArgs e)
525
        {
526
 
527
        }
528
 
529
        private void btnConnectToCopter_Click(object sender, RoutedEventArgs e)
530
        {
531
            if (!serialPortCtrl.Port.IsOpen)
532
                serialPortCtrl.Connect(true);
533
            else
534
                _readCont(!bReadContinously);
535
        }
536
        private void btnSetHP_Click(object sender, RoutedEventArgs e)
537
        {
538
            setHomePos();
539
        }
540
        private void btnClearHP_Click(object sender, RoutedEventArgs e)
541
        {
542
            clearHomePos();
543
        }
544
        private void btnGotoHP_Click(object sender, RoutedEventArgs e)
545
        {
546
            if (home != null && MainMap.Markers.Contains(home))
547
                MainMap.Position = home.Position;
548
        }
2295 - 549
        private void checkBoxAutoSetHP_Click(object sender, RoutedEventArgs e)
550
        {
551
            _bAutoHome = (bool)checkBoxAutoSetHP.IsChecked;
552
        }
2287 - 553
        private void chkBoxSaveNormalState_Click(object sender, RoutedEventArgs e)
554
        {
555
            _bSaveWinStateNormal = (bool)chkBoxSaveNormalState.IsChecked;
556
        }
557
        private void chkBoxSaveFullScreenState_Click(object sender, RoutedEventArgs e)
558
        {
559
            _bSaveWinStateFull = (bool)chkBoxSaveFullScreenState.IsChecked;
560
        }
561
 
2291 - 562
        #region thresholds
2287 - 563
        private void sliderThresholdVoltageWarn_ValueChanged(object sender, RoutedPropertyChangedEventArgs<double> e)
564
        {
565
            if(!_init)
566
                _dThresholdVoltageWarn = sliderThresholdVoltageWarn.Value;
567
        }
568
        private void sliderThresholdVoltageCrit_ValueChanged(object sender, RoutedPropertyChangedEventArgs<double> e)
569
        {
570
            if(!_init)
571
                _dThresholdVoltageCrit = sliderThresholdVoltageCrit.Value;
572
        }
573
        private void checkBoxThresholdVoltageVoice_Click(object sender, RoutedEventArgs e)
574
        {
575
            _bVoiceVoltPlay = (bool)checkBoxThresholdVoltageVoice.IsChecked;
576
        }
2291 - 577
 
578
        private void sliderThresholdDistanceWarn_ValueChanged(object sender, RoutedPropertyChangedEventArgs<double> e)
579
        {
580
            if(!_init)
581
                _dThresholdDistanceWarn = sliderThresholdDistanceWarn.Value;
582
        }
583
        private void checkBoxThresholdDistanceVoice_Click(object sender, RoutedEventArgs e)
584
        {
585
            _bVoiceDistancePlay = (bool)checkBoxThresholdDistanceVoice.IsChecked;
586
        }
587
 
588
        private void checkBoxSatfixLost_Click(object sender, RoutedEventArgs e)
589
        {
590
            _bVoiceSatFixPlay = (bool)checkBoxSatfixLost.IsChecked;
591
        }
592
        private void checkBoxMagneticField_Click(object sender, RoutedEventArgs e)
593
        {
594
            _bVoiceMagneticFieldPlay = (bool)checkBoxMagneticField.IsChecked;
595
        }
596
        private void checkBoxRClevel_Click(object sender, RoutedEventArgs e)
597
        {
598
            _bVoiceRCLevelPlay = (bool)checkBoxRClevel.IsChecked;
599
        }
600
        #endregion thresholds
601
 
2287 - 602
        private void buttonSwitchNC_Click(object sender, RoutedEventArgs e)
603
        {
604
            _switchToNC();
605
        }
606
 
607
        private void Window_Loaded(object sender, RoutedEventArgs e)
608
        {
609
            stbVoltageCritAnim = TryFindResource("VoltageCritAnim") as Storyboard;
2291 - 610
            stbSatFixLostAnim = TryFindResource("SatFixLostAnim") as Storyboard;
611
            stbMagneticFieldAnim = TryFindResource("MagneticFieldCritAnim") as Storyboard;
612
            stbDistanceWarnAnim = TryFindResource("DistanceCritAnim") as Storyboard;
613
            stbRCLevelAnim = TryFindResource("RCCritAnim") as Storyboard;
2287 - 614
            _setMotorGridSize();
615
        }
616
        #endregion events
617
 
618
        #region GMap
619
 
620
        void _setupMap()
621
        {
622
            MainMap.Manager.Mode = AccessMode.ServerAndCache;
623
            MainMap.MapProvider = GMapProviders.BingHybridMap;
624
            MainMap.SetPositionByKeywords("Landshut");
625
            MainMap.MinZoom = 0;
626
            MainMap.MaxZoom = 24;
627
            MainMap.Zoom = 16;
628
            MainMap.ShowCenter = true;
629
            MainMap.ShowTileGridLines = false;
630
            sliderMapZoom.Value = 16;
631
            comboBoxMapType.ItemsSource = providerList;
632
            comboBoxMapType.DisplayMemberPath = "Name";
633
            comboBoxMapType.SelectedItem = MainMap.MapProvider;
634
 
635
            // acccess mode
636
            comboBoxMode.ItemsSource = Enum.GetValues(typeof(AccessMode));
637
            comboBoxMode.SelectedItem = MainMap.Manager.Mode;
638
 
639
        }
640
 
641
        /// <summary>
642
        /// selection of relevant map providers --> if You need more, You can change the line:
643
        ///     comboBoxMapType.ItemsSource = providerList; 
644
        /// to:
645
        ///     comboBoxMapType.ItemsSource = GMapProviders.List;
646
        /// in _setupMap()
647
        /// or add items here:
648
        /// </summary>
649
        List<GMap.NET.MapProviders.GMapProvider> providerList = new List<GMap.NET.MapProviders.GMapProvider>
650
        { GMap.NET.MapProviders.GMapProviders.OpenCycleMap, GMap.NET.MapProviders.GMapProviders.OpenCycleLandscapeMap, GMap.NET.MapProviders.GMapProviders.OpenCycleTransportMap,
651
        GMap.NET.MapProviders.GMapProviders.BingMap,GMap.NET.MapProviders.GMapProviders.BingSatelliteMap,GMap.NET.MapProviders.GMapProviders.BingHybridMap,
652
        GMap.NET.MapProviders.GMapProviders.GoogleMap,GMap.NET.MapProviders.GMapProviders.GoogleSatelliteMap,GMap.NET.MapProviders.GMapProviders.GoogleHybridMap,GMap.NET.MapProviders.GMapProviders.GoogleTerrainMap,
653
        GMap.NET.MapProviders.GMapProviders.OviMap,GMap.NET.MapProviders.GMapProviders.OviSatelliteMap,GMap.NET.MapProviders.GMapProviders.OviHybridMap,GMap.NET.MapProviders.GMapProviders.OviTerrainMap};
654
 
655
        private void MainMap_Loaded(object sender, RoutedEventArgs e)
656
        {
657
            MainMap.Manager.Mode = AccessMode.ServerAndCache;
658
            copter = new GMapMarker(MainMap.Position);
659
            copter.Shape = new CustomMarkerCopter(this, copter, MainMap.Position.Lat.ToString("0.#######°") + System.Environment.NewLine + MainMap.Position.Lng.ToString("0.#######°"));
660
            copter.Offset = new System.Windows.Point(-18, -18);
661
            copter.ZIndex = int.MaxValue;
662
            MainMap.Markers.Add(copter);
663
            copter.Position = MainMap.Position;
664
        }
665
        void setHomePos()
666
        {
667
            pHome = MainMap.Position;
668
            if (!MainMap.Markers.Contains(home))
669
            {
670
                home = new GMapMarker(MainMap.Position);
671
                home.Shape = new CustomMarkerHome(this, home, MainMap.Position.Lat.ToString("0.#######°") + System.Environment.NewLine + MainMap.Position.Lng.ToString("0.#######°"));
672
                home.Offset = new System.Windows.Point(-18, -18);
673
                // home.ZIndex = int.MaxValue;
674
                MainMap.Markers.Add(home);
675
            }
676
            home.Position = MainMap.Position;
677
            ((CustomMarkerHome)(home.Shape)).setText(MainMap.Position.Lat.ToString("0.#######°") + System.Environment.NewLine + MainMap.Position.Lng.ToString("0.#######°"));
678
        }
679
        void clearHomePos()
680
        {
681
            MainMap.Markers.Remove(home);
682
        }
683
 
684
        // access mode
685
        private void comboBoxMode_DropDownClosed(object sender, EventArgs e)
686
        {
687
            MainMap.Manager.Mode = (AccessMode)comboBoxMode.SelectedItem;
688
            MainMap.ReloadMap();
689
        }
690
        // zoom up
691
        private void czuZoomUp_Click(object sender, RoutedEventArgs e)
692
        {
693
            MainMap.Zoom = ((int)MainMap.Zoom) + 1;
694
        }
695
 
696
        // zoom down
697
        private void czuZoomDown_Click(object sender, RoutedEventArgs e)
698
        {
699
            MainMap.Zoom = ((int)(MainMap.Zoom + 0.99)) - 1;
700
        }
701
 
702
        // prefetch
703
        private void buttonPrefetch_Click(object sender, RoutedEventArgs e)
704
        {
705
            RectLatLng area = MainMap.SelectedArea;
706
            if (!area.IsEmpty)
707
            {
708
                for (int i = (int)MainMap.Zoom; i <= MainMap.MaxZoom; i++)
709
                {
710
                    MessageBoxResult res = MessageBox.Show("Ready ripp at Zoom = " + i + " ?", "GMap.NET", MessageBoxButton.YesNoCancel);
711
 
712
                    if (res == MessageBoxResult.Yes)
713
                    {
714
                        TilePrefetcher obj = new TilePrefetcher();
715
                        obj.Owner = this;
716
                        obj.ShowCompleteMessage = true;
717
                        obj.Start(area, i, MainMap.MapProvider, 100);
718
                    }
719
                    else if (res == MessageBoxResult.No)
720
                    {
721
                        continue;
722
                    }
723
                    else if (res == MessageBoxResult.Cancel)
724
                    {
725
                        break;
726
                    }
727
                }
728
            }
729
            else
730
            {
731
                MessageBox.Show("Select map area holding ALT", "GMap.NET", MessageBoxButton.OK, MessageBoxImage.Exclamation);
732
            }
733
        }
734
 
735
        // goto by geocoder
736
        private void buttonGeoCoding_Click(object sender, RoutedEventArgs e)
737
        {
738
            _goto_byGeoCoder();
739
        }
740
        // goto by geocoder
741
        private void textBoxGeo_KeyUp(object sender, System.Windows.Input.KeyEventArgs e)
742
        {
743
            if (e.Key == System.Windows.Input.Key.Enter)
744
                _goto_byGeoCoder();
745
        }
746
        void _goto_byGeoCoder()
747
        {
748
            GeoCoderStatusCode status = MainMap.SetPositionByKeywords(textBoxGeo.Text);
749
            if (status != GeoCoderStatusCode.G_GEO_SUCCESS)
750
            {
751
                MessageBox.Show("Geocoder can't find: '" + textBoxGeo.Text + "', reason: " + status.ToString(), "GMap.NET", MessageBoxButton.OK, MessageBoxImage.Exclamation);
752
            }
753
        }
754
        private void buttonGeoLoc_Click(object sender, RoutedEventArgs e)
755
        {
756
            try
757
            {
758
                double lat = double.Parse(textBoxLat.Text, System.Globalization.CultureInfo.InvariantCulture);
759
                double lng = double.Parse(textBoxLng.Text, System.Globalization.CultureInfo.InvariantCulture);
760
 
761
                MainMap.Position = new PointLatLng(lat, lng);
762
            }
763
            catch (Exception ex)
764
            {
765
                MessageBox.Show("incorrect coordinate format: " + ex.Message);
766
            }
767
 
768
        }
769
 
770
        private void ReloadMap_Click(object sender, RoutedEventArgs e)
771
        {
772
            MainMap.ReloadMap();
773
        }
774
 
775
        private void MainMap_OnPositionChanged(PointLatLng point)
776
        {
777
            if (_bFollowCopter)
778
                _setCopterData(MainMap.Position);
779
        }
780
 
781
        private void MainMap_OnMapZoomChanged()
782
        {
783
            if (_bFollowCopter)
784
                _setCopterData(MainMap.Position);
785
            if((int)sliderMapZoom.Value != MainMap.Zoom)
786
                sliderMapZoom.Value = MainMap.Zoom;
787
        }
788
 
789
        void _setCopterData(PointLatLng p)
790
        {
791
            Dispatcher.Invoke(() =>
792
            {
793
                copter.Position = p;
794
                ((CustomMarkerCopter)(copter.Shape)).setText(p.Lat.ToString("0.#######°") + System.Environment.NewLine + p.Lng.ToString("0.#######°"));
795
                textBoxLat_currentPos.Text = p.Lat.ToString() + "°";
796
                textBoxLng_currentPos.Text = p.Lng.ToString() + "°";
797
            });
798
            if (home != null && MainMap.Markers.Contains(home))
799
            {
800
                Dispatcher.Invoke(() => ArtHor.rotateHome = GMapProviders.EmptyProvider.Projection.GetBearing(copter.Position, home.Position));
801
                double d = GMapProviders.EmptyProvider.Projection.GetDistance(home.Position, copter.Position);
802
                Dispatcher.Invoke(() => tbTopDistanceHP.Text = (d * 1000).ToString("0.0 m"));
2291 - 803
 
804
                if(d*1000 < _dThresholdDistanceWarn)
805
                {
806
                    _iDistanceJitter = 0; _bVoiceDistanceActive = false;
807
                    if (stbDistanceWarnAnim != null && _bAnimDistanceActive)
808
                    {
809
                        Dispatcher.Invoke(() => stbDistanceWarnAnim.Stop());
810
                        _bAnimDistanceActive = false;
811
                    }
812
                }
813
                else
814
                {
815
                    if (_iDistanceJitter < 20)
816
                    { _iDistanceJitter++; }
817
                    if (_iDistanceJitter == 20)
818
                    {
819
                        if (stbDistanceWarnAnim != null && !_bAnimDistanceActive)
820
                        {
821
                            Dispatcher.Invoke(() => stbDistanceWarnAnim.Begin());
822
                            _bAnimDistanceActive = true;
823
                        }
824
                        if (_bVoiceDistancePlay && !_bVoiceDistanceActive)
825
                        {
2295 - 826
                            Thread t = new Thread(()=>_mediaPlayer("Voice\\Distance.mp3"));
827
                            t.Start();
2291 - 828
                            _bVoiceDistanceActive = true;
829
                        }
830
                        _iDistanceJitter++;
831
                    }
832
                }
2287 - 833
            }
834
        }
835
 
836
        private void checkBoxFollowCopter_Click(object sender, RoutedEventArgs e)
837
        {
838
            _bFollowCopter = (bool)checkBoxFollowCopter.IsChecked;
839
        }
840
 
841
        private void sliderMapZoom_ValueChanged(object sender, RoutedPropertyChangedEventArgs<double> e)
842
        {
843
            if (MainMap.Zoom != sliderMapZoom.Value)
844
                MainMap.Zoom = (int)sliderMapZoom.Value;
845
        }
846
        #region Touch zooming hackattack ;) 
847
        /// <summary>
848
        /// inspired by http://www.codeproject.com/Articles/692286/WPF-and-multi-touch
849
        /// </summary>
850
        bool bFirstAccess = true;
851
        double dDistance = 0;
852
        int iZoom;
853
        private void MainMap_StylusDown(object sender, StylusDownEventArgs e)
854
        {
855
            var id = e.StylusDevice.Id;
856
            e.StylusDevice.Capture(MainMap);
857
            if (iFirstStylusID == -1)
858
            {
859
                iFirstStylusID = id;
860
            }
861
            else
862
            {
863
 
864
                MainMap.CanDragMap = false;
865
            }
866
        }
867
        private void MainMap_StylusUp(object sender, StylusEventArgs e)
868
        {
869
            MainMap.ReleaseStylusCapture();
870
            iFirstStylusID = -1;
871
            bFirstAccess = true;
872
            MainMap.CanDragMap = true;
873
            iZoom = 0;
874
        }
875
        private void MainMap_StylusMove(object sender, StylusEventArgs e)
876
        {
877
            var id = e.StylusDevice.Id;
878
            var tp = e.GetPosition(MainMap);
879
 
880
            // This is the first Stylus point; just record its position. 
881
            if (id == iFirstStylusID)
882
            {
883
                pTouch1.X = tp.X;
884
                pTouch1.Y = tp.Y;
885
            }
886
            else
887
            if (iFirstStylusID > -1)
888
            {
889
                pTouch2.X = tp.X;
890
                pTouch2.Y = tp.Y;
891
                double distance = Point.Subtract(pTouch1, pTouch2).Length;
892
                if (!bFirstAccess)
893
                {
894
                    if (distance > dDistance)
895
                        iZoom++;
896
                    else
897
                        if (distance < dDistance)
898
                        iZoom--;
899
                }
900
                if (iZoom > 30)
901
                {
902
                    iZoom = 0;
903
                    Dispatcher.Invoke(() => sliderMapZoom.Value += 1);
904
                }
905
                if (iZoom < -30)
906
                {
907
                    iZoom = 0;
908
                    Dispatcher.Invoke(() => sliderMapZoom.Value -= 1);
909
                }
910
                dDistance = distance;
911
                bFirstAccess = false;
912
            }
913
        }
914
        #endregion Touch zooming hackattack ;)
915
 
916
        #endregion GMap
917
 
918
        #region settings
919
        private void cBoxTimingsDebug_DropDownClosed(object sender, EventArgs e)
920
        {
921
            if(! _bCBInit && cBoxTimingsDebug.SelectedIndex > -1)
922
                debugInterval = (byte)(Convert.ToInt16(cBoxTimingsDebug.SelectedItem) / 10);
923
        }
924
        private void cBoxTimingsNav_DropDownClosed(object sender, EventArgs e)
925
        {
926
            if(! _bCBInit && cBoxTimingsNav.SelectedIndex > -1)
927
                navctrlInterval = (byte)(Convert.ToInt16(cBoxTimingsNav.SelectedItem) / 10);
928
        }
929
        private void cBoxTimingsBl_DropDownClosed(object sender, EventArgs e)
930
        {
931
            if (!_bCBInit && cBoxTimingsBl.SelectedIndex > -1)
932
                blctrlInterval = (byte)(Convert.ToInt16(cBoxTimingsBl.SelectedItem) / 10);
933
        }
934
        private void cBoxTimingsOSD_DropDownClosed(object sender, EventArgs e)
935
        {
936
            if (!_bCBInit && cBoxTimingsOSD.SelectedIndex > -1)
937
                OSDInterval = (byte)(Convert.ToInt16(cBoxTimingsOSD.SelectedItem) / 10);
938
        }
939
        private void chkbAutoDbg_Click(object sender, RoutedEventArgs e)
940
        {
941
            if (!_init) _debugDataAutorefresh = (bool)chkbAutoDbg.IsChecked;
942
        }
943
        private void chkbAutoNav_Click(object sender, RoutedEventArgs e)
944
        {
945
            if (!_init) _navCtrlDataAutorefresh = (bool)chkbAutoNav.IsChecked;
946
        }
947
        private void chkbAutoBL_Click(object sender, RoutedEventArgs e)
948
        {
949
            if (!_init) _blctrlDataAutorefresh = (bool)chkbAutoBL.IsChecked;
950
        }
951
        private void chkbAutoOSD_Click(object sender, RoutedEventArgs e)
952
        {
953
            if (!_init) _OSDAutorefresh = (bool)chkbAutoOSD.IsChecked;
954
        }
955
 
956
        private void cBoxLiPoCells_DropDownClosed(object sender, EventArgs e)
957
        {
958
            if (cBoxLiPoCells.SelectedIndex > -1)
959
            {
960
                _LipoCells = cBoxLiPoCells.SelectedIndex + 3;
961
                _LipoMinMax();
962
            }
963
        }
964
        void _LipoMinMax()
965
        {
966
            _dLipoVMax = (double)(_LipoCells) * 4.22;
967
            _dLipoVMin = (double)_LipoCells * 3;
968
            pbTopVoltage.Maximum = _dLipoVMax;
969
            pbTopVoltage.Minimum = _dLipoVMin;
970
            sliderThresholdVoltageWarn.Maximum = _dLipoVMax;
971
            sliderThresholdVoltageWarn.Minimum = _dLipoVMin;
972
        }
973
        private void cBoxMotors_DropDownClosed(object sender, EventArgs e)
974
        {
975
            if (cBoxMotors.SelectedIndex > -1)
976
            {
977
                _iMotors = cBoxMotors.SelectedIndex + 3;
978
                Dispatcher.Invoke(() =>
979
                {
980
                    dgvMotors1.Height = (272 / 12.6) * (_iMotors + 1);  //272 / 12.6 --> Workaround, cause the headerheight = NaN...?
981
                    GridMotors.Height = dgvMotors1.Height + 10;
982
                });
983
            }
984
        }
985
        void _setMotorGridSize()
986
        {
987
            if (dgvMotors1.Columns.Count > 2)
988
            {
989
                dgvMotors1.Columns[0].Width = 24;
990
                dgvMotors1.Columns[1].Width = 50;
991
                dgvMotors1.Columns[2].Width = 50;
992
                dgvMotors1.Height = (272 / 12.6) * (_iMotors + 1);
993
                GridMotors.Height = dgvMotors1.Height + 10;
994
            }
995
 
996
        }
997
        #endregion settings
998
 
999
        #region functions  
1000
 
1001
        #region logging      
1002
        /// <summary> Log data to the terminal window. </summary>
1003
        /// <param name="msgtype"> The type of message to be written. </param>
1004
        /// <param name="msg"> The string containing the message to be shown. </param>
1005
        private void Log(LogMsgType msgtype, string msg)
1006
        {
1007
            Dispatcher.Invoke(() =>
1008
            {
1009
               // rtfTerminal.CaretPosition = rtfTerminal.CaretPosition.DocumentEnd;
1010
               // rtfTerminal.Foreground = new SolidColorBrush(LogMsgTypeColor[(int)msgtype]);
1011
//                rtfTerminal.AppendText(msg + "\r");
1012
                TextRange tr = new TextRange(rtfTerminal.Document.ContentEnd,rtfTerminal.Document.ContentEnd);
1013
                tr.Text = msg;
1014
                tr.ApplyPropertyValue(TextElement.ForegroundProperty, new SolidColorBrush(LogMsgTypeColor[(int)msgtype]));
1015
                rtfTerminal.AppendText("\r");
1016
                rtfTerminal.ScrollToEnd();
1017
            });
1018
        }
1019
        private void ErrorLog(LogMsgType msgtype, string msg)
1020
        {
1021
            Dispatcher.Invoke(() =>
1022
            {
1023
                TextRange tr = new TextRange(rtfError.Document.ContentEnd, rtfError.Document.ContentEnd);
1024
                tr.Text = msg;
1025
                tr.ApplyPropertyValue(TextElement.ForegroundProperty, new SolidColorBrush(LogMsgTypeColor[(int)msgtype]));
1026
                rtfError.AppendText("\r");
1027
                rtfError.ScrollToEnd();
1028
 
1029
                _bErrorLog = true;
1030
            });
1031
        }
1032
        /// <summary>
1033
        /// Clear the line in the  errorlog window 
1034
        /// containing the error string when error has ceased
1035
        /// </summary>
1036
        /// <param name="s">substring of errrormessage</param>
1037
        void _clearErrorLog(string s)
1038
        {
1039
            Dispatcher.Invoke((Action)(() =>
1040
            {
1041
                TextRange searchRange = new TextRange(rtfError.Document.ContentStart, rtfError.Document.ContentEnd);
1042
                TextRange foundRange = FindTextInRange(searchRange, s);
1043
 
1044
                int iStart = searchRange.Text.IndexOf(s, StringComparison.OrdinalIgnoreCase);
1045
 
1046
 
1047
                if (iStart > -1)
1048
                {
1049
                    int iLength = 0;
1050
                    int iEnd = searchRange.Text.IndexOf('\r', iStart);
1051
                    if (iEnd > 0)
1052
                    {
1053
                        iLength = iEnd + 1;
1054
                        int iHttp = searchRange.Text.IndexOf("http", iEnd);
1055
                        if (iHttp == iLength)
1056
                        {
1057
                            int iEnd2 = searchRange.Text.IndexOf('\r', iLength);
1058
                            if (iEnd2 > iLength)
1059
                            {
1060
                                iLength = iEnd2 + 1;
1061
                              //  TextRange result = new TextRange(rtfError.Document.ContentStart.GetPositionAtOffset(iStart), GetTextPositionAtOffset(rtfError.Document.ContentStart.GetPositionAtOffset(iStart), iLength));
1062
 
1063
                                rtfError.Selection.Select(rtfError.Document.ContentStart.GetPositionAtOffset(iStart), GetTextPositionAtOffset(rtfError.Document.ContentStart.GetPositionAtOffset(iStart), iLength));
1064
                                rtfError.Selection.Text = string.Empty;
1065
                                if (rtfError.Document.ContentEnd.GetTextRunLength(LogicalDirection.Backward) < 2) _bErrorLog = false;
1066
                            }
1067
 
1068
                        }
1069
                        else
1070
                        {
1071
                            rtfError.Selection.Select(rtfError.Document.ContentStart.GetPositionAtOffset(iStart), GetTextPositionAtOffset(rtfError.Document.ContentStart.GetPositionAtOffset(iStart), iLength));
1072
                            rtfError.Selection.Text = string.Empty;
1073
                            if (rtfError.Document.ContentEnd.GetTextRunLength(LogicalDirection.Backward) < 2) _bErrorLog = false;
1074
                        }
1075
                    }
1076
                }
1077
            }));
1078
 
1079
        }
1080
        public TextRange FindTextInRange(TextRange searchRange, string searchText)
1081
        {
1082
            int offset = searchRange.Text.IndexOf(searchText, StringComparison.OrdinalIgnoreCase);
1083
            if (offset < 0)
1084
                return null;  // Not found
1085
 
1086
            var start = GetTextPositionAtOffset(searchRange.Start, offset);
1087
            TextRange result = new TextRange(start, GetTextPositionAtOffset(start, searchText.Length));
1088
 
1089
            return result;
1090
        }
1091
        TextPointer GetTextPositionAtOffset(TextPointer position, int characterCount)
1092
        {
1093
            while (position != null)
1094
            {
1095
                if (position.GetPointerContext(LogicalDirection.Forward) == TextPointerContext.Text)
1096
                {
1097
                    int count = position.GetTextRunLength(LogicalDirection.Forward);
1098
                    if (characterCount <= count)
1099
                    {
1100
                        return position.GetPositionAtOffset(characterCount);
1101
                    }
1102
 
1103
                    characterCount -= count;
1104
                }
1105
 
1106
                TextPointer nextContextPosition = position.GetNextContextPosition(LogicalDirection.Forward);
1107
                if (nextContextPosition == null)
1108
                    return position;
1109
 
1110
                position = nextContextPosition;
1111
            }
1112
 
1113
            return position;
1114
        }
1115
        #endregion logging
1116
 
1117
        #region processing received data
1118
 
1119
        private void processMessage(byte[] message)
1120
        {
1121
            if (message.Length > 0)
1122
            {
1123
                _iLifeCounter++;
1124
                //Log(LogMsgType.Incoming, BitConverter.ToString(message));
1125
                //Log(LogMsgType.Incoming, message.Length.ToString());
1126
                string s = new string(ASCIIEncoding.ASCII.GetChars(message, 0, message.Length));
1127
                char cmdID;
1128
                byte adr;
1129
                byte[] data;
1130
                byte[] tmp = null;
1131
                if (message[0] != '#')
1132
                {
1133
                    int iFound = -1;
1134
                    for (int i = 0; i < message.Length; i++)   //Sometimes the FC/NC sends strings without termination (like WP messages)
1135
                    {                                   //so this is a workaround to not spam the log box
1136
                        if (message[i] == 35)
1137
                        {
1138
                            iFound = i;
1139
                            break;
1140
                        }
1141
                    }
1142
                    if (iFound > 0)
1143
                    {
1144
                        s = new string(ASCIIEncoding.ASCII.GetChars(message, 0, iFound));
1145
                        tmp = new byte[message.Length - iFound];
1146
                        Buffer.BlockCopy(message, iFound, tmp, 0, message.Length - iFound);
1147
                    }
1148
                    s = s.Trim('\0', '\n', '\r');
1149
                    if (s.Length > 0)
1150
                        Log(LogMsgType.Normal, s);
1151
                    if (tmp != null)
1152
                    {
1153
                        s = new string(ASCIIEncoding.ASCII.GetChars(tmp, 0, tmp.Length));
1154
                        processMessage(tmp);
1155
                    }
1156
                }
1157
                //Debug.Print(s);
1158
                else
1159
                {
1160
                    FlightControllerMessage.ParseMessage(message, out cmdID, out adr, out data);
1161
 
1162
                    if (adr == 255) { crcError++; }
1163
                    else crcError = 0;
1164
                    Dispatcher.Invoke(() => tbCrc.Text = crcError.ToString());
1165
                    //display the active controller (FC / NC) 
1166
                    if (adr > 0 && adr < 3 && adr != _iCtrlAct) //adr < 3: temporary workaround cause when I've connected the FC alone it always switches between mk3mag & FC every second...???
1167
                    {
1168
                        _iCtrlAct = adr;
1169
                        switch (adr)
1170
                        {
1171
                            case 1:
1172
                                Dispatcher.Invoke(() => tbCtrl.Text = "FC");
2298 - 1173
                                Dispatcher.Invoke(() => buttonSwitchNC.Visibility = Visibility.Visible);
2287 - 1174
                                //Dispatcher.Invoke(() => labelSwitchToNavi.Visibility = Visibility.Visible);
1175
                              //  _setFieldsNA(); //display fields NA for FC 
1176
                                break;
1177
                            case 2:
1178
                                Dispatcher.Invoke(() => tbCtrl.Text = "NC");
1179
                                //Dispatcher.Invoke(() => buttonSwitchNC.Visibility = Visibility.Hidden);
1180
                                //Dispatcher.Invoke(() => labelSwitchToNavi.Visibility = Visibility.Hidden);
1181
                                break;
1182
                            //case 3:
1183
                            //    lblCtrl.Invoke((Action)(() => lblCtrl.Text = "MK3MAG"));
1184
                            //    break;
1185
                            //case 4:
1186
                            //    lblCtrl.Invoke((Action)(() => lblCtrl.Text = "BL-CTRL"));
1187
                            //    break;
1188
                            default:
1189
                                Dispatcher.Invoke(() => tbCtrl.Text = "NA");
1190
                                break;
1191
                        }
1192
                       // _loadLabelNames();
1193
                    }
1194
                    // else
1195
                    //     Debug.Print("Address == 0?");
1196
 
1197
                    if (data != null && data.Length > 0)
1198
                    {
1199
                        s = new string(ASCIIEncoding.ASCII.GetChars(data, 1, data.Length - 1));
1200
                        s = s.Trim('\0', '\n');
1201
 
1202
                        switch (cmdID)
1203
                        {
1204
                            //case 'A': //Label names
1205
                            //    _processLabelNames(s);
1206
                            //    break;
1207
 
1208
                            case 'D': //Debug data
1209
                                _processDebugVals(adr, data);
1210
                                break;
1211
 
1212
                            case 'V': //Version
1213
                                _processVersion(adr, data);
1214
                                break;
1215
 
1216
                            case 'K'://BL-CTRL data
1217
                                _processBLCtrl(data);
1218
                                break;
1219
 
1220
                            case 'O': //NC Data
1221
                                _processNCData(data);
1222
                                break;
1223
 
1224
                            case 'E': //NC error-string
1225
                                ErrorLog(LogMsgType.Error, "NC Error: " + s);
1226
                                break;
1227
 
1228
                            case 'L': //OSD Menue (called by pagenumber)
1229
                                _processOSDSingle(data);
1230
                                break;
1231
 
1232
                            case 'H': //OSD Menue (with autoupdate - called by Key)
1233
                                _processOSDAuto(data);
1234
                                break;
1235
 
1236
                            case 'X': //Waypoint data
1237
                                _processWPData(data);
1238
                                break;
1239
 
1240
                                //default:
1241
                                //    Log(LogMsgType.Incoming, "cmd: " + cmdID.ToString());
1242
                                //    Log(LogMsgType.Incoming, BitConverter.ToString(data));
1243
                                //    break;
1244
                        }
1245
                    }
1246
                    //else
1247
                    //{
1248
                    //    Log(LogMsgType.Incoming, "cmd: " + cmdID.ToString());
1249
                    //    Log(LogMsgType.Incoming, BitConverter.ToString(data));
1250
                    //}
1251
                }
1252
            }
1253
        }
1254
        /// <summary>
1255
        /// Analog label names 'A'
1256
        /// each label name is returned as a single string 
1257
        /// and added to string array sAnalogLabel[]
1258
        /// and the datatable dtAnalog
1259
        /// </summary>
1260
        /// <param name="s">the label name</param>
1261
        void _processLabelNames(string s)
1262
        {
1263
            //if (iLableIndex < 32)
1264
            //{
1265
            //    sAnalogLabel[iLableIndex] = s;
1266
            //    if (dtAnalog.Rows.Count < 32)
1267
            //        dtAnalog.Rows.Add(s, "");
1268
            //    else
1269
            //        dtAnalog.Rows[iLableIndex].SetField(0, s);
1270
 
1271
            //  //  _getAnalogLabels(iLableIndex + 1);
1272
            //}
1273
            //Debug.Print(s);
1274
        }
1275
        /// <summary>
1276
        /// Debug values 'D'
1277
        /// </summary>
1278
        /// <param name="adr">adress of the active controller (1-FC, 2-NC)</param>
1279
        /// <param name="data">the received byte array to process</param>
1280
        void _processDebugVals(byte adr, byte[] data)
1281
        {
1282
            if (data.Length == 66)
1283
            {
1284
                int[] iAnalogData = new int[32];
1285
                double v;
1286
                int index = 0;
1287
                Int16 i16 = 0;
1288
                double dTemp = 0;
1289
                for (int i = 2; i < 66; i += 2)
1290
                {
1291
                    i16 = data[i + 1];
1292
                    i16 = (Int16)(i16 << 8);
1293
                    iAnalogData[index] = data[i] + i16;
1294
                    sAnalogData[index] = (data[i] + i16).ToString();
1295
                   // dtAnalog.Rows[index].SetField(1, sAnalogData[index]);
1296
 
1297
                    if (adr == 2) //NC
1298
                    {
1299
                        switch (index)
1300
                        {
1301
                            case 0: //pitch (German: nick)
1302
                                Dispatcher.Invoke(() => ArtHor.Pitch = ((double)iAnalogData[index] / (double)10));
1303
                                Dispatcher.Invoke((Action)(() => tbPitch.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0°")));
1304
                                break;
1305
                            case 1: //roll
1306
                                Dispatcher.Invoke(() => ArtHor.Roll = ((double)iAnalogData[index] / (double)10));
1307
                                Dispatcher.Invoke((Action)(() => tbRoll.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0°")));
1308
                                break;
1309
                            case 4: //altitude
1310
                                Dispatcher.Invoke(() => tbAlt.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0 m"));
1311
                                Dispatcher.Invoke(() => tbTopHeight.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0 m"));
1312
                                break;
1313
                            case 7: //Voltage
1314
                                v = (double)iAnalogData[index] / (double)10;
1315
                                Dispatcher.Invoke(() => tbVolt.Text = v.ToString("0.0 V"));
1316
                                Dispatcher.Invoke(() => tbTopVoltage.Text = v.ToString("0.0 V"));
1317
                                Dispatcher.Invoke(() => pbTopVoltage.Value = v);
1318
                                if (v - _dLipoVMin < 1 | v < _dThresholdVoltageWarn)
1319
                                {
1320
                                    if (v == _dVoltLast)
1321
                                        if(_iVoltJitter < 20) _iVoltJitter++;
1322
                                    else
1323
                                    {
1324
                                        _iVoltJitter = 0;
1325
                                        _dVoltLast = v;
1326
                                    }
1327
                                    if (_iVoltJitter == 20)
1328
                                    {
1329
                                        Dispatcher.Invoke(() => pbTopVoltage.Foreground = Brushes.Orange);
1330
 
1331
                                        if (v - _dLipoVMin < 1 | v < _dThresholdVoltageCrit)
1332
                                        {
1333
                                            Dispatcher.Invoke(() => pbTopVoltage.Foreground = Brushes.Red);
1334
                                            if (stbVoltageCritAnim != null && !_bCritAnimVoltActive)
1335
                                            {
1336
                                                Dispatcher.Invoke(() => stbVoltageCritAnim.Begin());
1337
                                                _bCritAnimVoltActive = true;
1338
                                            }
1339
                                            if (_bVoiceVoltPlay && !_bCritVoiceVoltActive)
1340
                                            {
2295 - 1341
                                                Thread t = new Thread(() => _mediaPlayer("Voice\\CriticalBattery.mp3"));
1342
                                                t.Start();
2287 - 1343
                                                _bCritVoiceVoltActive = true;
1344
                                            }
1345
                                        }
1346
                                        else
1347
                                        {
1348
                                            if (stbVoltageCritAnim != null && _bCritAnimVoltActive)
1349
                                            {
1350
                                                Dispatcher.Invoke(() => stbVoltageCritAnim.Stop());
1351
                                                _bCritAnimVoltActive = false;
1352
                                            }
1353
                                            _bCritVoiceVoltActive = false;
1354
 
2291 - 1355
                                            if (_bVoiceVoltPlay && !_bWarnVoiceVoltActive)
2287 - 1356
                                            {
2295 - 1357
                                                Thread t = new Thread(() => _mediaPlayer("Voice\\LowBattery.mp3"));
1358
                                                t.Start();
2291 - 1359
                                                _bWarnVoiceVoltActive = true;
2287 - 1360
                                            }
1361
                                        }
1362
                                    }
1363
                                }
1364
                                else
1365
                                {
1366
                                    Dispatcher.Invoke(() => pbTopVoltage.Foreground = new SolidColorBrush(Color.FromArgb(255, 107, 195, 123)));
1367
                                    if (stbVoltageCritAnim != null && _bCritAnimVoltActive)
1368
                                    {
1369
                                        Dispatcher.Invoke(() => stbVoltageCritAnim.Stop());
1370
                                        _bCritAnimVoltActive = false;
1371
                                    }
1372
                                    _bCritVoiceVoltActive = false;
2291 - 1373
                                    _bWarnVoiceVoltActive = false;
2287 - 1374
                                    _iVoltJitter = 0;
1375
                                }
1376
                                break;
1377
                            case 8: // Current
1378
                                Dispatcher.Invoke(() => tbCur.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0 A"));
1379
                                Dispatcher.Invoke(() => tbTopCurrent.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0 A"));
1380
                                break;
1381
                            case 10: //heading
2291 - 1382
                                Dispatcher.Invoke((Action)(() => tbHeading.Text = sAnalogData[index] + "°"));
2287 - 1383
                                Dispatcher.Invoke(() => ArtHor.rotate = iAnalogData[index]);
1384
                                break;
1385
                            case 12: // SPI error
2291 - 1386
                                Dispatcher.Invoke((Action)(() => tbSPI.Text = sAnalogData[index]));
2287 - 1387
                                break;
1388
                            case 14: //i2c error
2291 - 1389
                                Dispatcher.Invoke((Action)(() => tbI2C.Text = sAnalogData[index]));
2287 - 1390
                                break;
1391
                            case 20: //Earthmagnet field
2291 - 1392
                                Dispatcher.Invoke((Action)(() => tbMagF.Text = sAnalogData[index] + "%"));
1393
                                Dispatcher.Invoke((Action)(() => tbTopEarthMag.Text = sAnalogData[index] + "%"));
1394
 
1395
                                if (Math.Abs(100 - iAnalogData[index]) < _iThresholdMagField)
1396
                                {
1397
                                    Dispatcher.Invoke(() => imageEarthMag.Source = new BitmapImage(new Uri("Images/EarthMag.png", UriKind.Relative)));
1398
                                    _iMagneticFieldJitter = 0; _bVoiceMagneticFieldActive = false;
1399
                                    if (stbMagneticFieldAnim != null && _bAnimMagneticFieldActive)
1400
                                    {
1401
                                        Dispatcher.Invoke(() => stbMagneticFieldAnim.Stop());
1402
                                        _bAnimMagneticFieldActive = false;
1403
                                    }
1404
                                }
1405
                                else
1406
                                {
1407
                                    Dispatcher.Invoke(() => imageEarthMag.Source = new BitmapImage(new Uri("Images/EarthMag_R.png", UriKind.Relative)));
1408
                                    if(_iMagneticFieldLast >= Math.Abs(100 - iAnalogData[index]))
1409
                                    {
1410
                                        if (_iMagneticFieldJitter < 20)
1411
                                            _iMagneticFieldJitter++;
1412
                                    }
1413
                                    else
1414
                                    {
1415
                                        _iMagneticFieldJitter = 0;
1416
                                        _iMagneticFieldLast = Math.Abs(100 - iAnalogData[index]);
1417
                                    }
1418
                                    if(_iMagneticFieldJitter == 20)
1419
                                    {
1420
                                        if (stbMagneticFieldAnim != null && !_bAnimMagneticFieldActive)
1421
                                        {
1422
                                            Dispatcher.Invoke(() => stbMagneticFieldAnim.Begin());
1423
                                            _bAnimMagneticFieldActive = true;
1424
                                        }
1425
                                        if (_bVoiceMagneticFieldPlay && !_bVoiceMagneticFieldActive)
1426
                                        {
2295 - 1427
                                            Thread t = new Thread(() => _mediaPlayer("Voice\\MagneticField.mp3"));
1428
                                            t.Start();
2291 - 1429
                                            _bVoiceMagneticFieldActive = true;
1430
                                        }
1431
                                    }
1432
                                }
2287 - 1433
                                break;
1434
                            case 21: //GroundSpeed
1435
                                     Dispatcher.Invoke((Action)(() => tbSpeed.Text = ((double)iAnalogData[index] / (double)100).ToString("0.00 m/s")));
1436
                                     Dispatcher.Invoke((Action)(() => tbTopSpeed.Text = ((double)iAnalogData[index] / (double)100).ToString("0.00 m/s")));
1437
                                break;
2291 - 1438
 
1439
                            ///**********   needs testing --> not sure what position this is  ***************
2287 - 1440
                            case 28: //Distance East from saved home position -> calculate distance with distance N + height
1441
                                    dTemp = Math.Pow((double)iAnalogData[index], 2) + Math.Pow((double)iAnalogData[index - 1], 2);
1442
                                    dTemp = Math.Sqrt(dTemp) / (double)10; //'flat' distance from HP with N/E
1443
                                                                           //  lblNCDist.Invoke((Action)(() => lblNCDist.Text = dTemp.ToString("0.00")));
1444
                                    dTemp = Math.Pow(dTemp, 2) + Math.Pow(((double)iAnalogData[4] / (double)10), 2); //adding 'height' into calculation
1445
                                    dTemp = Math.Sqrt(dTemp) / (double)10;
1446
                               //     Dispatcher.Invoke((Action)(() => tbTopDistanceHP.Text = dTemp.ToString("0.0 m")));
1447
                                    Dispatcher.Invoke((Action)(() => tbHP1.Text = dTemp.ToString("0.0 m")));
1448
                                break;
2291 - 1449
 
2287 - 1450
                            case 31: //Sats used
1451
                                     Dispatcher.Invoke((Action)(() => tbSats.Text = sAnalogData[index]));
1452
                                    // Dispatcher.Invoke((Action)(() => tbTopSats.Text = sAnalogData[index]));                                   
1453
                                break;
1454
                        }
1455
                    }
1456
                    index++;
1457
                }
1458
            }
1459
            else
1460
                Debug.Print("wrong data-length (66): " + data.Length.ToString());
1461
        }
1462
        /// <summary>
1463
        /// Version string 'V'
1464
        /// </summary>
1465
        /// <param name="adr">adress of the active controller (1-FC, 2-NC)</param>
1466
        /// <param name="data">the received byte array to process</param>
1467
        void _processVersion(byte adr, byte[] data)
1468
        {
1469
            if (data.Length == 12)
1470
            {
1471
                if (!check_HWError)
1472
                {
1473
                    string[] sVersionStruct = new string[10] { "SWMajor: ", "SWMinor: ", "ProtoMajor: ", "LabelTextCRC: ", "SWPatch: ", "HardwareError 1: ", "HardwareError 2: ", "HWMajor: ", "BL_Firmware: ", "Flags: " };
1474
                    string sVersion = "";
1475
                    //sbyte[] signed = Array.ConvertAll(data, b => unchecked((sbyte)b));
1476
                    Log(LogMsgType.Warning, (adr == 1 ? "FC-" : "NC-") + "Version: ");
1477
                    sVersion = "HW V" + (data[7] / 10).ToString() + "." + (data[7] % 10).ToString();
1478
                    Log(LogMsgType.Incoming, sVersion);
1479
                    sVersion = "SW V" + (data[0]).ToString() + "." + (data[1]).ToString() + ((char)(data[4] + 'a')).ToString();
1480
                    Log(LogMsgType.Incoming, sVersion);
1481
                    Log(LogMsgType.Incoming, "BL-Firmware: V" + (data[8] / 100).ToString() + "." + (data[8] % 100).ToString());
1482
                }
1483
                if (data[5] > 0) //error0 
1484
                {
1485
                    if (adr == 1)
1486
                        ErrorLog(LogMsgType.Error, "FC - HW-Error " + data[5].ToString() + ": " + ((FC_HWError0)data[5]).ToString());
1487
                    if (adr == 2)
1488
                        ErrorLog(LogMsgType.Error, "NC - HW-Error " + data[5].ToString() + ": " + ((NC_HWError0)data[5]).ToString());
1489
                }
1490
                if (data[6] > 0) //error1 
1491
                {
1492
                    if (adr == 1)
1493
                        ErrorLog(LogMsgType.Error, "FC - HW-Error " + data[6].ToString() + ": " + ((FC_HWError1)data[6]).ToString());
1494
                    if (adr == 2)
1495
                        ErrorLog(LogMsgType.Error, "NC - Unknown HW-ERROR: " + data[6].ToString()); //@moment NC has only one error field
1496
                }
1497
                if ((data[5] + data[6] == 0) && _bErrorLog)
1498
                    _clearErrorLog(adr == 1 ? "FC - HW-Error" : "NC - HW-Error");
1499
 
1500
            }
1501
            check_HWError = false;
1502
        }
1503
        /// <summary>
1504
        /// BL-Ctrl data 'K'
1505
        /// for FC you have to use a customized firmware
1506
        /// </summary>
1507
        /// <param name="data">the received byte array to process</param>
1508
        void _processBLCtrl(byte[] data)
1509
        {
1510
            if (data.Length % 6 == 0) //data.Length up to 96 (16 motors x 6 byte data) --> new datastruct in FC -> not standard!
1511
            {
1512
                bool bAvailable = false;
1513
                for (int i = 0; i < data.Length && data[i] < _iMotors; i += 6) // data[i] < _iMotors -- only show set number of motors (12 max @ moment)
1514
                {
1515
 
1516
                    if ((data[i + 4] & 128) == 128) //Status bit at pos 7 = 128 dec -- if true, motor is available
1517
                        bAvailable = true;
1518
                    else
1519
                        bAvailable = false;
1520
 
1521
                    if (data[i] < _iMotors)
1522
                    {
1523
                        if (bAvailable)
1524
                        {
1525
                            dtMotors1.Rows[data[i]].SetField(1, ((double)data[i + 1] / (double)10).ToString("0.0 A"));
1526
                            dtMotors1.Rows[data[i]].SetField(2, data[i + 2].ToString("0 °C"));
1527
                        }
1528
                        else
1529
                        {
1530
                            dtMotors1.Rows[data[i]].SetField(1, "NA");
1531
                            dtMotors1.Rows[data[i]].SetField(2, "NA");
1532
                        }
1533
                    }
1534
                    //if (data[i] > 3 && data[i] < 8)
1535
                    //{
1536
                    //    if (bAvailable)
1537
                    //    {
1538
                    //        dtMotors2.Rows[data[i] - 4].SetField(1, ((double)data[i + 1] / (double)10).ToString("0.0 A"));
1539
                    //        dtMotors2.Rows[data[i] - 4].SetField(2, data[i + 2].ToString("0 °C"));
1540
                    //    }
1541
                    //    else
1542
                    //    {
1543
                    //        dtMotors2.Rows[data[i] - 4].SetField(1, "NA");
1544
                    //        dtMotors2.Rows[data[i] - 4].SetField(2, "NA");
1545
                    //    }
1546
                    //}
1547
                }
1548
            }
1549
        }
1550
        /// <summary>
1551
        /// Navi-Ctrl data 'O'
1552
        /// GPS-Position, capacatiy, flying time...
1553
        /// </summary>
1554
        /// <param name="data">the received byte array to process</param>
1555
        void _processNCData(byte[] data)
1556
        {
1557
            int i_32, i_16, iVal;
1558
            double d;
1559
            i_32 = data[4];
1560
            iVal = i_32 << 24;
1561
            i_32 = data[3];
1562
            iVal += i_32 << 16;
1563
            i_32 = data[2];
1564
            iVal += i_32 << 8;
1565
            iVal += data[1];
1566
            d = (double)iVal / Math.Pow(10, 7);
1567
 
1568
            PointLatLng p = new PointLatLng();
1569
 
1570
            p.Lng = d;
1571
          //  lblNCGPSLong.Invoke((Action)(() => lblNCGPSLong.Text = d.ToString("0.######°"))); //GPS-Position: Longitude in decimal degree
1572
            //lblNCGPSLong.Invoke((Action)(() => lblNCGPSLong.Text = _convertDegree(d))); //GPS-Position: Longitude in minutes, seconds
1573
 
1574
            i_32 = data[8];
1575
            iVal = i_32 << 24;
1576
            i_32 = data[7];
1577
            iVal += i_32 << 16;
1578
            i_32 = data[6];
1579
            iVal += i_32 << 8;
1580
            iVal += data[5];
1581
            d = (double)iVal / Math.Pow(10, 7);
1582
            p.Lat = d;
2291 - 1583
            if (data[50] > 4)//if more than 4 sats in use . otherwise the map would jump and scroll insane at beginning
1584
            {
1585
                _bSatFix = true; _iSatsJitter = 0; _bVoiceSatFixActive = false;
2295 - 1586
                if(_bAutoHome && !_bFirstSatFix)
1587
                {
1588
                    if (_iFirstSatFix < 3)
1589
                        _iFirstSatFix++;
1590
                    else
1591
                    {
1592
                        _bFirstSatFix = true;
1593
                        Dispatcher.Invoke(() => setHomePos());
1594
                    }
1595
                }
2291 - 1596
                if (stbSatFixLostAnim != null && _bAnimSatFixActive)
1597
                {
1598
                    Dispatcher.Invoke(() => stbSatFixLostAnim.Stop());
1599
                    _bAnimSatFixActive = false;
1600
                }
1601
                if (!_bFollowCopter)
1602
                {
1603
                    _setCopterData(p);
1604
                    if (!MainMap.ViewArea.Contains(p))
1605
                        Dispatcher.Invoke(() => MainMap.Position = p);
2287 - 1606
 
2291 - 1607
                }
1608
                else
2287 - 1609
                    Dispatcher.Invoke(() => MainMap.Position = p);
1610
            }
1611
            else
2291 - 1612
            {
1613
                if(_bSatFix)
1614
                {
1615
                    if (data[50] == _iSatsLast)
1616
                    {
1617
                        if (_iSatsJitter < 20) _iSatsJitter++;
1618
                    }
1619
                    else
1620
                    {
1621
                        _iSatsJitter = 0;
1622
                        _iSatsLast = data[50];
1623
                    }
2287 - 1624
 
2291 - 1625
                    if (_iSatsJitter == 20)
1626
                    {
1627
                        if (stbSatFixLostAnim != null && !_bAnimSatFixActive)
1628
                        {
1629
                            Dispatcher.Invoke(() => stbSatFixLostAnim.Begin());
1630
                            _bAnimSatFixActive = true;
1631
                        }
1632
                        if (_bVoiceSatFixPlay && !_bVoiceSatFixActive)
1633
                        {
2295 - 1634
                            Thread th = new Thread(() => _mediaPlayer("Voice\\CriticalBattery.mp3"));
1635
                            th.Start();
2291 - 1636
                            _bVoiceSatFixActive = true;
1637
                        }
1638
 
1639
                        _bSatFix = false;
1640
                    }
1641
                }
1642
            }
1643
 
2287 - 1644
            //  lblNCGPSLat.Invoke((Action)(() => lblNCGPSLat.Text = d.ToString("0.######°"))); //GPS-Position: Latitude in decimal degree
1645
            //lblNCGPSLat.Invoke((Action)(() => lblNCGPSLat.Text = _convertDegree(d))); //GPS-Position: Latitude in minutes, seconds
1646
 
1647
            i_16 = data[28];
1648
            i_16 = (Int16)(i_16 << 8);
1649
            iVal = data[27] + i_16;
1650
            Dispatcher.Invoke((Action)(() => tbWP.Text = ((double)iVal / (double)10).ToString("0.0 m"))); //Distance to next WP
1651
 
1652
            i_16 = data[45];
1653
            i_16 = (Int16)(i_16 << 8);
1654
            iVal = data[44] + i_16;
1655
        //    Dispatcher.Invoke((Action)(() => tbTopDistanceHP.Text = ((double)iVal / (double)10).ToString("0.0 m"))); //Distance to HP set by GPS on
1656
            Dispatcher.Invoke((Action)(() => tbHP.Text = ((double)iVal / (double)10).ToString("0.0 m"))); //Distance to HP set by GPS on
1657
 
1658
            Dispatcher.Invoke((Action)(() => tbWPIndex.Text = data[48].ToString())); //Waypoint index
1659
            Dispatcher.Invoke((Action)(() => tbWPCount.Text = data[49].ToString())); //Waypoints count
1660
 
1661
            Dispatcher.Invoke((Action)(() => tbTopSats.Text = data[50].ToString())); //Satellites
1662
 
1663
 
1664
            //--------------- Capacity used ------------------------
1665
            i_16 = data[81];
1666
            i_16 = (Int16)(i_16 << 8);
1667
            iVal = data[80] + i_16;
1668
            Dispatcher.Invoke((Action)(() => tbCapacity.Text = iVal.ToString() + " mAh"));
1669
            Dispatcher.Invoke((Action)(() => tbTopCapacity.Text = iVal.ToString() + " mAh"));
1670
 
1671
            //--------------- Flying time ------------------------
1672
            i_16 = data[56];
1673
            i_16 = (Int16)(i_16 << 8);
1674
            iVal = data[55] + i_16;
1675
            TimeSpan t = TimeSpan.FromSeconds(iVal);
1676
            string Text = t.Hours.ToString("D2") + ":" + t.Minutes.ToString("D2") + ":" + t.Seconds.ToString("D2");
1677
            Dispatcher.Invoke((Action)(() => tbFTime.Text = Text.ToString()));
1678
            Dispatcher.Invoke((Action)(() => tbTopFTime.Text = Text.ToString()));
1679
 
1680
            //--------------- RC quality ------------------------
1681
            Dispatcher.Invoke((Action)(() => tbRCQ.Text = data[66].ToString()));
1682
            Dispatcher.Invoke((Action)(() => tbTopRC.Text = data[66].ToString()));
1683
 
2291 - 1684
            if(data[66] > _iThresholdRC)
1685
            {
1686
                _iRCLevelJitter = 0; _bVoiceRCLevelActive = false;
1687
                if (stbRCLevelAnim != null && _bAnimRCLevelActive)
1688
                {
1689
                    Dispatcher.Invoke(() => stbRCLevelAnim.Stop());
1690
                    _bAnimRCLevelActive = false;
1691
                }
1692
            }
1693
            else
1694
            {
1695
                if (_iRCLevelJitter < 20) _iRCLevelJitter++;
1696
                if (_iRCLevelJitter == 20)
1697
                {
1698
                    if (stbRCLevelAnim != null && !_bAnimRCLevelActive)
1699
                    {
1700
                        Dispatcher.Invoke(() => stbRCLevelAnim.Begin());
1701
                        _bAnimRCLevelActive = true;
1702
                    }
1703
                    if (_bVoiceRCLevelPlay && !_bVoiceRCLevelActive)
1704
                    {
2295 - 1705
                        Thread th = new Thread(() => _mediaPlayer("Voice\\RCLevel.mp3"));
1706
                        th.Start();
2291 - 1707
                        _bVoiceRCLevelActive = true;
1708
                    }
1709
                        _iRCLevelJitter++;
1710
                }
1711
            }
1712
 
2287 - 1713
            //--------------- NC Error ------------------------
1714
            Dispatcher.Invoke((Action)(() => tbNCErr.Text = data[69].ToString()));  //NC Errornumber
1715
            if (data[69] > 0)
1716
                _readNCError();
1717
            if (data[69] > 0 & data[69] < 44)
1718
                ErrorLog(LogMsgType.Error, "NC Error [" + data[69].ToString() + "]: " + NC_Error[data[69]]);
1719
            else
1720
                if (_bErrorLog) _clearErrorLog("NC Error");
1721
 
2298 - 1722
            //-------------FC / NC Status Flags
1723
            Dispatcher.Invoke((Action)(() => FC1_1.Background = ((data[67] & 1) ==1) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS_MOTOR_RUN                             0x01
1724
            Dispatcher.Invoke((Action)(() => FC1_2.Background = ((data[67] & 2) ==2) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS_FLY                                   0x02
1725
            Dispatcher.Invoke((Action)(() => FC1_3.Background = ((data[67] & 4) ==4) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS_CALIBRATE                             0x04
1726
            Dispatcher.Invoke((Action)(() => FC1_4.Background = ((data[67] & 8) ==8) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS_START                                 0x08
1727
            Dispatcher.Invoke((Action)(() => FC1_5.Background = ((data[67] & 16) ==16) ? new SolidColorBrush(Colors.LightCoral) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS_EMERGENCY_LANDING                      0x10
1728
            Dispatcher.Invoke((Action)(() => FC1_6.Background = ((data[67] & 32) ==32) ? new SolidColorBrush(Colors.LightCoral) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS_LOWBAT                         0x20
1729
 
1730
            Dispatcher.Invoke((Action)(() => FC2_1.Background = ((data[74] & 1) ==1) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS2_CAREFREE                             0x01
1731
            Dispatcher.Invoke((Action)(() => FC2_2.Background = ((data[74] & 2) ==2) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS2_ALTITUDE_CONTROL                     0x02
1732
            Dispatcher.Invoke((Action)(() => FC2_3.Background = ((data[74] & 4) ==4) ? new SolidColorBrush(Colors.LightCoral) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS2_RC_FAILSAVE_ACTIVE                      0x04
1733
            Dispatcher.Invoke((Action)(() => FC2_4.Background = ((data[74] & 8) ==8) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS2_OUT1_ACTIVE                          0x08
1734
            Dispatcher.Invoke((Action)(() => FC2_5.Background = ((data[74] & 16) ==16) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS2_OUT2_ACTIVE                        0x10
1735
            Dispatcher.Invoke((Action)(() => FC2_6.Background = ((data[74] & 32) ==32) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS2_WAIT_FOR_TAKEOFF                   0x20   // Motor Running, but still on the ground
1736
            Dispatcher.Invoke((Action)(() => FC2_7.Background = ((data[74] & 64) ==64) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS2_AUTO_STARTING                              0x40
1737
            Dispatcher.Invoke((Action)(() => FC2_8.Background = ((data[74] & 128) ==128) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS2_AUTO_LANDING                             0x80
1738
 
1739
            Dispatcher.Invoke((Action)(() => NC1_2.Background = ((data[68] & 2) == 2) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// NC_FLAG_PH                                     0x02
1740
            Dispatcher.Invoke((Action)(() => NC1_3.Background = ((data[68] & 4) == 4) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// NC_FLAG_CH                                     0x04
1741
            Dispatcher.Invoke((Action)(() => NC1_4.Background = ((data[68] & 8) == 8) ? new SolidColorBrush(Colors.LightCoral) : new SolidColorBrush(Colors.Transparent)));// NC_FLAG_RANGE_LIMIT                               0x08
1742
            Dispatcher.Invoke((Action)(() => NC1_5.Background = ((data[68] & 16) == 16) ? new SolidColorBrush(Colors.LightCoral) : new SolidColorBrush(Colors.Transparent)));// NC_FLAG_NOSERIALLINK                            0x10
1743
            Dispatcher.Invoke((Action)(() => NC1_6.Background = ((data[68] & 32) == 32) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// NC_FLAG_TARGET_REACHED                               0x20
1744
            Dispatcher.Invoke((Action)(() => NC1_7.Background = ((data[68] & 64) == 64) ? new SolidColorBrush(Colors.DodgerBlue) : new SolidColorBrush(Colors.Transparent)));// NC_FLAG_MANUAL_CONTROL                          0x40
1745
            Dispatcher.Invoke((Action)(() => NC1_8.Background = ((data[68] & 128) == 128) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// NC_FLAG_GPS_OK                                     0x80
2299 - 1746
 
1747
            //Sidebar StatusSymbols
1748
            Dispatcher.Invoke((Action)(() => tbSideBarStatusMotors.Background = ((data[67] & 1) ==1) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS_MOTOR_RUN                             0x01
1749
            Dispatcher.Invoke((Action)(() => tbSideBarStatusMotors.Foreground = ((data[67] & 1) ==1) ? new SolidColorBrush(Colors.White) : new SolidColorBrush(Color.FromArgb(255,211,210,210))));// FC_STATUS_MOTOR_RUN                                0x01
1750
            Dispatcher.Invoke((Action)(() => tbSideBarStatusMotors.BorderBrush = ((data[67] & 1) ==1) ? new SolidColorBrush(Colors.White) : new SolidColorBrush(Color.FromArgb(255, 211, 210, 210))));// FC_STATUS_MOTOR_RUN                            0x01
1751
 
1752
            Dispatcher.Invoke((Action)(() => tbSideBarStatusCF.Background = ((data[74] & 1) == 1) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS2_CAREFREE                                0x01
1753
            Dispatcher.Invoke((Action)(() => tbSideBarStatusCF.Foreground = ((data[74] & 1) == 1) ? new SolidColorBrush(Colors.White) : new SolidColorBrush(Color.FromArgb(255, 211, 210, 210))));// FC_STATUS2_CAREFREE                                0x01
1754
            Dispatcher.Invoke((Action)(() => tbSideBarStatusCF.BorderBrush = ((data[74] & 1) ==1) ? new SolidColorBrush(Colors.White) : new SolidColorBrush(Color.FromArgb(255, 211, 210, 210))));// FC_STATUS2_CAREFREE                                0x01
1755
 
1756
            Dispatcher.Invoke((Action)(() => tbSideBarStatusEmergencyLanding.Background = ((data[67] & 16) == 16) ? new SolidColorBrush(Colors.LightCoral) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS_EMERGENCY_LANDING                   0x10
2304 - 1757
            Dispatcher.Invoke((Action)(() => tbSideBarStatusEmergencyLanding.Foreground = ((data[67] & 16) == 16) ? new SolidColorBrush(Colors.White) : new SolidColorBrush(Color.FromArgb(255, 211, 210, 210))));// FC_STATUS_EMERGENCY_LANDING                0x10
1758
            Dispatcher.Invoke((Action)(() => tbSideBarStatusEmergencyLanding.BorderBrush = ((data[67] & 16) == 16) ? new SolidColorBrush(Colors.White) : new SolidColorBrush(Color.FromArgb(255, 211, 210, 210))));// FC_STATUS_EMERGENCY_LANDING               0x10
2299 - 1759
 
1760
            Dispatcher.Invoke((Action)(() => tbSideBarStatusAC.Background = ((data[74] & 2) ==2) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS2_ALTITUDE_CONTROL                         0x02
1761
            Dispatcher.Invoke((Action)(() => tbSideBarStatusAC.Foreground = ((data[74] & 2) ==2) ? new SolidColorBrush(Colors.White) : new SolidColorBrush(Color.FromArgb(255, 211, 210, 210))));// FC_STATUS2_ALTITUDE_CONTROL                         0x02
1762
            Dispatcher.Invoke((Action)(() => tbSideBarStatusAC.BorderBrush = ((data[74] & 2) ==2) ? new SolidColorBrush(Colors.White) : new SolidColorBrush(Color.FromArgb(255, 211, 210, 210))));// FC_STATUS2_ALTITUDE_CONTROL                        0x02
1763
 
1764
            Dispatcher.Invoke((Action)(() => tbSideBarStatusPH.Text = ((data[68] & 4) == 4) ? "CH" : "PH"));// NC_FLAG_PH 0x02 / NC_FLAG_CH 0x04
2304 - 1765
            Dispatcher.Invoke((Action)(() => tbSideBarStatusPH.Background = (((data[68] & 2) == 2)|((data[68] & 4) == 4)) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// NC_FLAG_PH 0x02 / NC_FLAG_CH 0x04
1766
            Dispatcher.Invoke((Action)(() => tbSideBarStatusPH.Foreground = (((data[68] & 2) == 2)|((data[68] & 4) == 4)) ? new SolidColorBrush(Colors.White) : new SolidColorBrush(Color.FromArgb(255, 211, 210, 210))));// NC_FLAG_PH 0x02 / NC_FLAG_CH 0x04
1767
            Dispatcher.Invoke((Action)(() => tbSideBarStatusPH.BorderBrush = (((data[68] & 2) == 2)|((data[68] & 4) == 4)) ? new SolidColorBrush(Colors.White) : new SolidColorBrush(Color.FromArgb(255, 211, 210, 210))));// NC_FLAG_PH 0x02 / NC_FLAG_CH 0x04
2299 - 1768
 
2287 - 1769
        }
1770
        /// <summary>
1771
        /// Navi-Ctrl WP data struct 'X'
1772
        /// called by index
1773
        /// </summary>
1774
        /// <param name="data">the received byte array to process</param>
1775
        void _processWPData(byte[] data)
1776
        {
1777
            _iWP = data[0];
1778
            _bGetWPCount = false;
1779
            if (data.Length >= 28)
1780
            {
1781
                //int count = data[0];
1782
                //int index = data[1];
1783
                //cbWPIndex.Invoke((Action)(() => cbWPIndex.Items.Clear()));
1784
                //for (int i = 0; i < count; i++)
1785
                //    cbWPIndex.Invoke((Action)(() => cbWPIndex.Items.Add(i + 1)));
1786
                //cbWPIndex.Invoke((Action)(() => cbWPIndex.SelectedItem = index));
1787
                Dispatcher.Invoke(() => lblWPIndex.Content = data[1].ToString());
1788
                Dispatcher.Invoke(() => lblWPCount.Content = data[0].ToString());
1789
                if (_bGetWP)
1790
                {
1791
                    if (data[1] == 1)
1792
                        dtWaypoints.Rows.Clear();
1793
                    DataRow dr = dtWaypoints.NewRow();
1794
                    dr = Waypoints.toDataRow(data, dr);
1795
                    //if (dtWaypoints.Rows.Contains(data[1]))
1796
                    //{
1797
                    //    dtWaypoints.Rows.Find(data[1]).Delete();
1798
                    //    dtWaypoints.Rows.InsertAt(dr, data[1] - 1);
1799
                    //}
1800
                    //else
1801
                        dtWaypoints.Rows.Add(dr);
1802
 
1803
                    if (data[1] == data[0])
1804
                    {
1805
                        _bGetWP = false;
1806
                        Dispatcher.Invoke(() => dgvWP.Items.Refresh());
1807
                    }
1808
 
1809
                }
1810
            }
1811
            else
1812
            {
1813
                Dispatcher.Invoke(() => lblWPIndex.Content = 0);
1814
                Dispatcher.Invoke(() => lblWPCount.Content = 0);
1815
               // Debug.Print(new string(ASCIIEncoding.ASCII.GetChars(data, 0, data.Length)));
1816
            }
1817
        }
1818
        /// <summary>
1819
        /// OSD Menue 'L'
1820
        /// single page called by pagenumber
1821
        /// no autoupdate
1822
        /// </summary>
1823
        /// <param name="data">the received byte array to process</param>
1824
        void _processOSDSingle(byte[] data)
1825
        {
1826
            if (data.Length == 84)
1827
            {
1828
                string sMessage = "";
1829
                iOSDPage = data[0];
1830
                iOSDMax = data[1];
1831
                if (cbOSD.Items.Count != iOSDMax) _initOSDCB();
1832
                sMessage = new string(ASCIIEncoding.ASCII.GetChars(data, 2, data.Length - 4));
1833
                OSD(LogMsgType.Incoming, sMessage.Substring(0, 20)+ "\r", true);
1834
                OSD(LogMsgType.Incoming, sMessage.Substring(20, 20)+ "\r", false);
1835
                OSD(LogMsgType.Incoming, sMessage.Substring(40, 20)+ "\r", false);
1836
                OSD(LogMsgType.Incoming, sMessage.Substring(60, 20), false);
1837
                Dispatcher.Invoke(() => { cbOSD.SelectedValue = iOSDPage; });
1838
              //  lblOSDPageNr.Invoke((Action)(() => lblOSDPageNr.Text = iOSDPage.ToString("[0]")));
1839
 
1840
            }
1841
            //else
1842
            //    OSD(LogMsgType.Incoming, "Wrong length: " + data.Length + " (should be 84)");
1843
 
1844
        }
1845
        /// <summary>
1846
        /// OSD Menue 'H'
1847
        /// called by keys (0x01,0x02,0x03,0x04)
1848
        /// autoupdate
1849
        /// </summary>
1850
        /// <param name="data">the received byte array to process</param>
1851
        void _processOSDAuto(byte[] data)
1852
        {
1853
            if (data.Length == 81)
1854
            {
1855
                string sMessage = "";
1856
                sMessage = new string(ASCIIEncoding.ASCII.GetChars(data, 0, data.Length - 1));
1857
                OSD(LogMsgType.Incoming, sMessage.Substring(0, 20)+ "\r", true);
1858
                OSD(LogMsgType.Incoming, sMessage.Substring(20, 20)+ "\r", false);
1859
                OSD(LogMsgType.Incoming, sMessage.Substring(40, 20)+ "\r", false);
1860
                OSD(LogMsgType.Incoming, sMessage.Substring(60, 20), false);
1861
 
1862
            }
1863
            //else
1864
            //    OSD(LogMsgType.Incoming, "Wrong length: " + data.Length + " (should be 81)");
1865
        }
1866
 
1867
        #endregion processing received data
1868
 
1869
        #region controller messages
1870
        /// <summary> send message to controller to request data
1871
        /// for detailed info see http://wiki.mikrokopter.de/en/SerialProtocol/
1872
        /// </summary>
1873
        /// <param name="CMDID"> the command ID </param>
1874
        /// <param name="address"> the address of the controller: 0-any, 1-FC, 2-NC </param>
1875
        private void _sendControllerMessage(char CMDID, byte address)
1876
        {
1877
            if (serialPortCtrl.Port.IsOpen)
1878
            {
1879
                Stream serialStream = serialPortCtrl.Port.BaseStream;
1880
                byte[] bytes = FlightControllerMessage.CreateMessage(CMDID, address);
1881
                serialStream.Write(bytes, 0, bytes.Length);
1882
 
1883
            }
1884
            else
1885
                Log(LogMsgType.Error, "NOT CONNECTED!");
1886
        }
1887
        /// <summary> send message to controller to request data
1888
        /// for detailed info see http://wiki.mikrokopter.de/en/SerialProtocol/
1889
        /// </summary>
1890
        /// <param name="CMDID"> the command ID </param>
1891
        /// <param name="address"> the address of the controller: 0-any, 1-FC, 2-NC </param>
1892
        /// <param name="data"> additional data for the request</param>
1893
        private void _sendControllerMessage(char CMDID, byte address, byte[] data)
1894
        {
1895
            if (serialPortCtrl.Port.IsOpen)
1896
            {
1897
                Stream serialStream = serialPortCtrl.Port.BaseStream;
1898
                byte[] bytes = FlightControllerMessage.CreateMessage(CMDID, address, data);
1899
                serialStream.Write(bytes, 0, bytes.Length);
1900
 
1901
            }
1902
            else
1903
                Log(LogMsgType.Error, "NOT CONNECTED!");
1904
        }
1905
 
1906
        /// <summary>
1907
        /// start/stop continous polling of controller values
1908
        /// </summary>
1909
        /// <param name="b">start/stop switch</param>
1910
        void _readCont(bool b)
1911
        {
1912
            bReadContinously = b;
1913
            if (bReadContinously)
1914
            {
1915
                if (_debugDataAutorefresh) { _readDebugData(true); Thread.Sleep(10); }
1916
                if (_blctrlDataAutorefresh) { _readBLCtrl(true); Thread.Sleep(10); }
1917
                if (_navCtrlDataAutorefresh && _iCtrlAct == 2) { _readNavData(true); Thread.Sleep(10); }
1918
                if (_OSDAutorefresh) { _OSDMenueAutoRefresh(); Thread.Sleep(10); }
1919
                // Dispatcher.Invoke((Action)(() => rctConnection.Fill = Brushes.LightGreen));
1920
                Dispatcher.Invoke(() => imageConn.Source = new BitmapImage(new Uri("Images/Data_G.png", UriKind.Relative)));
1921
            }
1922
            else
1923
            {
1924
                // Dispatcher.Invoke((Action)(() => rctConnection.Fill = Brushes.LightGray));
1925
                Dispatcher.Invoke(() => imageConn.Source = new BitmapImage(new Uri("Images/Data_W.png", UriKind.Relative)));
1926
                _bConnErr = false;
1927
            }
1928
            _iLifeCounter = 0;
1929
        }
1930
 
1931
        private void _getVersion()
1932
        {
1933
            _sendControllerMessage('v', 0);
1934
        }
1935
        /// <summary>
1936
        /// get FC version struct via NC
1937
        /// by sending '1' as data (not documented in wiki...)
1938
        /// returns HW error 255 (comment in uart1.c : tells the KopterTool that it is the FC-version)
1939
        /// </summary>
1940
        /// <param name="ctrl">controller number 1=FC</param> 
1941
        private void _getVersion(byte ctrl)
1942
        {
1943
            _sendControllerMessage('v', 0, new byte[1] { ctrl });
1944
        }
1945
        /// <summary>
1946
        /// Switch back to NC by sending the 'Magic Packet' 0x1B,0x1B,0x55,0xAA,0x00
1947
        /// </summary>
1948
        private void _switchToNC()
1949
        {
1950
            if (serialPortCtrl.Port.IsOpen)
1951
            {
1952
                Stream serialStream = serialPortCtrl.Port.BaseStream;
1953
                byte[] bytes = new byte[5] { 0x1B, 0x1B, 0x55, 0xAA, 0x00 };
1954
                serialStream.Write(bytes, 0, bytes.Length);
1955
 
1956
                Thread.Sleep(100);
1957
                _getVersion();
1958
                Thread.Sleep(100);
1959
               // _OSDMenue(0);
1960
            }
1961
            else
1962
                Log(LogMsgType.Error, "NOT CONNECTED!");
1963
        }
1964
        /// <summary>
1965
        /// switch to FC
1966
        /// </summary>
1967
        private void _switchToFC()
1968
        {
1969
            _sendControllerMessage('u', 2, new byte[1] { (byte)0 });
1970
            Thread.Sleep(100);
1971
            _getVersion();
1972
            Thread.Sleep(100);
1973
          //  _OSDMenue(0);
1974
        }
1975
        /// <summary>
1976
        /// send RESET signal to FC
1977
        /// </summary>
1978
        private void _resetCtrl()
1979
        {
1980
            _sendControllerMessage('R', 1);
1981
        }
1982
        /// <summary>
1983
        /// poll the debug data (4sec subscription)
1984
        /// </summary>
1985
        /// <param name="auto"> onetimequery(false) or autoupdate(true) with set timing interval </param>
1986
        private void _readDebugData(bool auto)
1987
        {
1988
            byte interval = auto ? debugInterval : (byte)0;
1989
            _sendControllerMessage('d', 0, new byte[1] { debugInterval });
1990
        }
1991
        /// <summary>
1992
        /// poll the BL-CTRL status via NC (4sec subscription)
1993
        /// </summary>
1994
        /// <param name="auto"> onetimequery(false) or autoupdate(true) with set timing interval </param>
1995
        private void _readBLCtrl(bool auto)
1996
        {
1997
            byte interval = auto ? blctrlInterval : (byte)0;
1998
            _sendControllerMessage('k', 0, new byte[1] { interval });
1999
        }
2000
        /// <summary>
2001
        /// poll the NC data struct (4sec subscription)
2002
        /// </summary>
2003
        /// <param name="auto"> onetimequery(false) or autoupdate(true) with set timing interval </param>
2004
        private void _readNavData(bool auto)
2005
        {
2006
            byte interval = auto ? navctrlInterval : (byte)0;
2007
            _sendControllerMessage('o', 2, new byte[1] { interval });
2008
        }
2009
        /// <summary>
2010
        /// get the errortext for pending NC error
2011
        /// </summary>
2012
        private void _readNCError()
2013
        {
2014
            _sendControllerMessage('e', 2);
2015
        }
2016
        /// <summary>
2017
        /// request the Waypoint at index
2018
        /// </summary>
2019
        /// <param name="index"></param>
2020
        void _getpWP(int index)
2021
        {
2022
            if (serialPortCtrl.Port.IsOpen)
2023
            {
2024
                Stream serialStream = serialPortCtrl.Port.BaseStream;
2025
                byte[] bytes = FlightControllerMessage.CreateMessage('x', 2, new byte[1] { (byte)index });
2026
                serialStream.Write(bytes, 0, bytes.Length);
2027
            }
2028
            else
2029
                Log(LogMsgType.Error, "NOT CONNECTED!");
2030
 
2031
        }
2032
        void _getWP()
2033
        {
2034
            //if (_iWP > 0)
2035
            //{
2036
            //    _getWPList();
2037
            //}
2038
            //else
2039
            //{
2040
            //    if (_iWP == -1)
2041
            //    {
2042
            _bGetWPCount = true;
2043
            _getpWP(1);
2044
            while (_bGetWPCount)
2045
                Thread.Sleep(100);
2046
            if (_iWP > 0)
2047
                _getWPList();
2048
            //    }
2049
            //}
2050
        }
2051
        void _getWPList()
2052
        {
2053
            _bGetWP = true;
2054
            for (int j = 0; j < _iWP; j++)
2055
            {
2056
                _getpWP(j + 1);
2057
                Thread.Sleep(10);
2058
            }
2059
        }
2060
 
2061
 
2062
        #region OSD-Menue
2063
 
2064
        /// <summary>
2065
        /// one time query of the OSD Menue with pagenumber
2066
        /// </summary>
2067
        /// <param name="iMenue">Menue page</param>
2068
        void _OSDMenue(int iMenue)
2069
        {
2070
            if (serialPortCtrl.Port.IsOpen)
2071
            {
2072
                if (iMenue > iOSDMax)
2073
                    iMenue = 0;
2074
                Stream serialStream = serialPortCtrl.Port.BaseStream;
2075
                byte[] bytes = FlightControllerMessage.CreateMessage('l', 0, new byte[1] { (byte)iMenue });
2076
                serialStream.Write(bytes, 0, bytes.Length);
2077
            }
2078
            else
2079
                Log(LogMsgType.Error, "NOT CONNECTED!");
2080
 
2081
        }
2082
        /// <summary>
2083
        /// call the OSDMenue and start autorefresh
2084
        ///  usually by sending a menuekey
2085
        /// a bit tricky - but by sending inverted value of 32 (32 = 0010 0000) you can start the OSD menue with autoupdate (abo) without switching the page with the keyvalues (0x1, 0x2)
2086
        /// therefore the value has to be negative (inverted) in order to distinguish from old (2 line) menuestyle
2087
        /// and must not have any bits of the menue keys 0x1 0x2 0x4 0x8 (0x10?) --> 0x20 = -33
2088
        /// </summary>
2089
        void _OSDMenueAutoRefresh()
2090
        {
2091
            _sendControllerMessage('h', 0, new byte[2] { unchecked((byte)(-33)), OSDInterval });
2092
        }
2093
        void _OSDMenueAutoRefresh(byte key)
2094
        {
2095
            _sendControllerMessage('h', 0, new byte[2] { unchecked((byte)~key), OSDInterval });
2096
        }
2097
        /// <summary>
2098
        /// initialize the OSD menue combobox
2099
        /// combox is filled by numbers from 0 to max pagenumber
2100
        /// </summary>
2101
        void _initOSDCB()
2102
        {
2103
            _bCBInit = true;
2104
            if (iOSDMax == 0)
2105
            {
2106
                _OSDMenue(0);
2107
                Thread.Sleep(10);
2108
            }
2109
            Dispatcher.Invoke((Action)(() => cbOSD.Items.Clear()));
2110
            for (int i = 0; i <= iOSDMax; i++)
2111
            {
2112
                Dispatcher.Invoke((Action)(() => cbOSD.Items.Add(i)));
2113
            }
2114
            Dispatcher.Invoke((Action)(() => cbOSD.SelectedItem = iOSDPage));
2115
            _bCBInit = false;
2116
        }
2117
        private void btnOSDForward_Click(object sender, RoutedEventArgs e)
2118
        {
2119
            iOSDPage++;
2120
            if (iOSDPage > iOSDMax)
2121
                iOSDPage = 0;
2122
 
2123
            _OSDMenue(iOSDPage);
2124
        }
2125
        private void btnOSDBackward_Click(object sender, RoutedEventArgs e)
2126
        {
2127
            iOSDPage--;
2128
            if (iOSDPage < 0)
2129
                iOSDPage = iOSDMax;
2130
 
2131
            _OSDMenue(iOSDPage);
2132
        }
2133
        private void btnOSDLeave_Click(object sender, RoutedEventArgs e)
2134
        {
2135
            _OSDMenueAutoRefresh(8);
2136
        }
2137
        private void btnOSDEnter_Click(object sender, RoutedEventArgs e)
2138
        {
2139
            _OSDMenueAutoRefresh(4);
2140
        }
2141
        private void cbOSD_DropDownClosing(object sender, EventArgs e)
2142
        {
2143
            if (!_bCBInit && cbOSD.SelectedIndex > -1)
2144
                _OSDMenue(cbOSD.SelectedIndex);
2145
        }
2146
        private void OSD(LogMsgType msgtype, string msg, bool bNew)
2147
        {
2148
            Dispatcher.Invoke(() =>
2149
            {
2150
                TextRange tr;
2151
                if (bNew)
2152
                {
2153
                    rtfOSD.SelectAll();
2154
                    rtfOSD.Selection.Text = string.Empty;
2155
                }
2156
                tr = new TextRange(rtfOSD.Document.ContentEnd, rtfOSD.Document.ContentEnd);
2157
                tr.Text = msg;
2158
                tr.ApplyPropertyValue(TextElement.ForegroundProperty, new SolidColorBrush(LogMsgTypeColor[(int)msgtype]));
2159
                //     rtfOSD.AppendText("\r");
2160
                rtfOSD.ScrollToEnd();
2161
 
2162
            });
2163
        }
2164
 
2165
        #endregion OSD-Menue
2166
 
2167
        #endregion controller messages
2168
 
2295 - 2169
        void _mediaPlayer(string file)
2170
        {
2171
            if (File.Exists(file))
2172
            {
2173
                MediaPlayer.MediaPlayer mp = new MediaPlayer.MediaPlayer();
2174
                mp.Open(file);
2175
                mp.Play();
2176
            }
2177
        }
2287 - 2178
        private void imageFullscreen_MouseDown(object sender, MouseButtonEventArgs e)
2179
        {
2180
            if (winState.isMaximized)
2181
            {
2182
                winState.Restore(this);
2183
                imageFullscreen.Source = new BitmapImage(new Uri("Images/Fullscreen.png", UriKind.Relative));
2184
                if(_bSaveWinStateFull)
2185
                    _saveScaleSliders(true);
2186
                if(_bSaveWinStateNormal)
2187
                    _setScaleSliders(false);
2188
            }
2189
            else
2190
            {
2191
                winState.Maximize(this);
2192
                imageFullscreen.Source = new BitmapImage(new Uri("Images/RestoreScreen.png", UriKind.Relative));
2193
                if(_bSaveWinStateNormal)
2194
                    _saveScaleSliders(false);
2195
                if(_bSaveWinStateFull)
2196
                    _setScaleSliders(true);
2197
            }
2198
        }
2199
 
2200
        /// <summary>
2201
        /// reset the scaling of all UI elements to default
2202
        /// </summary>
2203
        /// <param name="sender"></param>
2204
        /// <param name="e"></param>
2205
        private void buttonUIScaleReset_Click(object sender, RoutedEventArgs e)
2206
        {
2207
            UIScaleHorizonSlider.Value =
2208
                UIScaleLOGSlider.Value =
2209
                UIScaleMotorsSlider.Value =
2210
                UIScaleOSDSlider.Value =
2211
                UIScaleSlider.Value =
2212
                UIScaleTopSlider.Value = 1;
2213
        }
2214
        /// <summary>
2215
        /// adjust the top postion of UI elements below the top bar to fit the bottom position of the bar when scaling the top bar
2216
        /// </summary>
2217
        /// <param name="sender"></param>
2218
        /// <param name="e"></param>
2219
        private void UIScaleTopSlider_ValueChanged(object sender, RoutedPropertyChangedEventArgs<double> e)
2220
        {
2221
            GridSettings.Margin = new Thickness(GridSettings.Margin.Left, 36 * UIScaleTopSlider.Value, GridSettings.Margin.Right, GridSettings.Margin.Bottom);
2222
            if (GridMotors != null)
2223
                GridMotors.Margin = new Thickness(GridMotors.Margin.Left, 36 * UIScaleTopSlider.Value, GridMotors.Margin.Right, GridMotors.Margin.Bottom);
2224
            if (GridSideBar != null)
2225
                GridSideBar.Margin = new Thickness(GridSideBar.Margin.Left, 36 * UIScaleTopSlider.Value, GridSideBar.Margin.Right, GridSideBar.Margin.Bottom);
2226
            if (GridOSD != null)
2227
                GridOSD.Margin = new Thickness(GridOSD.Margin.Left, 36 * UIScaleTopSlider.Value, GridOSD.Margin.Right, GridOSD.Margin.Bottom);
2228
            if (GridData != null)
2229
                GridData.Margin = new Thickness(GridData.Margin.Left, 36 * UIScaleTopSlider.Value, GridData.Margin.Right, GridData.Margin.Bottom);
2230
            if (GridWP != null)
2231
                GridWP.Margin = new Thickness(GridWP.Margin.Left, 36 * UIScaleTopSlider.Value, GridWP.Margin.Right, GridWP.Margin.Bottom);
2232
        }
2233
 
2234
        void _setScaleSliders(bool bFull)
2235
        {
2236
            if(bFull)
2237
            {
2238
                UIScaleSlider.Value = scaleFullAll;
2239
                UIScaleTopSlider.Value = scaleFullTopBar;
2240
                UIScaleMotorsSlider.Value = scaleFullMotors;
2241
                UIScaleOSDSlider.Value = scaleFullOSD;
2242
                UIScaleLOGSlider.Value = scaleFullLOG;
2243
                UIScaleHorizonSlider.Value = scaleFullHorizon;
2244
            }
2245
            else
2246
            {
2247
                UIScaleSlider.Value = scaleNormalAll;
2248
                UIScaleTopSlider.Value = scaleNormalTopBar;
2249
                UIScaleMotorsSlider.Value = scaleNormalMotors;
2250
                UIScaleOSDSlider.Value = scaleNormalOSD;
2251
                UIScaleLOGSlider.Value = scaleNormalLOG;
2252
                UIScaleHorizonSlider.Value = scaleNormalHorizon;
2253
            }
2254
        }
2255
 
2256
        void _saveScaleSliders(bool bFull)
2257
        {
2258
 
2259
            if (bFull)
2260
            {
2261
                scaleFullAll = UIScaleSlider.Value;
2262
                scaleFullTopBar = UIScaleTopSlider.Value;
2263
                scaleFullMotors = UIScaleMotorsSlider.Value;
2264
                scaleFullOSD = UIScaleOSDSlider.Value;
2265
                scaleFullLOG = UIScaleLOGSlider.Value;
2266
                scaleFullHorizon = UIScaleHorizonSlider.Value;
2267
            }
2268
            else
2269
            {
2270
                scaleNormalAll = UIScaleSlider.Value;
2271
                scaleNormalTopBar = UIScaleTopSlider.Value;
2272
                scaleNormalMotors = UIScaleMotorsSlider.Value;
2273
                scaleNormalOSD = UIScaleOSDSlider.Value;
2274
                scaleNormalLOG = UIScaleLOGSlider.Value;
2275
                scaleNormalHorizon = UIScaleHorizonSlider.Value;
2276
            }
2277
        }
2278
 
2279
        /// <summary>
2280
        /// read settings from ini-file
2281
        /// </summary>
2282
        void _readIni()
2283
        {
2284
            if (!File.Exists(filePath + "\\MKLiveViewSettings.ini"))
2285
                _writeIni();
2286
            IniFile ini = new IniFile("MKLiveViewSettings.ini");
2287
            ini.path = filePath + "\\MKLiveViewSettings.ini";
2288
 
2289
            string sVal = ini.IniReadValue("timings", "AutorefreshDebugData");
2295 - 2290
            if (sVal != "") _debugDataAutorefresh = Convert.ToBoolean(sVal);
2287 - 2291
            sVal = ini.IniReadValue("timings", "AutorefreshNavCtrlData");
2295 - 2292
            if (sVal != "") _navCtrlDataAutorefresh = Convert.ToBoolean(sVal);
2287 - 2293
            sVal = ini.IniReadValue("timings", "AutorefreshBLCtrlData");
2295 - 2294
            if (sVal != "") _blctrlDataAutorefresh = Convert.ToBoolean(sVal);
2287 - 2295
            sVal = ini.IniReadValue("timings", "AutorefreshOSDData");
2295 - 2296
            if (sVal != "") _OSDAutorefresh = Convert.ToBoolean(sVal);
2287 - 2297
 
2298
            sVal = ini.IniReadValue("timings", "IntervalDebugData");
2295 - 2299
            if (sVal != "") debugInterval = (byte)Convert.ToInt16(sVal);
2287 - 2300
            sVal = ini.IniReadValue("timings", "IntervalNavCtrlData");
2295 - 2301
            if (sVal != "") navctrlInterval = (byte)Convert.ToInt16(sVal);
2287 - 2302
            sVal = ini.IniReadValue("timings", "IntervalBLCtrlData");
2295 - 2303
            if (sVal != "") blctrlInterval = (byte)Convert.ToInt16(sVal);
2287 - 2304
            sVal = ini.IniReadValue("timings", "IntervalOSDData");
2295 - 2305
            if (sVal != "") OSDInterval = (byte)Convert.ToInt16(sVal);
2287 - 2306
 
2307
            sVal = ini.IniReadValue("topBar", "voltage");
2295 - 2308
            if (sVal != "") chkBoxTopBarShowVoltage.IsChecked = Convert.ToBoolean(sVal);
2287 - 2309
            sVal = ini.IniReadValue("topBar", "capacity");
2295 - 2310
            if (sVal != "") chkBoxTopBarShowCapacity.IsChecked = Convert.ToBoolean(sVal);
2287 - 2311
            sVal = ini.IniReadValue("topBar", "current");
2295 - 2312
            if (sVal != "") chkBoxTopBarShowCurrent.IsChecked = Convert.ToBoolean(sVal);
2287 - 2313
            sVal = ini.IniReadValue("topBar", "flightTime");
2295 - 2314
            if (sVal != "") chkBoxTopBarShowFlightTime.IsChecked = Convert.ToBoolean(sVal);
2287 - 2315
            sVal = ini.IniReadValue("topBar", "distanceHP");
2295 - 2316
            if (sVal != "") chkBoxTopBarShowDistanceHP.IsChecked = Convert.ToBoolean(sVal);
2287 - 2317
            sVal = ini.IniReadValue("topBar", "height");
2295 - 2318
            if (sVal != "") chkBoxTopBarShowHeight.IsChecked = Convert.ToBoolean(sVal);
2287 - 2319
            sVal = ini.IniReadValue("topBar", "speed");
2295 - 2320
            if (sVal != "") chkBoxTopBarShowSpeed.IsChecked = Convert.ToBoolean(sVal);
2287 - 2321
            sVal = ini.IniReadValue("topBar", "magneticField");
2295 - 2322
            if (sVal != "") chkBoxTopBarShowMF.IsChecked = Convert.ToBoolean(sVal);
2287 - 2323
            sVal = ini.IniReadValue("topBar", "satellites");
2295 - 2324
            if (sVal != "") chkBoxTopBarShowSatellites.IsChecked = Convert.ToBoolean(sVal);
2287 - 2325
            sVal = ini.IniReadValue("topBar", "rc");
2295 - 2326
            if (sVal != "") chkBoxTopBarShowRC.IsChecked = Convert.ToBoolean(sVal);
2287 - 2327
 
2328
            sVal = ini.IniReadValue("style", "saveFullScreen");
2295 - 2329
            if (sVal != "") chkBoxSaveFullScreenState.IsChecked = Convert.ToBoolean(sVal);
2287 - 2330
            sVal = ini.IniReadValue("style", "saveNormalState");
2295 - 2331
            if (sVal != "") chkBoxSaveNormalState.IsChecked = Convert.ToBoolean(sVal);
2287 - 2332
 
2333
            sVal = ini.IniReadValue("style", "scaleNormalAll");
2295 - 2334
            if (sVal != "") scaleNormalAll = Convert.ToDouble(sVal);
2287 - 2335
            sVal = ini.IniReadValue("style", "scaleNormalTopBar");
2295 - 2336
            if (sVal != "") scaleNormalTopBar = Convert.ToDouble(sVal);
2287 - 2337
            sVal = ini.IniReadValue("style", "scaleNormalMotors");
2295 - 2338
            if (sVal != "") scaleNormalMotors = Convert.ToDouble(sVal);
2287 - 2339
            sVal = ini.IniReadValue("style", "scaleNormalOSD");
2295 - 2340
            if (sVal != "") scaleNormalOSD = Convert.ToDouble(sVal);
2287 - 2341
            sVal = ini.IniReadValue("style", "scaleNormalLOG");
2295 - 2342
            if (sVal != "") scaleNormalLOG = Convert.ToDouble(sVal);
2287 - 2343
            sVal = ini.IniReadValue("style", "scaleNormalHorizon");
2295 - 2344
            if (sVal != "") scaleNormalHorizon = Convert.ToDouble(sVal);
2287 - 2345
 
2346
            sVal = ini.IniReadValue("style", "scaleFullAll");
2295 - 2347
            if (sVal != "") scaleFullAll = Convert.ToDouble(sVal);
2287 - 2348
            sVal = ini.IniReadValue("style", "scaleFullTopBar");
2295 - 2349
            if (sVal != "") scaleFullTopBar = Convert.ToDouble(sVal);
2287 - 2350
            sVal = ini.IniReadValue("style", "scaleFullMotors");
2295 - 2351
            if (sVal != "") scaleFullMotors = Convert.ToDouble(sVal);
2287 - 2352
            sVal = ini.IniReadValue("style", "scaleFullOSD");
2295 - 2353
            if (sVal != "") scaleFullOSD = Convert.ToDouble(sVal);
2287 - 2354
            sVal = ini.IniReadValue("style", "scaleFullLOG");
2295 - 2355
            if (sVal != "") scaleFullLOG = Convert.ToDouble(sVal);
2287 - 2356
            sVal = ini.IniReadValue("style", "scaleFullHorizon");
2295 - 2357
            if (sVal != "") scaleFullHorizon = Convert.ToDouble(sVal);
2287 - 2358
 
2359
            sVal = ini.IniReadValue("general", "LiPoCells");
2360
            _LipoCells = Convert.ToInt16(sVal);
2361
            sVal = ini.IniReadValue("general", "Motors");
2295 - 2362
            if (sVal != "") _iMotors = Convert.ToInt16(sVal);
2287 - 2363
 
2364
            sVal = ini.IniReadValue("map", "followMe");
2295 - 2365
            if (sVal != "") _bFollowCopter = Convert.ToBoolean(sVal);
2366
            sVal = ini.IniReadValue("map", "AutoSetHome");
2367
            if (sVal != "") _bAutoHome = Convert.ToBoolean(sVal);
2287 - 2368
 
2369
            sVal = ini.IniReadValue("threshold", "VoltageWarning");
2370
            if(sVal != "") _dThresholdVoltageWarn = Convert.ToDouble(sVal);
2371
            sVal = ini.IniReadValue("threshold", "VoltageCritical");
2372
            if(sVal != "") _dThresholdVoltageCrit = Convert.ToDouble(sVal);
2291 - 2373
            sVal = ini.IniReadValue("threshold", "VoiceVoltageEnable");
2287 - 2374
            if(sVal != "") _bVoiceVoltPlay = Convert.ToBoolean(sVal);
2291 - 2375
            sVal = ini.IniReadValue("threshold", "VoiceSatFixEnable");
2376
            if(sVal != "") _bVoiceSatFixPlay = Convert.ToBoolean(sVal);
2377
            sVal = ini.IniReadValue("threshold", "VoiceMagFieldEnable");
2378
            if(sVal != "") _bVoiceMagneticFieldPlay = Convert.ToBoolean(sVal);
2379
            sVal = ini.IniReadValue("threshold", "DistanceWarning");
2380
            if(sVal != "") _dThresholdDistanceWarn = Convert.ToDouble(sVal);
2381
            sVal = ini.IniReadValue("threshold", "VoiceDistanceWarnEnable");
2382
            if(sVal != "") _bVoiceDistancePlay = Convert.ToBoolean(sVal);
2383
            sVal = ini.IniReadValue("threshold", "VoiceRCLevelWarnEnable");
2384
            if(sVal != "") _bVoiceRCLevelPlay = Convert.ToBoolean(sVal);
2385
            sVal = ini.IniReadValue("threshold", "MaxDistance");
2386
            if(sVal != "") _dThresholdDistanceMax = Convert.ToDouble(sVal);
2387
            sVal = ini.IniReadValue("threshold", "RCThreshold");
2388
            if(sVal != "") _iThresholdRC = Convert.ToInt32(sVal);
2389
            sVal = ini.IniReadValue("threshold", "MagFieldThreshold");
2390
            if(sVal != "") _iThresholdMagField = Convert.ToInt32(sVal);
2287 - 2391
 
2392
        }
2393
 
2291 - 2394
 
2287 - 2395
        /// <summary>
2396
        /// save settings to ini-file
2397
        /// </summary>
2398
        void _writeIni()
2399
        {
2400
 
2401
            IniFile ini = new IniFile("MKLiveViewSettings.ini");
2402
            ini.path = filePath + "\\MKLiveViewSettings.ini";
2403
 
2404
            ini.IniWriteValue("timings", "AutorefreshDebugData", _debugDataAutorefresh ? "true" : "false");
2405
            ini.IniWriteValue("timings", "AutorefreshNavCtrlData", _navCtrlDataAutorefresh ? "true" : "false");
2406
            ini.IniWriteValue("timings", "AutorefreshBLCtrlData", _blctrlDataAutorefresh ? "true" : "false");
2407
            ini.IniWriteValue("timings", "AutorefreshOSDData", _OSDAutorefresh ? "true" : "false");
2408
 
2409
            ini.IniWriteValue("timings", "IntervalDebugData", debugInterval.ToString());
2410
            ini.IniWriteValue("timings", "IntervalNavCtrlData", navctrlInterval.ToString());
2411
            ini.IniWriteValue("timings", "IntervalBLCtrlData", blctrlInterval.ToString());
2412
            ini.IniWriteValue("timings", "IntervalOSDData", OSDInterval.ToString());
2413
 
2414
            ini.IniWriteValue("general", "LiPoCells", _LipoCells.ToString());
2415
            ini.IniWriteValue("general", "Motors", _iMotors.ToString());
2416
 
2417
            ini.IniWriteValue("map", "followMe", _bFollowCopter.ToString());
2295 - 2418
            ini.IniWriteValue("map", "AutoSetHome", _bAutoHome.ToString());
2287 - 2419
 
2420
            ini.IniWriteValue("topBar", "voltage", chkBoxTopBarShowVoltage.IsChecked.ToString());
2421
            ini.IniWriteValue("topBar", "capacity", chkBoxTopBarShowCapacity.IsChecked.ToString());
2422
            ini.IniWriteValue("topBar", "current", chkBoxTopBarShowCurrent.IsChecked.ToString());
2423
            ini.IniWriteValue("topBar", "flightTime", chkBoxTopBarShowFlightTime.IsChecked.ToString());
2424
            ini.IniWriteValue("topBar", "distanceHP", chkBoxTopBarShowDistanceHP.IsChecked.ToString());
2425
            ini.IniWriteValue("topBar", "height", chkBoxTopBarShowHeight.IsChecked.ToString());
2426
            ini.IniWriteValue("topBar", "speed", chkBoxTopBarShowSpeed.IsChecked.ToString());
2427
            ini.IniWriteValue("topBar", "magneticField", chkBoxTopBarShowMF.IsChecked.ToString());
2428
            ini.IniWriteValue("topBar", "satellites", chkBoxTopBarShowSatellites.IsChecked.ToString());
2429
            ini.IniWriteValue("topBar", "rc", chkBoxTopBarShowRC.IsChecked.ToString());
2430
 
2431
            ini.IniWriteValue("style", "saveFullScreen", chkBoxSaveFullScreenState.IsChecked.ToString());
2432
            ini.IniWriteValue("style", "saveNormalState", chkBoxSaveNormalState.IsChecked.ToString());
2433
 
2434
            ini.IniWriteValue("style", "scaleNormalAll", scaleNormalAll.ToString());
2435
            ini.IniWriteValue("style", "scaleNormalTopBar", scaleNormalTopBar.ToString());
2436
            ini.IniWriteValue("style", "scaleNormalMotors", scaleNormalMotors.ToString());
2437
            ini.IniWriteValue("style", "scaleNormalOSD", scaleNormalOSD.ToString());
2438
            ini.IniWriteValue("style", "scaleNormalLOG", scaleNormalLOG.ToString());
2439
            ini.IniWriteValue("style", "scaleNormalHorizon", scaleNormalHorizon.ToString());
2440
 
2441
            ini.IniWriteValue("style", "scaleFullAll", scaleFullAll.ToString());
2442
            ini.IniWriteValue("style", "scaleFullTopBar", scaleFullTopBar.ToString());
2443
            ini.IniWriteValue("style", "scaleFullMotors", scaleFullMotors.ToString());
2444
            ini.IniWriteValue("style", "scaleFullOSD", scaleFullOSD.ToString());
2445
            ini.IniWriteValue("style", "scaleFullLOG", scaleFullLOG.ToString());
2446
            ini.IniWriteValue("style", "scaleFullHorizon", scaleFullHorizon.ToString());
2447
 
2448
            ini.IniWriteValue("style", "horizon", chkBoxShowHorizon.IsChecked.ToString());
2449
 
2450
            ini.IniWriteValue("threshold", "VoltageWarning", _dThresholdVoltageWarn.ToString());
2451
            ini.IniWriteValue("threshold", "VoltageCritical", _dThresholdVoltageCrit.ToString());
2291 - 2452
            ini.IniWriteValue("threshold", "VoiceVoltageEnable", _bVoiceVoltPlay.ToString());
2453
            ini.IniWriteValue("threshold", "VoiceSatFixEnable", _bVoiceSatFixPlay.ToString());
2454
            ini.IniWriteValue("threshold", "VoiceMagFieldEnable", _bVoiceMagneticFieldPlay.ToString());
2455
            ini.IniWriteValue("threshold", "VoiceDistanceWarnEnable", _bVoiceDistancePlay.ToString());
2456
            ini.IniWriteValue("threshold", "VoiceRCLevelWarnEnable", _bVoiceRCLevelPlay.ToString());
2457
            ini.IniWriteValue("threshold", "DistanceWarning", _dThresholdDistanceWarn.ToString());
2458
            ini.IniWriteValue("threshold", "MaxDistance", _dThresholdDistanceMax.ToString());
2459
            ini.IniWriteValue("threshold", "RCThreshold", _iThresholdRC.ToString());
2460
            ini.IniWriteValue("threshold", "MagFieldThreshold", _iThresholdMagField.ToString());
2287 - 2461
        }
2462
        #endregion functions
2463
 
2295 - 2464
 
2287 - 2465
        private void Window_Closing(object sender, CancelEventArgs e)
2466
        {
2467
            _writeIni();
2468
        }
2469
    }
2470
    public class BooleanToVisibilityConverter : IValueConverter
2471
    {
2472
 
2473
        public object Convert(object value, Type targetType, object parameter, System.Globalization.CultureInfo culture)
2474
        {
2475
            return (bool)value ? Visibility.Visible : Visibility.Collapsed;
2476
        }
2477
 
2478
        public object ConvertBack(object value, Type targetType, object parameter, System.Globalization.CultureInfo culture)
2479
        {
2480
            throw new NotImplementedException();
2481
        }
2482
    }
2483
 
2484
    public class IniFile
2485
    {
2486
        public string path;
2487
 
2488
        [DllImport("kernel32")]
2489
        private static extern long WritePrivateProfileString(string section,
2490
          string key, string val, string filePath);
2491
 
2492
        [DllImport("kernel32.dll", CharSet = CharSet.Auto)]
2493
        static extern uint GetPrivateProfileSectionNames(IntPtr lpszReturnBuffer,
2494
               uint nSize, string lpFileName);
2495
 
2496
        [DllImport("kernel32")]
2497
        private static extern int GetPrivateProfileString(string section,
2498
          string key, string def, StringBuilder retVal,
2499
          int size, string filePath);
2500
 
2501
        public IniFile(string INIPath)
2502
        {
2503
            path = INIPath;
2504
        }
2505
 
2506
        public void IniWriteValue(string Section, string Key, string Value)
2507
        {
2508
            WritePrivateProfileString(Section, Key, Value, this.path);
2509
        }
2510
 
2511
        public string IniReadValue(string Section, string Key)
2512
        {
2513
            StringBuilder temp = new StringBuilder(255);
2514
            int i = GetPrivateProfileString(Section, Key, "", temp, 255, this.path);
2515
            return temp.ToString();
2516
        }
2517
        //Ini_sections auslesen in String-Array
2518
        public string[] IniSectionNames()
2519
        {
2520
 
2521
            //  uint MAX_BUFFER = 32767;
2522
            uint MAX_BUFFER = 8388608;
2523
            IntPtr pReturnedString = Marshal.AllocCoTaskMem((int)MAX_BUFFER);
2524
            uint bytesReturned = GetPrivateProfileSectionNames(pReturnedString, MAX_BUFFER, this.path);
2525
            if (bytesReturned == 0)
2526
            {
2527
                Marshal.FreeCoTaskMem(pReturnedString);
2528
                return null;
2529
            }
2530
            string local = Marshal.PtrToStringAuto(pReturnedString, (int)bytesReturned).ToString();
2531
            Marshal.FreeCoTaskMem(pReturnedString);
2532
            //use of Substring below removes terminating null for split
2533
            return local.Substring(0, local.Length - 1).Split('\0');
2534
 
2535
 
2536
        }
2537
    }
2538
 
2539
    /// <summary>
2540
    /// Selected Win AI Function Calls
2541
    /// </summary>
2542
    public class WinApi
2543
    {
2544
        [DllImport("user32.dll", EntryPoint = "GetSystemMetrics")]
2545
        public static extern int GetSystemMetrics(int which);
2546
        [DllImport("user32.dll")]
2547
        public static extern void
2548
                SetWindowPos(IntPtr hwnd, IntPtr hwndInsertAfter,
2549
                             int X, int Y, int width, int height, uint flags);
2550
 
2551
        private const int SM_CXSCREEN = 0;
2552
        private const int SM_CYSCREEN = 1;
2553
        private static IntPtr HWND_TOP = IntPtr.Zero;
2554
        private const int SWP_SHOWWINDOW = 64; // 0x0040
2555
 
2556
        public static int ScreenX
2557
        {
2558
            get { return GetSystemMetrics(SM_CXSCREEN); }
2559
        }
2560
 
2561
        public static int ScreenY
2562
        {
2563
            get { return GetSystemMetrics(SM_CYSCREEN); }
2564
        }
2565
 
2566
        public static void SetWinFullScreen(IntPtr hwnd)
2567
        {
2568
            SetWindowPos(hwnd, HWND_TOP, -8, -7, ScreenX+15, ScreenY+14, SWP_SHOWWINDOW);
2569
        }
2570
    }
2571
    /// <summary>
2572
    /// Class used to preserve / restore state of the window
2573
    /// </summary>
2574
    public class WinState
2575
    {
2576
        private WindowState winState;
2577
        private WindowStyle brdStyle;
2578
        private bool topMost;
2579
        private Rect restore;
2580
        private bool IsMaximized = false;
2581
 
2582
        public bool isMaximized
2583
        {
2584
            get { return IsMaximized; }
2585
        }
2586
        public void Maximize(Window targetForm)
2587
        {
2588
            if (!IsMaximized)
2589
            {
2590
                IsMaximized = true;
2591
                Save(targetForm);
2592
                targetForm.WindowState = WindowState.Maximized;
2593
                targetForm.WindowStyle = WindowStyle.None;
2594
                targetForm.Topmost = true;
2595
                WinApi.SetWinFullScreen(new WindowInteropHelper(targetForm).Handle);
2596
            }
2597
        }
2598
 
2599
        public void Save(Window targetForm)
2600
        {
2601
            winState = targetForm.WindowState;
2602
            brdStyle = targetForm.WindowStyle;
2603
            topMost = targetForm.Topmost;
2604
            restore = targetForm.RestoreBounds;
2605
        }
2606
        public void Restore(Window targetForm)
2607
        {
2608
            targetForm.WindowState = winState;
2609
            targetForm.WindowStyle = brdStyle;
2610
            targetForm.Topmost = topMost;
2611
 
2612
            targetForm.Left = restore.Left;
2613
            targetForm.Top = restore.Top;
2614
            targetForm.Height = restore.Height;
2615
            targetForm.Width = restore.Width;
2616
            IsMaximized = false;
2617
        }
2618
    }
2619
 
2620
}