Subversion Repositories Projects

Rev

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