Subversion Repositories Projects

Rev

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