Subversion Repositories Projects

Rev

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