Subversion Repositories Projects

Rev

Rev 2315 | Go to most recent revision | Blame | Last modification | View Log | RSS feed

using GMap.NET;
using GMap.NET.MapProviders;
using GMap.NET.WindowsPresentation;
using MKLiveView.GMapCustomMarkers;
using System;
using System.Collections.Generic;
using System.ComponentModel;
using System.Data;
using System.Diagnostics;
using System.IO;
using System.Linq;
using System.Linq.Expressions;
using System.Runtime.InteropServices;
using System.Text;
using System.Threading;
using System.Threading.Tasks;
using System.Windows;
using System.Windows.Controls;
using System.Windows.Data;
using System.Windows.Documents;
using System.Windows.Input;
using System.Windows.Interop;
using System.Windows.Media;
using System.Windows.Media.Animation;
using System.Windows.Media.Imaging;
using System.Windows.Navigation;
using System.Windows.Shapes;
using System.Windows.Threading;
using System.Globalization;

namespace MKLiveView
{
    /// <summary>
    /// Interaktionslogik für MainWindow.xaml
    /// </summary>
    public partial class MainWindow : Window
    {
        #region declarations

        GMapMarker copter;
        GMapMarker home;
        PointLatLng start;
        PointLatLng end;
        PointLatLng pHome;


        String[] NC_Error = new string[44]
        {
            "No Error",
            "FC not compatible" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A1_.22FC_not_compatible_.22",
            "MK3Mag not compatible" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A2_.22MK3Mag_not_compatible_.22",
            "no FC communication" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A3_.22no_FC_communication_.22",
            "no compass communication" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A4_.22no_compass_communication_.22",
            "no GPS communication" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A5_.22no_GPS_communication_.22",
            "bad compass value" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A6_.22bad_compass_value.22",
            "RC Signal lost" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A7_.22RC_Signal_lost_.22",
            "FC spi rx error" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A8_.22FC_spi_rx_error_.22",
            "ERR: no NC communication" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A9:_.22ERR:_no_NC_communication.22",
            "ERR: FC Nick Gyro" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A10_.22ERR:_FC_Nick_Gyro.22",
            "ERR: FC Roll Gyro" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A11_.22ERR:_FC_Roll_Gyro.22",
            "ERR: FC Yaw Gyro" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A12_.22ERR:_FC_Yaw_Gyro.22",
            "ERR: FC Nick ACC" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A13_.22ERR:_FC_Nick_ACC.22",
            "ERR: FC Roll ACC" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A14_.22ERR:_FC_Roll_ACC.22",
            "ERR: FC Z-ACC" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A15_.22ERR:_FC_Z-ACC.22",
            "ERR: Pressure sensor" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A16_.22ERR:_Pressure_sensor.22",
            "ERR: FC I2C" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A17_.22ERR:_FC_I2C.22",
            "ERR: Bl Missing" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A18_.22ERR:_Bl_Missing.22",
            "Mixer Error" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A19_.22Mixer_Error.22",
            "FC: Carefree Error" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A20_.22FC:_Carefree_Error.22",
            "ERR: GPS lost" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A21_.22ERR:_GPS_lost.22",
            "ERR: Magnet Error" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A22_.22ERR:_Magnet_Error.22",
            "Motor restart" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A23_.22Motor_restart.22",
            "BL Limitation" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A24_.22BL_Limitation.22",
            "Waypoint range" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A25_.22Waypoint_range.22",
            "ERR:No SD-Card" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A26_.22ERR:No_SD-Card.22",
            "ERR:SD Logging aborted" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A27_.22ERR:SD_Logging_aborted.22",
            "ERR:Flying range!" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A28_.22ERR:Flying_range.21.22",
            "ERR:Max Altitude" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A29_.22ERR:Max_Altitude.22",
            "No GPS Fix" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A30_.22No_GPS_Fix.22",
            "compass not calibrated" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A31_.22compass_not_calibrated.22",
            "ERR:BL selftest" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A32_.22ERR:BL_selftest.22",
            "no ext. compass" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A33_.22no_ext._compass.22",
            "compass sensor" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A34_.22compass_sensor.22",
            "FAILSAFE pos.!" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A35_.22FAILSAFE_pos..21__.22",
            "ERR:Redundancy" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A36_.22ERR:Redundancy__.22",
            "Redundancy test" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A37_.22Redundancy_test_.22",
            "GPS Update rate" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A38_.22GPS_Update_rate.22",
            "ERR:Canbus" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A39_.22ERR:Canbus.22",
            "ERR: 5V RC-Supply" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A40_.22ERR:_5V_RC-Supply.22",
            "ERR:Power-Supply" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A41_.22ERR:Power-Supply.22",
            "ACC not calibr." + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A42_.22ACC_not_calibr..22",
            "ERR:Parachute!" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A43_.22ERR:Parachute.21.22"
        };

        [FlagsAttribute]
        enum NC_HWError0 : short
        {
            None = 0,
            SPI_RX = 1,
            COMPASS_RX = 2,
            FC_INCOMPATIBLE = 4,
            COMPASS_INCOMPATIBLE = 8,
            GPS_RX = 16,
            COMPASS_VALUE = 32
        };
        [FlagsAttribute]
        enum FC_HWError0 : short
        {
            None = 0,
            GYRO_NICK = 1,
            GYRO_ROLL = 2,
            GYRO_YAW = 4,
            ACC_NICK = 8,
            ACC_ROLL = 16,
            ACC_TOP = 32,
            PRESSURE = 64,
            CAREFREE = 128
        };
        [FlagsAttribute]
        enum FC_HWError1 : short
        {
            None = 0,
            I2C = 1,
            BL_MISSING = 2,
            SPI_RX = 4,
            PPM = 8,
            MIXER = 16,
            RC_VOLTAGE = 32,
            ACC_NOT_CAL = 64,
            RES3 = 128
        };
        public enum LogMsgType { Incoming, Outgoing, Normal, Warning, Error };
        // Various colors for logging info
        private Color[] LogMsgTypeColor = { Color.FromArgb(255, 43, 145, 175), Colors.Green, Colors.Black, Colors.Orange, Colors.Red };

        bool _bCBInit = true;
        bool _init = true;
        bool check_HWError = false;

        string filePath = Directory.GetCurrentDirectory();
        bool bReadContinously = false;
        bool _debugDataAutorefresh = true;
        bool _navCtrlDataAutorefresh = true;
        bool _blctrlDataAutorefresh = true;
        bool _OSDAutorefresh = true;
        bool _bErrorLog = false;
        bool _bConnErr = false;
        bool _bFollowCopter = false;

        bool _bSaveWinStateNormal = true;
        bool _bSaveWinStateFull = true;

        double scaleNormalAll = 1;
        double scaleNormalTopBar = 1;
        double scaleNormalMotors = 1;
        double scaleNormalOSD = 1;
        double scaleNormalLOG = 1;
        double scaleNormalHorizon = 1;

        double scaleFullAll = 1;
        double scaleFullTopBar = 1;
        double scaleFullMotors = 1;
        double scaleFullOSD = 1;
        double scaleFullLOG = 1;
        double scaleFullHorizon = 1;

        int _iCtrlAct = 0;
        int iOSDPage = 0;
        int iOSDMax = 0;
        int _iLifeCounter = 0;
        int crcError = 0;

        bool _bSatFix = false;
        Storyboard stbSatFixLostAnim;
        bool _bAnimSatFixActive = false;
        bool _bVoiceSatFixActive = false;
        bool _bVoiceSatFixPlay = false;
        int _iSatsLast = 0;
        int _iSatsJitter = 0;

        bool _bMagneticFieldOK = false;
        Storyboard stbMagneticFieldAnim;
        bool _bAnimMagneticFieldActive = false;
        bool _bVoiceMagneticFieldActive = false;
        bool _bVoiceMagneticFieldPlay = false;
        int _iMagneticFieldLast = 0;
        int _iMagneticFieldJitter = 0;

        bool _bRCLevelOK = false;
        Storyboard stbRCLevelAnim;
        bool _bAnimRCLevelActive = false;
        bool _bVoiceRCLevelActive = false;
        bool _bVoiceRCLevelPlay = false;
        int _iRCLevelLast = 0;
        int _iRCLevelJitter = 0;

        int _iMotors = 4;
        int _LipoCells = 4;

        double _dLipoVMax = 16.88;
        double _dLipoVMin = 12;
        double _dThresholdVoltageWarn = 0;
        double _dThresholdVoltageCrit = 0;
        Storyboard stbVoltageCritAnim;
        bool _bCritAnimVoltActive = false;
        bool _bCritVoiceVoltActive = false;
        bool _bWarnVoiceVoltActive = false;
        bool _bVoiceVoltPlay = false;
        double _dVoltLast = 0;
        int _iVoltJitter = 0;

        double _dThresholdDistanceWarn = 100;
        Storyboard stbDistanceWarnAnim;
        bool _bAnimDistanceActive = false;
        bool _bVoiceDistanceActive = false;
        bool _bVoiceDistancePlay = false;
        double _dDistanceLast = 0;
        int _iDistanceJitter = 0;

        double _dThresholdDistanceMax = 1000;
        int _iThresholdRC = 160;
        int _iThresholdMagField = 15;

        bool _bAutoHome = false;
        bool _bFirstSatFix = false;
        int _iFirstSatFix = 0;

        double _dTopHeight = 36;

        int[] serChan = new int[12] { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };
        int[] serChan_sub = new int[12] { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };
        string[] serChanTitle = new string[12];

        string[] sAnalogLabel = new string[32];
        string[] sAnalogData = new string[32];

        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 };
        int[] iMotors = new int[] {3,4,5,6,7,8,9,10,11,12 };
        string[] sLiPoCells = new string[] { "3s", "4s", "5s", "6s" };
        /// <summary>
        /// interval for sending debugdata (multiplied by 10ms)
        /// </summary>
        byte debugInterval = 10; //(=> 100ms)
        /// <summary>
        /// interval for sending BL-CTRL status (multiplied by 10ms)
        /// </summary>
        byte blctrlInterval = 75;
        /// <summary>
        /// interval for sending NAV-CTRL status (multiplied by 10ms)
        /// </summary>
        byte navctrlInterval = 80;
        /// <summary>
        /// interval for sending OSD page update (multiplied by 10ms)
        /// </summary>
        byte OSDInterval = 85;
        /// <summary>
        /// datatable for the debug data array - displayed on settings tabpage in datagridview
        /// </summary>
        DataTable dtAnalog = new DataTable();
        /// <summary>
        /// datatable for motordata (current,temp)
        /// </summary>
        DataTable dtMotors = new DataTable();

        DataTable dtWaypoints = new DataTable();
        static volatile int _iWPCount = -1;
        static volatile int _iWPIndex = -1;
        int _iWPTimeout = 1000;
        bool _bGetWP = false;
        static volatile bool _bGetWPCount = false;

        DispatcherTimer timer = new DispatcherTimer();

        /// <summary>
        /// stuff for enabeling touch zoom for the map
        /// </summary>
        Point pTouch1 = new Point(0,0), pTouch2 = new Point(0,0);
        int iFirstStylusID = -1;
        public string connectButtonText
        {
            get
            {
                return bReadContinously ? "stop polling data" + System.Environment.NewLine + "from copter" : "start polling data" + System.Environment.NewLine + "from copter";
            }
        }

        WinState winState = new WinState();
        #endregion declarations
        public MainWindow()
        {
            InitializeComponent();
            _initForm();
            _dataTablesInit();
            _setupMap();
            _init = false;
            timer.Tick += new EventHandler(timerEvent);
            timer.Interval = new TimeSpan(0, 0, 1);
            timer.Start();
        }

        #region init
        void _initForm()
        {
            _readIni();
            if (_bSaveWinStateNormal)
                _setScaleSliders(false);
            cBoxTimingsDebug.ItemsSource =
                cBoxTimingsNav.ItemsSource =
                cBoxTimingsBl.ItemsSource =
                cBoxTimingsOSD.ItemsSource =
                iTimings;
            cBoxLiPoCells.ItemsSource = sLiPoCells;
            cBoxLiPoCells.SelectedItem = _LipoCells.ToString() + "s";
            _LipoMinMax();
            sliderThresholdVoltageWarn.Value = _dThresholdVoltageWarn;
            sliderThresholdVoltageCrit.Value = _dThresholdVoltageCrit;
            checkBoxThresholdVoltageVoice.IsChecked = _bVoiceVoltPlay;
            checkBoxSatfixLost.IsChecked = _bVoiceSatFixPlay;
            checkBoxMagneticField.IsChecked = _bVoiceMagneticFieldPlay;
            checkBoxThresholdDistanceVoice.IsChecked = _bVoiceDistancePlay;
            sliderThresholdDistanceWarn.Value = _dThresholdDistanceWarn;
            checkBoxRClevel.IsChecked = _bVoiceRCLevelPlay;

            sliderThresholdDistanceWarn.Maximum = _dThresholdDistanceMax;

            cBoxMotors.ItemsSource = iMotors;
            cBoxMotors.SelectedItem = _iMotors;

            serialPortCtrl.PortClosed += serialPortCtrl_PortClosed;
            serialPortCtrl.PortOpened += serialPortCtrl_PortOpened;
            serialPortCtrl.DataReceived += processMessage;

            chkbAutoBL.IsChecked = _blctrlDataAutorefresh;
            chkbAutoDbg.IsChecked = _debugDataAutorefresh;
            chkbAutoNav.IsChecked = _navCtrlDataAutorefresh;
            chkbAutoOSD.IsChecked = _OSDAutorefresh;

            cBoxTimingsDebug.SelectedItem = debugInterval * 10;
            cBoxTimingsNav.SelectedItem = navctrlInterval * 10;
            cBoxTimingsBl.SelectedItem = blctrlInterval * 10;
            cBoxTimingsOSD.SelectedItem = OSDInterval * 10;
            checkBoxAutoSetHP.IsChecked = _bAutoHome;
            checkBoxFollowCopter.IsChecked = _bFollowCopter;


        }
        /// <summary>
        /// initialize the datatables
        /// with columnnames etc
        /// </summary>
        void _dataTablesInit()
        {
            dtMotors.Columns.Add("#");
            if (Thread.CurrentThread.CurrentUICulture.Name == "de-DE")
                dtMotors.Columns.Add("Strom");
            else
                dtMotors.Columns.Add("Current");
            dtMotors.Columns.Add("Temp");
            dgvMotors1.DataContext = dtMotors.DefaultView;
            _initDTMotors();

            Setter setter = new Setter(ContentControl.PaddingProperty, new Thickness(5,0,5,0));
            Style style = new Style(typeof(System.Windows.Controls.Primitives.DataGridColumnHeader));
            style.Setters.Add(setter);
            setter = new Setter(ContentControl.BackgroundProperty, new SolidColorBrush(Colors.Transparent));
            style.Setters.Add(setter);
            setter = new Setter(ContentControl.ForegroundProperty, new SolidColorBrush(Colors.White));
            style.Setters.Add(setter);

            dtWaypoints.Columns.Add("Index",typeof(int));
            dtWaypoints.Columns.Add("Type", typeof(int));
            dtWaypoints.Columns.Add("Name",typeof(string));
            dtWaypoints.Columns.Add("Latitude",typeof(double));
            dtWaypoints.Columns.Add("Longitude",typeof(double));
            dtWaypoints.Columns.Add("Altitude",typeof(string));
            dtWaypoints.Columns.Add("Heading",typeof(string));
            dtWaypoints.Columns.Add("Speed",typeof(string));
            dtWaypoints.Columns.Add("ClimbRate",typeof(string));
            dtWaypoints.Columns.Add("Radius",typeof(string));
            dtWaypoints.Columns.Add("HoldTime",typeof(string));
            dtWaypoints.Columns.Add("AutoTrigger",typeof(string));
            dtWaypoints.Columns.Add("CamAngle",typeof(string));
            dtWaypoints.Columns.Add("Event",typeof(string));
            dtWaypoints.Columns.Add("Out1Timer",typeof(string));
            dtWaypoints.Columns.Add("Status",typeof(string));
            dtWaypoints.PrimaryKey = new DataColumn[] { dtWaypoints.Columns["Index"] };
            dgvWP.ItemsSource = dtWaypoints.DefaultView;
            dgvWP.ColumnHeaderStyle = new Style();
            dgvWP.ColumnHeaderStyle = style;


        }
        /// <summary>
        /// initialize the datatable dtMotors for motor values
        /// DataGridView dgvMotors1 is bound to dtMotors1
        /// </summary>
        void _initDTMotors()
        {
            for (int i = 0; i < 12; i++)
            {
                if (dtMotors.Rows.Count < 12)
                    dtMotors.Rows.Add((i + 1).ToString(), "NA", "NA");
                else
                {
                    dtMotors.Rows[i].SetField(1, "NA");
                    dtMotors.Rows[i].SetField(2, "NA");
                }
            }
        }

        #endregion init

        #region events
        private void serialPortCtrl_PortOpened()
        {
            Dispatcher.Invoke(() => imageWiFi.Source = new BitmapImage(new Uri("Images/WiFi_G.png", UriKind.Relative)));
            _getVersion();
            Thread.Sleep(100);
            //_OSDMenue(0);
            //Thread.Sleep(200);
            //_sendSerialData();
            _readCont(true);
        }
        private void serialPortCtrl_PortClosed()
        {
            Dispatcher.Invoke(() => imageWiFi.Source = new BitmapImage(new Uri("Images/WiFi_W.png", UriKind.Relative)));
            _readCont(false);
        }
        void timerEvent(object sender, EventArgs e)
        {
            if (bReadContinously)
            {
                if (_debugDataAutorefresh) { _readDebugData(true); Thread.Sleep(10); }

                if (_blctrlDataAutorefresh) { _readBLCtrl(true); Thread.Sleep(10); }

                if (_navCtrlDataAutorefresh && _iCtrlAct == 2) { _readNavData(true); Thread.Sleep(10); }
                check_HWError = true;
                _getVersion();
                Thread.Sleep(10);
                if (_OSDAutorefresh)
                {
                    if (iOSDMax == 0 | cbOSD.Items.Count != iOSDMax)
                        _initOSDCB();
                    _OSDMenueAutoRefresh();
                }
                if (_iLifeCounter > 0)
                {
                    Dispatcher.Invoke(() => imageConn.Source = new BitmapImage(new Uri("Images/Data_G.png", UriKind.Relative)));
                  //  Dispatcher.Invoke((Action)(() => rctConnection.Fill = Brushes.LightGreen));
                    _iLifeCounter = 0;
                    _bConnErr = false;
                }
                else
                {
                    if (!_bConnErr)
                    {
                        Log(LogMsgType.Error, "No communication to NC/FC!");
                        Dispatcher.Invoke(() => imageConn.Source = new BitmapImage(new Uri("Images/Data_R.png", UriKind.Relative)));
                       // Dispatcher.Invoke((Action)(() => rctConnection.Fill = Brushes.Red));
                        _bConnErr = true;
                    }
                }
            }
        }

        private void labelData_MouseDown(object sender, MouseButtonEventArgs e)
        {
            GridData.Visibility = GridData.Visibility == Visibility.Collapsed ? Visibility.Visible : Visibility.Collapsed;
            GridSettings.Visibility = GridWP.Visibility = Visibility.Collapsed;
        }
        private void labelMotorData_MouseDown(object sender, MouseButtonEventArgs e)
        {
            GridMotors.Visibility = GridMotors.Visibility == Visibility.Hidden ? Visibility.Visible : Visibility.Hidden;
            if (GridMotors.IsVisible)
                _setMotorGridSize();
        }
        private void labelSettings_MouseDown(object sender, MouseButtonEventArgs e)
        {
            GridData.Visibility = GridWP.Visibility = Visibility.Collapsed;
            GridSettings.Visibility = GridSettings.Visibility == Visibility.Collapsed ? Visibility.Visible : Visibility.Collapsed;
        }
        private void labelLog_MouseDown(object sender, MouseButtonEventArgs e)
        {
            GridLog.Visibility = GridLog.Visibility == Visibility.Collapsed ? Visibility.Visible : Visibility.Collapsed;
        }
        private void labelOSD_MouseDown(object sender, MouseButtonEventArgs e)
        {
            GridOSD.Visibility = GridOSD.Visibility == Visibility.Hidden ? Visibility.Visible : Visibility.Hidden;
        }
        private void labelWaypoints_MouseDown(object sender, MouseButtonEventArgs e)
        {
            GridData.Visibility = GridSettings.Visibility = Visibility.Collapsed;
            GridWP.Visibility = GridWP.Visibility == Visibility.Collapsed ? Visibility.Visible : Visibility.Collapsed;
        }

        private void btnGetWP_Click(object sender, RoutedEventArgs e)
        {
            Thread t = new Thread(new ThreadStart(_getWP));
            t.Start();
        }
        private void btnSendWPList_Click(object sender, RoutedEventArgs e)
        {
            Thread t = new Thread(new ThreadStart(_sendWPList));
            t.Start();
        }

        private void btnConnectToCopter_Click(object sender, RoutedEventArgs e)
        {
            if (!serialPortCtrl.Port.IsOpen)
                serialPortCtrl.Connect(true);
            else
                _readCont(!bReadContinously);
        }
        private void btnSetHP_Click(object sender, RoutedEventArgs e)
        {
            setHomePos();
        }
        private void btnClearHP_Click(object sender, RoutedEventArgs e)
        {
            clearHomePos();
        }
        private void btnGotoHP_Click(object sender, RoutedEventArgs e)
        {
            if (home != null && MainMap.Markers.Contains(home))
                MainMap.Position = home.Position;
        }
        private void checkBoxAutoSetHP_Click(object sender, RoutedEventArgs e)
        {
            _bAutoHome = (bool)checkBoxAutoSetHP.IsChecked;
        }
        private void chkBoxSaveNormalState_Click(object sender, RoutedEventArgs e)
        {
            _bSaveWinStateNormal = (bool)chkBoxSaveNormalState.IsChecked;
        }
        private void chkBoxSaveFullScreenState_Click(object sender, RoutedEventArgs e)
        {
            _bSaveWinStateFull = (bool)chkBoxSaveFullScreenState.IsChecked;
        }

        #region thresholds
        private void sliderThresholdVoltageWarn_ValueChanged(object sender, RoutedPropertyChangedEventArgs<double> e)
        {
            if(!_init)
                _dThresholdVoltageWarn = sliderThresholdVoltageWarn.Value;
        }
        private void sliderThresholdVoltageCrit_ValueChanged(object sender, RoutedPropertyChangedEventArgs<double> e)
        {
            if(!_init)
                _dThresholdVoltageCrit = sliderThresholdVoltageCrit.Value;
        }
        private void checkBoxThresholdVoltageVoice_Click(object sender, RoutedEventArgs e)
        {
            _bVoiceVoltPlay = (bool)checkBoxThresholdVoltageVoice.IsChecked;
        }

        private void sliderThresholdDistanceWarn_ValueChanged(object sender, RoutedPropertyChangedEventArgs<double> e)
        {
            if(!_init)
                _dThresholdDistanceWarn = sliderThresholdDistanceWarn.Value;
        }
        private void checkBoxThresholdDistanceVoice_Click(object sender, RoutedEventArgs e)
        {
            _bVoiceDistancePlay = (bool)checkBoxThresholdDistanceVoice.IsChecked;
        }

        private void checkBoxSatfixLost_Click(object sender, RoutedEventArgs e)
        {
            _bVoiceSatFixPlay = (bool)checkBoxSatfixLost.IsChecked;
        }
        private void checkBoxMagneticField_Click(object sender, RoutedEventArgs e)
        {
            _bVoiceMagneticFieldPlay = (bool)checkBoxMagneticField.IsChecked;
        }
        private void checkBoxRClevel_Click(object sender, RoutedEventArgs e)
        {
            _bVoiceRCLevelPlay = (bool)checkBoxRClevel.IsChecked;
        }
        #endregion thresholds

        private void buttonSwitchNC_Click(object sender, RoutedEventArgs e)
        {
            _switchToNC();
        }

        private void Window_Loaded(object sender, RoutedEventArgs e)
        {
            stbVoltageCritAnim = TryFindResource("VoltageCritAnim") as Storyboard;
            stbSatFixLostAnim = TryFindResource("SatFixLostAnim") as Storyboard;
            stbMagneticFieldAnim = TryFindResource("MagneticFieldCritAnim") as Storyboard;
            stbDistanceWarnAnim = TryFindResource("DistanceCritAnim") as Storyboard;
            stbRCLevelAnim = TryFindResource("RCCritAnim") as Storyboard;
            _setMotorGridSize();
        }
        private void Window_Closing(object sender, CancelEventArgs e)
        {
            _writeIni();
        }
        #endregion events

        #region GMap

        void _setupMap()
        {
            MainMap.Manager.Mode = AccessMode.ServerAndCache;
            MainMap.MapProvider = GMapProviders.BingHybridMap;
            MainMap.SetPositionByKeywords("Landshut");
            MainMap.MinZoom = 0;
            MainMap.MaxZoom = 24;
            MainMap.Zoom = 16;
            MainMap.ShowCenter = true;
            MainMap.ShowTileGridLines = false;
            sliderMapZoom.Value = 16;
            comboBoxMapType.ItemsSource = providerList;
            comboBoxMapType.DisplayMemberPath = "Name";
            comboBoxMapType.SelectedItem = MainMap.MapProvider;

            // acccess mode
            comboBoxMode.ItemsSource = Enum.GetValues(typeof(AccessMode));
            comboBoxMode.SelectedItem = MainMap.Manager.Mode;

        }
       
        /// <summary>
        /// selection of relevant map providers --> if You need more, You can change the line:
        ///     comboBoxMapType.ItemsSource = providerList;
        /// to:
        ///     comboBoxMapType.ItemsSource = GMapProviders.List;
        /// in _setupMap()
        /// or add items here:
        /// </summary>
        List<GMap.NET.MapProviders.GMapProvider> providerList = new List<GMap.NET.MapProviders.GMapProvider>
        { GMap.NET.MapProviders.GMapProviders.OpenCycleMap, GMap.NET.MapProviders.GMapProviders.OpenCycleLandscapeMap, GMap.NET.MapProviders.GMapProviders.OpenCycleTransportMap,
        GMap.NET.MapProviders.GMapProviders.BingMap,GMap.NET.MapProviders.GMapProviders.BingSatelliteMap,GMap.NET.MapProviders.GMapProviders.BingHybridMap,
        GMap.NET.MapProviders.GMapProviders.GoogleMap,GMap.NET.MapProviders.GMapProviders.GoogleSatelliteMap,GMap.NET.MapProviders.GMapProviders.GoogleHybridMap,GMap.NET.MapProviders.GMapProviders.GoogleTerrainMap,
        GMap.NET.MapProviders.GMapProviders.OviMap,GMap.NET.MapProviders.GMapProviders.OviSatelliteMap,GMap.NET.MapProviders.GMapProviders.OviHybridMap,GMap.NET.MapProviders.GMapProviders.OviTerrainMap};

        private void MainMap_Loaded(object sender, RoutedEventArgs e)
        {
            MainMap.Manager.Mode = AccessMode.ServerAndCache;
            copter = new GMapMarker(MainMap.Position);

            copter.Shape = new CustomMarkerCopter(this, copter, MainMap.Position.Lat.ToString("0.#######°") + System.Environment.NewLine + MainMap.Position.Lng.ToString("0.#######°"),"red");
            if (comboBoxCopterColor.SelectionBoxItem != null)
            {
                string s = comboBoxCopterColor.SelectionBoxItem.ToString();
                ((CustomMarkerCopter)(copter.Shape)).setColor(s);
            }
            copter.Offset = new System.Windows.Point(-18, -18);
            copter.ZIndex = int.MaxValue;
            MainMap.Markers.Add(copter);
            copter.Position = MainMap.Position;
        }
        void setHomePos()
        {
            pHome = MainMap.Position;
            if (!MainMap.Markers.Contains(home))
            {
                home = new GMapMarker(MainMap.Position);
                home.Shape = new CustomMarkerHome(this, home, MainMap.Position.Lat.ToString("0.#######°") + System.Environment.NewLine + MainMap.Position.Lng.ToString("0.#######°"));
                home.Offset = new System.Windows.Point(-18, -18);
                // home.ZIndex = int.MaxValue;
                MainMap.Markers.Add(home);
            }
            home.Position = MainMap.Position;
            ((CustomMarkerHome)(home.Shape)).setText(MainMap.Position.Lat.ToString("0.#######°") + System.Environment.NewLine + MainMap.Position.Lng.ToString("0.#######°"));
        }
        void clearHomePos()
        {
            MainMap.Markers.Remove(home);
        }

        // access mode
        private void comboBoxMode_DropDownClosed(object sender, EventArgs e)
        {
            MainMap.Manager.Mode = (AccessMode)comboBoxMode.SelectedItem;
            MainMap.ReloadMap();
        }
        // zoom up
        private void czuZoomUp_Click(object sender, RoutedEventArgs e)
        {
            MainMap.Zoom = ((int)MainMap.Zoom) + 1;
        }

        // zoom down
        private void czuZoomDown_Click(object sender, RoutedEventArgs e)
        {
            MainMap.Zoom = ((int)(MainMap.Zoom + 0.99)) - 1;
        }

        // prefetch
        private void buttonPrefetch_Click(object sender, RoutedEventArgs e)
        {
            RectLatLng area = MainMap.SelectedArea;
            if (!area.IsEmpty)
            {
                for (int i = (int)MainMap.Zoom; i <= MainMap.MaxZoom; i++)
                {
                    MessageBoxResult res = MessageBox.Show("Ready ripp at Zoom = " + i + " ?", "GMap.NET", MessageBoxButton.YesNoCancel);

                    if (res == MessageBoxResult.Yes)
                    {
                        TilePrefetcher obj = new TilePrefetcher();
                        obj.Owner = this;
                        obj.ShowCompleteMessage = true;
                        obj.Start(area, i, MainMap.MapProvider, 100);
                    }
                    else if (res == MessageBoxResult.No)
                    {
                        continue;
                    }
                    else if (res == MessageBoxResult.Cancel)
                    {
                        break;
                    }
                }
            }
            else
            {
                MessageBox.Show("Select map area holding ALT", "GMap.NET", MessageBoxButton.OK, MessageBoxImage.Exclamation);
            }
        }

        // goto by geocoder
        private void buttonGeoCoding_Click(object sender, RoutedEventArgs e)
        {
            _goto_byGeoCoder();
        }
        // goto by geocoder
        private void textBoxGeo_KeyUp(object sender, System.Windows.Input.KeyEventArgs e)
        {
            if (e.Key == System.Windows.Input.Key.Enter)
                _goto_byGeoCoder();
        }
        void _goto_byGeoCoder()
        {
            GeoCoderStatusCode status = MainMap.SetPositionByKeywords(textBoxGeo.Text);
            if (status != GeoCoderStatusCode.G_GEO_SUCCESS)
            {
                MessageBox.Show("Geocoder can't find: '" + textBoxGeo.Text + "', reason: " + status.ToString(), "GMap.NET", MessageBoxButton.OK, MessageBoxImage.Exclamation);
            }
        }
        private void buttonGeoLoc_Click(object sender, RoutedEventArgs e)
        {
            try
            {
                double lat = double.Parse(textBoxLat.Text, System.Globalization.CultureInfo.InvariantCulture);
                double lng = double.Parse(textBoxLng.Text, System.Globalization.CultureInfo.InvariantCulture);

                MainMap.Position = new PointLatLng(lat, lng);
            }
            catch (Exception ex)
            {
                MessageBox.Show("incorrect coordinate format: " + ex.Message);
            }

        }

        private void ReloadMap_Click(object sender, RoutedEventArgs e)
        {
            MainMap.ReloadMap();
        }

        private void MainMap_OnPositionChanged(PointLatLng point)
        {
            if (_bFollowCopter)
                _setCopterData(MainMap.Position);
        }

        private void MainMap_OnMapZoomChanged()
        {
            if (_bFollowCopter)
                _setCopterData(MainMap.Position);
            if((int)sliderMapZoom.Value != MainMap.Zoom)
                sliderMapZoom.Value = MainMap.Zoom;
        }

        void _setCopterData(PointLatLng p)
        {
            Dispatcher.Invoke(() =>
            {
                copter.Position = p;
                ((CustomMarkerCopter)(copter.Shape)).setText(p.Lat.ToString("0.#######°") + System.Environment.NewLine + p.Lng.ToString("0.#######°"));
                textBoxLat_currentPos.Text = p.Lat.ToString() + "°";
                textBoxLng_currentPos.Text = p.Lng.ToString() + "°";
            });
            if (home != null && MainMap.Markers.Contains(home))
            {
                Dispatcher.Invoke(() => ArtHor.rotateHome = GMapProviders.EmptyProvider.Projection.GetBearing(copter.Position, home.Position));
                double d = GMapProviders.EmptyProvider.Projection.GetDistance(home.Position, copter.Position);
                Dispatcher.Invoke(() => tbTopDistanceHP.Text = (d * 1000).ToString("0.0 m"));

                if(d*1000 < _dThresholdDistanceWarn)
                {
                    _iDistanceJitter = 0; _bVoiceDistanceActive = false;
                    if (stbDistanceWarnAnim != null && _bAnimDistanceActive)
                    {
                        Dispatcher.Invoke(() => stbDistanceWarnAnim.Stop());
                        _bAnimDistanceActive = false;
                    }
                }
                else
                {
                    if (_iDistanceJitter < 20)
                    { _iDistanceJitter++; }
                    if (_iDistanceJitter == 20)
                    {
                        if (stbDistanceWarnAnim != null && !_bAnimDistanceActive)
                        {
                            Dispatcher.Invoke(() => stbDistanceWarnAnim.Begin());
                            _bAnimDistanceActive = true;
                        }
                        if (_bVoiceDistancePlay && !_bVoiceDistanceActive)
                        {
                            Thread t = new Thread(()=>_mediaPlayer("Voice\\Distance.mp3"));
                            t.Start();
                            _bVoiceDistanceActive = true;
                        }
                        _iDistanceJitter++;
                    }
                }
            }
        }

        private void checkBoxFollowCopter_Click(object sender, RoutedEventArgs e)
        {
            _bFollowCopter = (bool)checkBoxFollowCopter.IsChecked;
        }

        private void sliderMapZoom_ValueChanged(object sender, RoutedPropertyChangedEventArgs<double> e)
        {
            if (MainMap.Zoom != sliderMapZoom.Value)
                MainMap.Zoom = (int)sliderMapZoom.Value;
        }
        #region Touch zooming hackattack ;)
        /// <summary>
        /// inspired by http://www.codeproject.com/Articles/692286/WPF-and-multi-touch
        /// </summary>
        bool bFirstAccess = true;
        double dDistance = 0;
        int iZoom;
        private void MainMap_StylusDown(object sender, StylusDownEventArgs e)
        {
            var id = e.StylusDevice.Id;
            e.StylusDevice.Capture(MainMap);
            if (iFirstStylusID == -1)
            {
                iFirstStylusID = id;
            }
            else
            {

                MainMap.CanDragMap = false;
            }
        }
        private void MainMap_StylusUp(object sender, StylusEventArgs e)
        {
            MainMap.ReleaseStylusCapture();
            iFirstStylusID = -1;
            bFirstAccess = true;
            MainMap.CanDragMap = true;
            iZoom = 0;
        }
        private void MainMap_StylusMove(object sender, StylusEventArgs e)
        {
            var id = e.StylusDevice.Id;
            var tp = e.GetPosition(MainMap);

            // This is the first Stylus point; just record its position.
            if (id == iFirstStylusID)
            {
                pTouch1.X = tp.X;
                pTouch1.Y = tp.Y;
            }
            else
            if (iFirstStylusID > -1)
            {
                pTouch2.X = tp.X;
                pTouch2.Y = tp.Y;
                double distance = Point.Subtract(pTouch1, pTouch2).Length;
                if (!bFirstAccess)
                {
                    if (distance > dDistance)
                        iZoom++;
                    else
                        if (distance < dDistance)
                        iZoom--;
                }
                if (iZoom > 30)
                {
                    iZoom = 0;
                    Dispatcher.Invoke(() => sliderMapZoom.Value += 1);
                }
                if (iZoom < -30)
                {
                    iZoom = 0;
                    Dispatcher.Invoke(() => sliderMapZoom.Value -= 1);
                }
                dDistance = distance;
                bFirstAccess = false;
            }
        }
        #endregion Touch zooming hackattack ;)

        #endregion GMap

        #region settings
        private void cBoxTimingsDebug_DropDownClosed(object sender, EventArgs e)
        {
            if(! _bCBInit && cBoxTimingsDebug.SelectedIndex > -1)
                debugInterval = (byte)(Convert.ToInt16(cBoxTimingsDebug.SelectedItem) / 10);
        }
        private void cBoxTimingsNav_DropDownClosed(object sender, EventArgs e)
        {
            if(! _bCBInit && cBoxTimingsNav.SelectedIndex > -1)
                navctrlInterval = (byte)(Convert.ToInt16(cBoxTimingsNav.SelectedItem) / 10);
        }
        private void cBoxTimingsBl_DropDownClosed(object sender, EventArgs e)
        {
            if (!_bCBInit && cBoxTimingsBl.SelectedIndex > -1)
                blctrlInterval = (byte)(Convert.ToInt16(cBoxTimingsBl.SelectedItem) / 10);
        }
        private void cBoxTimingsOSD_DropDownClosed(object sender, EventArgs e)
        {
            if (!_bCBInit && cBoxTimingsOSD.SelectedIndex > -1)
                OSDInterval = (byte)(Convert.ToInt16(cBoxTimingsOSD.SelectedItem) / 10);
        }
        private void chkbAutoDbg_Click(object sender, RoutedEventArgs e)
        {
            if (!_init) _debugDataAutorefresh = (bool)chkbAutoDbg.IsChecked;
        }
        private void chkbAutoNav_Click(object sender, RoutedEventArgs e)
        {
            if (!_init) _navCtrlDataAutorefresh = (bool)chkbAutoNav.IsChecked;
        }
        private void chkbAutoBL_Click(object sender, RoutedEventArgs e)
        {
            if (!_init) _blctrlDataAutorefresh = (bool)chkbAutoBL.IsChecked;
        }
        private void chkbAutoOSD_Click(object sender, RoutedEventArgs e)
        {
            if (!_init) _OSDAutorefresh = (bool)chkbAutoOSD.IsChecked;
        }

        private void cBoxLiPoCells_DropDownClosed(object sender, EventArgs e)
        {
            if (cBoxLiPoCells.SelectedIndex > -1)
            {
                _LipoCells = cBoxLiPoCells.SelectedIndex + 3;
                _LipoMinMax();
            }
        }
        void _LipoMinMax()
        {
            _dLipoVMax = (double)(_LipoCells) * 4.22;
            _dLipoVMin = (double)_LipoCells * 3;
            pbTopVoltage.Maximum = _dLipoVMax;
            pbTopVoltage.Minimum = _dLipoVMin;
            sliderThresholdVoltageWarn.Maximum = _dLipoVMax;
            sliderThresholdVoltageWarn.Minimum = _dLipoVMin;
        }
        private void cBoxMotors_DropDownClosed(object sender, EventArgs e)
        {
            if (cBoxMotors.SelectedIndex > -1)
            {
                _iMotors = cBoxMotors.SelectedIndex + 3;
                Dispatcher.Invoke(() =>
                {
                    dgvMotors1.Height = (272 / 12.6) * (_iMotors + 1);  //272 / 12.6 --> Workaround, cause the headerheight = NaN...?
                    GridMotors.Height = dgvMotors1.Height + 10;
                });
            }
        }
        void _setMotorGridSize()
        {
            if (dgvMotors1.Columns.Count > 2)
            {
                dgvMotors1.Columns[0].Width = 24;
                dgvMotors1.Columns[1].Width = 50;
                dgvMotors1.Columns[2].Width = 50;
                dgvMotors1.Height = (272 / 12.6) * (_iMotors + 1);
                GridMotors.Height = dgvMotors1.Height + 10;
            }

        }
        #endregion settings

        #region functions  

        #region logging      
        /// <summary> Log data to the terminal window. </summary>
        /// <param name="msgtype"> The type of message to be written. </param>
        /// <param name="msg"> The string containing the message to be shown. </param>
        private void Log(LogMsgType msgtype, string msg)
        {
            Dispatcher.Invoke(() =>
            {
               // rtfTerminal.CaretPosition = rtfTerminal.CaretPosition.DocumentEnd;
               // rtfTerminal.Foreground = new SolidColorBrush(LogMsgTypeColor[(int)msgtype]);
//                rtfTerminal.AppendText(msg + "\r");
                TextRange tr = new TextRange(rtfTerminal.Document.ContentEnd,rtfTerminal.Document.ContentEnd);
                tr.Text = msg;
                tr.ApplyPropertyValue(TextElement.ForegroundProperty, new SolidColorBrush(LogMsgTypeColor[(int)msgtype]));
                rtfTerminal.AppendText("\r");
                rtfTerminal.ScrollToEnd();
            });
        }
        private void ErrorLog(LogMsgType msgtype, string msg)
        {
            Dispatcher.Invoke(() =>
            {
                TextRange tr = new TextRange(rtfError.Document.ContentEnd, rtfError.Document.ContentEnd);
                tr.Text = msg;
                tr.ApplyPropertyValue(TextElement.ForegroundProperty, new SolidColorBrush(LogMsgTypeColor[(int)msgtype]));
                rtfError.AppendText("\r");
                rtfError.ScrollToEnd();

                _bErrorLog = true;
            });
        }
        /// <summary>
        /// Clear the line in the  errorlog window
        /// containing the error string when error has ceased
        /// </summary>
        /// <param name="s">substring of errrormessage</param>
        void _clearErrorLog(string s)
        {
            Dispatcher.Invoke((Action)(() =>
            {
                TextRange searchRange = new TextRange(rtfError.Document.ContentStart, rtfError.Document.ContentEnd);
                TextRange foundRange = FindTextInRange(searchRange, s);

                int iStart = searchRange.Text.IndexOf(s, StringComparison.OrdinalIgnoreCase);


                if (iStart > -1)
                {
                    int iLength = 0;
                    int iEnd = searchRange.Text.IndexOf('\r', iStart);
                    if (iEnd > 0)
                    {
                        iLength = iEnd + 1;
                        int iHttp = searchRange.Text.IndexOf("http", iEnd);
                        if (iHttp == iLength)
                        {
                            int iEnd2 = searchRange.Text.IndexOf('\r', iLength);
                            if (iEnd2 > iLength)
                            {
                                iLength = iEnd2 + 1;
                              //  TextRange result = new TextRange(rtfError.Document.ContentStart.GetPositionAtOffset(iStart), GetTextPositionAtOffset(rtfError.Document.ContentStart.GetPositionAtOffset(iStart), iLength));

                                rtfError.Selection.Select(rtfError.Document.ContentStart.GetPositionAtOffset(iStart), GetTextPositionAtOffset(rtfError.Document.ContentStart.GetPositionAtOffset(iStart), iLength));
                                rtfError.Selection.Text = string.Empty;
                                if (rtfError.Document.ContentEnd.GetTextRunLength(LogicalDirection.Backward) < 2) _bErrorLog = false;
                            }

                        }
                        else
                        {
                            rtfError.Selection.Select(rtfError.Document.ContentStart.GetPositionAtOffset(iStart), GetTextPositionAtOffset(rtfError.Document.ContentStart.GetPositionAtOffset(iStart), iLength));
                            rtfError.Selection.Text = string.Empty;
                            if (rtfError.Document.ContentEnd.GetTextRunLength(LogicalDirection.Backward) < 2) _bErrorLog = false;
                        }
                    }
                }
            }));

        }
        public TextRange FindTextInRange(TextRange searchRange, string searchText)
        {
            int offset = searchRange.Text.IndexOf(searchText, StringComparison.OrdinalIgnoreCase);
            if (offset < 0)
                return null;  // Not found

            var start = GetTextPositionAtOffset(searchRange.Start, offset);
            TextRange result = new TextRange(start, GetTextPositionAtOffset(start, searchText.Length));

            return result;
        }
        TextPointer GetTextPositionAtOffset(TextPointer position, int characterCount)
        {
            while (position != null)
            {
                if (position.GetPointerContext(LogicalDirection.Forward) == TextPointerContext.Text)
                {
                    int count = position.GetTextRunLength(LogicalDirection.Forward);
                    if (characterCount <= count)
                    {
                        return position.GetPositionAtOffset(characterCount);
                    }

                    characterCount -= count;
                }

                TextPointer nextContextPosition = position.GetNextContextPosition(LogicalDirection.Forward);
                if (nextContextPosition == null)
                    return position;

                position = nextContextPosition;
            }

            return position;
        }
        #endregion logging

        #region processing received data

        private void processMessage(byte[] message)
        {
            if (message.Length > 0)
            {
                _iLifeCounter++;
                //Log(LogMsgType.Incoming, BitConverter.ToString(message));
                //Log(LogMsgType.Incoming, message.Length.ToString());
                string s = new string(ASCIIEncoding.ASCII.GetChars(message, 0, message.Length));
                char cmdID;
                byte adr;
                byte[] data;
                byte[] tmp = null;
                if (message[0] != '#')
                {
                    int iFound = -1;
                    for (int i = 0; i < message.Length; i++)   //Sometimes the FC/NC sends strings without termination (like WP messages)
                    {                                   //so this is a workaround to not spam the log box
                        if (message[i] == 35)
                        {
                            iFound = i;
                            break;
                        }
                    }
                    if (iFound > 0)
                    {
                        s = new string(ASCIIEncoding.ASCII.GetChars(message, 0, iFound));
                        tmp = new byte[message.Length - iFound];
                        Buffer.BlockCopy(message, iFound, tmp, 0, message.Length - iFound);
                    }
                    s = s.Trim('\0', '\n', '\r');
                    if (s.Length > 0)
                        Log(LogMsgType.Normal, s);
                    if (tmp != null)
                    {
                        s = new string(ASCIIEncoding.ASCII.GetChars(tmp, 0, tmp.Length));
                        processMessage(tmp);
                    }
                }
                //Debug.Print(s);
                else
                {
                    FlightControllerMessage.ParseMessage(message, out cmdID, out adr, out data);

                    if (adr == 255) { crcError++; }
                    else crcError = 0;
                    Dispatcher.Invoke(() => tbCrc.Text = crcError.ToString());
                    //display the active controller (FC / NC)
                    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...???
                    {
                        _iCtrlAct = adr;
                        switch (adr)
                        {
                            case 1:
                                Dispatcher.Invoke(() => tbCtrl.Text = "FC");
                                Dispatcher.Invoke(() => buttonSwitchNC.Visibility = Visibility.Visible);
                                //Dispatcher.Invoke(() => labelSwitchToNavi.Visibility = Visibility.Visible);
                              //  _setFieldsNA(); //display fields NA for FC
                                break;
                            case 2:
                                Dispatcher.Invoke(() => tbCtrl.Text = "NC");
                                //Dispatcher.Invoke(() => buttonSwitchNC.Visibility = Visibility.Hidden);
                                //Dispatcher.Invoke(() => labelSwitchToNavi.Visibility = Visibility.Hidden);
                                break;
                            //case 3:
                            //    lblCtrl.Invoke((Action)(() => lblCtrl.Text = "MK3MAG"));
                            //    break;
                            //case 4:
                            //    lblCtrl.Invoke((Action)(() => lblCtrl.Text = "BL-CTRL"));
                            //    break;
                            default:
                                Dispatcher.Invoke(() => tbCtrl.Text = "NA");
                                break;
                        }
                       // _loadLabelNames();
                    }
                    // else
                    //     Debug.Print("Address == 0?");

                    if (data != null && data.Length > 0)
                    {
                        s = new string(ASCIIEncoding.ASCII.GetChars(data, 1, data.Length - 1));
                        s = s.Trim('\0', '\n');

                        switch (cmdID)
                        {
                            //case 'A': //Label names
                            //    _processLabelNames(s);
                            //    break;

                            case 'D': //Debug data
                                _processDebugVals(adr, data);
                                break;

                            case 'V': //Version
                                _processVersion(adr, data);
                                break;

                            case 'K'://BL-CTRL data
                                _processBLCtrl(data);
                                break;

                            case 'O': //NC Data
                                _processNCData(data);
                                break;

                            case 'E': //NC error-string
                                ErrorLog(LogMsgType.Error, "NC Error: " + s);
                                break;

                            case 'L': //OSD Menue (called by pagenumber)
                                _processOSDSingle(data);
                                break;

                            case 'H': //OSD Menue (with autoupdate - called by Key)
                                _processOSDAuto(data);
                                break;

                            case 'X': //Waypoint data
                                _processWPData(data);
                                break;

                            case 'W': //return new Waypoint items count after sending waypoint to copter
                                _iWPCount = data[0];
                                break;
                                //default:
                                //    Log(LogMsgType.Incoming, "cmd: " + cmdID.ToString());
                                //    Log(LogMsgType.Incoming, BitConverter.ToString(data));
                                //    break;
                        }
                    }
                    //else
                    //{
                    //    Log(LogMsgType.Incoming, "cmd: " + cmdID.ToString());
                    //    Log(LogMsgType.Incoming, BitConverter.ToString(data));
                    //}
                }
            }
        }
        /// <summary>
        /// Analog label names 'A'
        /// each label name is returned as a single string
        /// and added to string array sAnalogLabel[]
        /// and the datatable dtAnalog
        /// </summary>
        /// <param name="s">the label name</param>
        void _processLabelNames(string s)
        {
            //if (iLableIndex < 32)
            //{
            //    sAnalogLabel[iLableIndex] = s;
            //    if (dtAnalog.Rows.Count < 32)
            //        dtAnalog.Rows.Add(s, "");
            //    else
            //        dtAnalog.Rows[iLableIndex].SetField(0, s);

            //  //  _getAnalogLabels(iLableIndex + 1);
            //}
            //Debug.Print(s);
        }
        /// <summary>
        /// Debug values 'D'
        /// </summary>
        /// <param name="adr">adress of the active controller (1-FC, 2-NC)</param>
        /// <param name="data">the received byte array to process</param>
        void _processDebugVals(byte adr, byte[] data)
        {
            if (data.Length == 66)
            {
                int[] iAnalogData = new int[32];
                double v;
                int index = 0;
                Int16 i16 = 0;
                double dTemp = 0;
                for (int i = 2; i < 66; i += 2)
                {
                    i16 = data[i + 1];
                    i16 = (Int16)(i16 << 8);
                    iAnalogData[index] = data[i] + i16;
                    sAnalogData[index] = (data[i] + i16).ToString();
                   // dtAnalog.Rows[index].SetField(1, sAnalogData[index]);

                    if (adr == 2) //NC
                    {
                        switch (index)
                        {
                            case 0: //pitch (German: nick)
                                Dispatcher.Invoke(() => ArtHor.Pitch = ((double)iAnalogData[index] / (double)10));
                                Dispatcher.Invoke((Action)(() => tbPitch.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0°")));
                                break;
                            case 1: //roll
                                Dispatcher.Invoke(() => ArtHor.Roll = ((double)iAnalogData[index] / (double)10));
                                Dispatcher.Invoke((Action)(() => tbRoll.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0°")));
                                break;
                            case 4: //altitude
                                Dispatcher.Invoke(() => tbAlt.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0 m"));
                                Dispatcher.Invoke(() => tbTopHeight.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0 m"));
                                break;
                            case 7: //Voltage
                                v = (double)iAnalogData[index] / (double)10;
                                Dispatcher.Invoke(() => tbVolt.Text = v.ToString("0.0 V"));
                                Dispatcher.Invoke(() => tbTopVoltage.Text = v.ToString("0.0 V"));
                                Dispatcher.Invoke(() => pbTopVoltage.Value = v);
                                if (v - _dLipoVMin < 1 | v < _dThresholdVoltageWarn)
                                {
                                    if (v == _dVoltLast)
                                        if(_iVoltJitter < 20) _iVoltJitter++;
                                    else
                                    {
                                        _iVoltJitter = 0;
                                        _dVoltLast = v;
                                    }
                                    if (_iVoltJitter == 20)
                                    {
                                        Dispatcher.Invoke(() => pbTopVoltage.Foreground = Brushes.Orange);

                                        if (v - _dLipoVMin < 1 | v < _dThresholdVoltageCrit)
                                        {
                                            Dispatcher.Invoke(() => pbTopVoltage.Foreground = Brushes.Red);
                                            if (stbVoltageCritAnim != null && !_bCritAnimVoltActive)
                                            {
                                                Dispatcher.Invoke(() => stbVoltageCritAnim.Begin());
                                                _bCritAnimVoltActive = true;
                                            }
                                            if (_bVoiceVoltPlay && !_bCritVoiceVoltActive)
                                            {
                                                Thread t = new Thread(() => _mediaPlayer("Voice\\CriticalBattery.mp3"));
                                                t.Start();
                                                _bCritVoiceVoltActive = true;
                                            }
                                        }
                                        else
                                        {
                                            if (stbVoltageCritAnim != null && _bCritAnimVoltActive)
                                            {
                                                Dispatcher.Invoke(() => stbVoltageCritAnim.Stop());
                                                _bCritAnimVoltActive = false;
                                            }
                                            _bCritVoiceVoltActive = false;

                                            if (_bVoiceVoltPlay && !_bWarnVoiceVoltActive)
                                            {
                                                Thread t = new Thread(() => _mediaPlayer("Voice\\LowBattery.mp3"));
                                                t.Start();
                                                _bWarnVoiceVoltActive = true;
                                            }
                                        }
                                    }
                                }
                                else
                                {
                                    Dispatcher.Invoke(() => pbTopVoltage.Foreground = new SolidColorBrush(Color.FromArgb(255, 107, 195, 123)));
                                    if (stbVoltageCritAnim != null && _bCritAnimVoltActive)
                                    {
                                        Dispatcher.Invoke(() => stbVoltageCritAnim.Stop());
                                        _bCritAnimVoltActive = false;
                                    }
                                    _bCritVoiceVoltActive = false;
                                    _bWarnVoiceVoltActive = false;
                                    _iVoltJitter = 0;
                                }
                                break;
                            case 8: // Current
                                Dispatcher.Invoke(() => tbCur.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0 A"));
                                Dispatcher.Invoke(() => tbTopCurrent.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0 A"));
                                break;
                            case 10: //heading
                                Dispatcher.Invoke((Action)(() => tbHeading.Text = sAnalogData[index] + "°"));
                                Dispatcher.Invoke(() => ArtHor.rotate = iAnalogData[index]);
                                break;
                            case 12: // SPI error
                                Dispatcher.Invoke((Action)(() => tbSPI.Text = sAnalogData[index]));
                                break;
                            case 14: //i2c error
                                Dispatcher.Invoke((Action)(() => tbI2C.Text = sAnalogData[index]));
                                break;
                            case 20: //Earthmagnet field
                                Dispatcher.Invoke((Action)(() => tbMagF.Text = sAnalogData[index] + "%"));
                                Dispatcher.Invoke((Action)(() => tbTopEarthMag.Text = sAnalogData[index] + "%"));
                               
                                if (Math.Abs(100 - iAnalogData[index]) < _iThresholdMagField)
                                {
                                    Dispatcher.Invoke(() => imageEarthMag.Source = new BitmapImage(new Uri("Images/EarthMag.png", UriKind.Relative)));
                                    _iMagneticFieldJitter = 0; _bVoiceMagneticFieldActive = false;
                                    if (stbMagneticFieldAnim != null && _bAnimMagneticFieldActive)
                                    {
                                        Dispatcher.Invoke(() => stbMagneticFieldAnim.Stop());
                                        _bAnimMagneticFieldActive = false;
                                    }
                                }
                                else
                                {
                                    Dispatcher.Invoke(() => imageEarthMag.Source = new BitmapImage(new Uri("Images/EarthMag_R.png", UriKind.Relative)));
                                    if(_iMagneticFieldLast >= Math.Abs(100 - iAnalogData[index]))
                                    {
                                        if (_iMagneticFieldJitter < 20)
                                            _iMagneticFieldJitter++;
                                    }
                                    else
                                    {
                                        _iMagneticFieldJitter = 0;
                                        _iMagneticFieldLast = Math.Abs(100 - iAnalogData[index]);
                                    }
                                    if(_iMagneticFieldJitter == 20)
                                    {
                                        if (stbMagneticFieldAnim != null && !_bAnimMagneticFieldActive)
                                        {
                                            Dispatcher.Invoke(() => stbMagneticFieldAnim.Begin());
                                            _bAnimMagneticFieldActive = true;
                                        }
                                        if (_bVoiceMagneticFieldPlay && !_bVoiceMagneticFieldActive)
                                        {
                                            Thread t = new Thread(() => _mediaPlayer("Voice\\MagneticField.mp3"));
                                            t.Start();
                                            _bVoiceMagneticFieldActive = true;
                                        }
                                    }
                                }
                                break;
                            case 21: //GroundSpeed
                                     Dispatcher.Invoke((Action)(() => tbSpeed.Text = ((double)iAnalogData[index] / (double)100).ToString("0.00 m/s")));
                                     Dispatcher.Invoke((Action)(() => tbTopSpeed.Text = ((double)iAnalogData[index] / (double)100).ToString("0.00 m/s")));
                                break;

                            ///**********   needs testing --> not sure what position this is  ***************
                            case 28: //Distance East from saved home position -> calculate distance with distance N + height
                                    dTemp = Math.Pow((double)iAnalogData[index], 2) + Math.Pow((double)iAnalogData[index - 1], 2);
                                    dTemp = Math.Sqrt(dTemp) / (double)10; //'flat' distance from HP with N/E
                                                                           //  lblNCDist.Invoke((Action)(() => lblNCDist.Text = dTemp.ToString("0.00")));
                                    dTemp = Math.Pow(dTemp, 2) + Math.Pow(((double)iAnalogData[4] / (double)10), 2); //adding 'height' into calculation
                                    dTemp = Math.Sqrt(dTemp) / (double)10;
                               //     Dispatcher.Invoke((Action)(() => tbTopDistanceHP.Text = dTemp.ToString("0.0 m")));
                                    Dispatcher.Invoke((Action)(() => tbHP1.Text = dTemp.ToString("0.0 m")));
                                break;

                            case 31: //Sats used
                                     Dispatcher.Invoke((Action)(() => tbSats.Text = sAnalogData[index]));
                                    // Dispatcher.Invoke((Action)(() => tbTopSats.Text = sAnalogData[index]));                                  
                                break;
                        }
                    }
                    index++;
                }
            }
            else
                Debug.Print("wrong data-length (66): " + data.Length.ToString());
        }
        /// <summary>
        /// Version string 'V'
        /// </summary>
        /// <param name="adr">adress of the active controller (1-FC, 2-NC)</param>
        /// <param name="data">the received byte array to process</param>
        void _processVersion(byte adr, byte[] data)
        {
            if (data.Length == 12)
            {
                if (!check_HWError)
                {
                    string[] sVersionStruct = new string[10] { "SWMajor: ", "SWMinor: ", "ProtoMajor: ", "LabelTextCRC: ", "SWPatch: ", "HardwareError 1: ", "HardwareError 2: ", "HWMajor: ", "BL_Firmware: ", "Flags: " };
                    string sVersion = "";
                    //sbyte[] signed = Array.ConvertAll(data, b => unchecked((sbyte)b));
                    Log(LogMsgType.Warning, (adr == 1 ? "FC-" : "NC-") + "Version: ");
                    sVersion = "HW V" + (data[7] / 10).ToString() + "." + (data[7] % 10).ToString();
                    Log(LogMsgType.Incoming, sVersion);
                    sVersion = "SW V" + (data[0]).ToString() + "." + (data[1]).ToString() + ((char)(data[4] + 'a')).ToString();
                    Log(LogMsgType.Incoming, sVersion);
                    Log(LogMsgType.Incoming, "BL-Firmware: V" + (data[8] / 100).ToString() + "." + (data[8] % 100).ToString());
                }
                if (data[5] > 0) //error0
                {
                    if (adr == 1)
                        ErrorLog(LogMsgType.Error, "FC - HW-Error " + data[5].ToString() + ": " + ((FC_HWError0)data[5]).ToString());
                    if (adr == 2)
                        ErrorLog(LogMsgType.Error, "NC - HW-Error " + data[5].ToString() + ": " + ((NC_HWError0)data[5]).ToString());
                }
                if (data[6] > 0) //error1
                {
                    if (adr == 1)
                        ErrorLog(LogMsgType.Error, "FC - HW-Error " + data[6].ToString() + ": " + ((FC_HWError1)data[6]).ToString());
                    if (adr == 2)
                        ErrorLog(LogMsgType.Error, "NC - Unknown HW-ERROR: " + data[6].ToString()); //@moment NC has only one error field
                }
                if ((data[5] + data[6] == 0) && _bErrorLog)
                    _clearErrorLog(adr == 1 ? "FC - HW-Error" : "NC - HW-Error");

            }
            check_HWError = false;
        }
        /// <summary>
        /// BL-Ctrl data 'K'
        /// for FC you have to use a customized firmware
        /// </summary>
        /// <param name="data">the received byte array to process</param>
        void _processBLCtrl(byte[] data)
        {
            if (data.Length % 6 == 0) //data.Length up to 96 (16 motors x 6 byte data) --> new datastruct in FC -> not standard!
            {
                bool bAvailable = false;
                for (int i = 0; i < data.Length && data[i] < _iMotors; i += 6) // data[i] < _iMotors -- only show set number of motors (12 max @ moment)
                {

                    if ((data[i + 4] & 128) == 128) //Status bit at pos 7 = 128 dec -- if true, motor is available
                        bAvailable = true;
                    else
                        bAvailable = false;

                    if (data[i] < _iMotors)
                    {
                        if (bAvailable)
                        {
                            dtMotors.Rows[data[i]].SetField(1, ((double)data[i + 1] / (double)10).ToString("0.0 A"));
                            dtMotors.Rows[data[i]].SetField(2, data[i + 2].ToString("0 °C"));
                        }
                        else
                        {
                            dtMotors.Rows[data[i]].SetField(1, "NA");
                            dtMotors.Rows[data[i]].SetField(2, "NA");
                        }
                    }
                    //if (data[i] > 3 && data[i] < 8)
                    //{
                    //    if (bAvailable)
                    //    {
                    //        dtMotors2.Rows[data[i] - 4].SetField(1, ((double)data[i + 1] / (double)10).ToString("0.0 A"));
                    //        dtMotors2.Rows[data[i] - 4].SetField(2, data[i + 2].ToString("0 °C"));
                    //    }
                    //    else
                    //    {
                    //        dtMotors2.Rows[data[i] - 4].SetField(1, "NA");
                    //        dtMotors2.Rows[data[i] - 4].SetField(2, "NA");
                    //    }
                    //}
                }
            }
        }
        /// <summary>
        /// Navi-Ctrl data 'O'
        /// GPS-Position, capacatiy, flying time...
        /// </summary>
        /// <param name="data">the received byte array to process</param>
        void _processNCData(byte[] data)
        {
            int i_32, i_16, iVal;
            double d;
            i_32 = data[4];
            iVal = i_32 << 24;
            i_32 = data[3];
            iVal += i_32 << 16;
            i_32 = data[2];
            iVal += i_32 << 8;
            iVal += data[1];
            d = (double)iVal / Math.Pow(10, 7);
           
            PointLatLng p = new PointLatLng();

            p.Lng = d;
          //  lblNCGPSLong.Invoke((Action)(() => lblNCGPSLong.Text = d.ToString("0.######°"))); //GPS-Position: Longitude in decimal degree
            //lblNCGPSLong.Invoke((Action)(() => lblNCGPSLong.Text = _convertDegree(d))); //GPS-Position: Longitude in minutes, seconds

            i_32 = data[8];
            iVal = i_32 << 24;
            i_32 = data[7];
            iVal += i_32 << 16;
            i_32 = data[6];
            iVal += i_32 << 8;
            iVal += data[5];
            d = (double)iVal / Math.Pow(10, 7);
            p.Lat = d;
            if (data[50] > 4)//if more than 4 sats in use . otherwise the map would jump and scroll insane at beginning
            {
                _bSatFix = true; _iSatsJitter = 0; _bVoiceSatFixActive = false;
                if(_bAutoHome && !_bFirstSatFix)
                {
                    if (_iFirstSatFix < 3)
                        _iFirstSatFix++;
                    else
                    {
                        _bFirstSatFix = true;
                        Dispatcher.Invoke(() => setHomePos());
                    }
                }
                if (stbSatFixLostAnim != null && _bAnimSatFixActive)
                {
                    Dispatcher.Invoke(() => stbSatFixLostAnim.Stop());
                    _bAnimSatFixActive = false;
                }
                if (!_bFollowCopter)
                {
                    _setCopterData(p);
                    if (!MainMap.ViewArea.Contains(p))
                        Dispatcher.Invoke(() => MainMap.Position = p);

                }
                else
                    Dispatcher.Invoke(() => MainMap.Position = p);
            }
            else
            {
                if(_bSatFix)
                {
                    if (data[50] == _iSatsLast)
                    {
                        if (_iSatsJitter < 20) _iSatsJitter++;
                    }
                    else
                    {
                        _iSatsJitter = 0;
                        _iSatsLast = data[50];
                    }

                    if (_iSatsJitter == 20)
                    {
                        if (stbSatFixLostAnim != null && !_bAnimSatFixActive)
                        {
                            Dispatcher.Invoke(() => stbSatFixLostAnim.Begin());
                            _bAnimSatFixActive = true;
                        }
                        if (_bVoiceSatFixPlay && !_bVoiceSatFixActive)
                        {
                            Thread th = new Thread(() => _mediaPlayer("Voice\\CriticalBattery.mp3"));
                            th.Start();
                            _bVoiceSatFixActive = true;
                        }

                        _bSatFix = false;
                    }
                }
            }

            //  lblNCGPSLat.Invoke((Action)(() => lblNCGPSLat.Text = d.ToString("0.######°"))); //GPS-Position: Latitude in decimal degree
            //lblNCGPSLat.Invoke((Action)(() => lblNCGPSLat.Text = _convertDegree(d))); //GPS-Position: Latitude in minutes, seconds

            i_16 = data[28];
            i_16 = (Int16)(i_16 << 8);
            iVal = data[27] + i_16;
            Dispatcher.Invoke((Action)(() => tbWP.Text = ((double)iVal / (double)10).ToString("0.0 m"))); //Distance to next WP

            i_16 = data[45];
            i_16 = (Int16)(i_16 << 8);
            iVal = data[44] + i_16;
        //    Dispatcher.Invoke((Action)(() => tbTopDistanceHP.Text = ((double)iVal / (double)10).ToString("0.0 m"))); //Distance to HP set by GPS on
            Dispatcher.Invoke((Action)(() => tbHP.Text = ((double)iVal / (double)10).ToString("0.0 m"))); //Distance to HP set by GPS on

            Dispatcher.Invoke((Action)(() => tbWPIndex.Text = data[48].ToString())); //Waypoint index
            Dispatcher.Invoke((Action)(() => tbWPCount.Text = data[49].ToString())); //Waypoints count
 
            Dispatcher.Invoke((Action)(() => tbTopSats.Text = data[50].ToString())); //Satellites


            //--------------- Capacity used ------------------------
            i_16 = data[81];
            i_16 = (Int16)(i_16 << 8);
            iVal = data[80] + i_16;
            Dispatcher.Invoke((Action)(() => tbCapacity.Text = iVal.ToString() + " mAh"));
            Dispatcher.Invoke((Action)(() => tbTopCapacity.Text = iVal.ToString() + " mAh"));

            //--------------- Flying time ------------------------
            i_16 = data[56];
            i_16 = (Int16)(i_16 << 8);
            iVal = data[55] + i_16;
            TimeSpan t = TimeSpan.FromSeconds(iVal);
            string Text = t.Hours.ToString("D2") + ":" + t.Minutes.ToString("D2") + ":" + t.Seconds.ToString("D2");
            Dispatcher.Invoke((Action)(() => tbFTime.Text = Text.ToString()));
            Dispatcher.Invoke((Action)(() => tbTopFTime.Text = Text.ToString()));

            //--------------- RC quality ------------------------
            Dispatcher.Invoke((Action)(() => tbRCQ.Text = data[66].ToString()));
            Dispatcher.Invoke((Action)(() => tbTopRC.Text = data[66].ToString()));

            if(data[66] > _iThresholdRC)
            {
                _iRCLevelJitter = 0; _bVoiceRCLevelActive = false;
                if (stbRCLevelAnim != null && _bAnimRCLevelActive)
                {
                    Dispatcher.Invoke(() => stbRCLevelAnim.Stop());
                    _bAnimRCLevelActive = false;
                }
            }
            else
            {
                if (_iRCLevelJitter < 20) _iRCLevelJitter++;
                if (_iRCLevelJitter == 20)
                {
                    if (stbRCLevelAnim != null && !_bAnimRCLevelActive)
                    {
                        Dispatcher.Invoke(() => stbRCLevelAnim.Begin());
                        _bAnimRCLevelActive = true;
                    }
                    if (_bVoiceRCLevelPlay && !_bVoiceRCLevelActive)
                    {
                        Thread th = new Thread(() => _mediaPlayer("Voice\\RCLevel.mp3"));
                        th.Start();
                        _bVoiceRCLevelActive = true;
                    }
                        _iRCLevelJitter++;
                }
            }

            //--------------- NC Error ------------------------
            Dispatcher.Invoke((Action)(() => tbNCErr.Text = data[69].ToString()));  //NC Errornumber
            if (data[69] > 0)
                _readNCError();
            if (data[69] > 0 & data[69] < 44)
                ErrorLog(LogMsgType.Error, "NC Error [" + data[69].ToString() + "]: " + NC_Error[data[69]]);
            else
                if (_bErrorLog) _clearErrorLog("NC Error");

            //-------------FC / NC Status Flags
            Dispatcher.Invoke((Action)(() => FC1_1.Background = ((data[67] & 1) ==1) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS_MOTOR_RUN                             0x01
            Dispatcher.Invoke((Action)(() => FC1_2.Background = ((data[67] & 2) ==2) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS_FLY                                   0x02
            Dispatcher.Invoke((Action)(() => FC1_3.Background = ((data[67] & 4) ==4) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS_CALIBRATE                             0x04
            Dispatcher.Invoke((Action)(() => FC1_4.Background = ((data[67] & 8) ==8) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS_START                                 0x08
            Dispatcher.Invoke((Action)(() => FC1_5.Background = ((data[67] & 16) ==16) ? new SolidColorBrush(Colors.LightCoral) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS_EMERGENCY_LANDING                      0x10
            Dispatcher.Invoke((Action)(() => FC1_6.Background = ((data[67] & 32) ==32) ? new SolidColorBrush(Colors.LightCoral) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS_LOWBAT                         0x20

            Dispatcher.Invoke((Action)(() => FC2_1.Background = ((data[74] & 1) ==1) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS2_CAREFREE                             0x01
            Dispatcher.Invoke((Action)(() => FC2_2.Background = ((data[74] & 2) ==2) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS2_ALTITUDE_CONTROL                     0x02
            Dispatcher.Invoke((Action)(() => FC2_3.Background = ((data[74] & 4) ==4) ? new SolidColorBrush(Colors.LightCoral) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS2_RC_FAILSAVE_ACTIVE                      0x04
            Dispatcher.Invoke((Action)(() => FC2_4.Background = ((data[74] & 8) ==8) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS2_OUT1_ACTIVE                          0x08
            Dispatcher.Invoke((Action)(() => FC2_5.Background = ((data[74] & 16) ==16) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS2_OUT2_ACTIVE                        0x10
            Dispatcher.Invoke((Action)(() => FC2_6.Background = ((data[74] & 32) ==32) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS2_WAIT_FOR_TAKEOFF                   0x20   // Motor Running, but still on the ground
            Dispatcher.Invoke((Action)(() => FC2_7.Background = ((data[74] & 64) ==64) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS2_AUTO_STARTING                              0x40
            Dispatcher.Invoke((Action)(() => FC2_8.Background = ((data[74] & 128) ==128) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS2_AUTO_LANDING                             0x80

            Dispatcher.Invoke((Action)(() => NC1_2.Background = ((data[68] & 2) == 2) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// NC_FLAG_PH                                     0x02
            Dispatcher.Invoke((Action)(() => NC1_3.Background = ((data[68] & 4) == 4) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// NC_FLAG_CH                                     0x04
            Dispatcher.Invoke((Action)(() => NC1_4.Background = ((data[68] & 8) == 8) ? new SolidColorBrush(Colors.LightCoral) : new SolidColorBrush(Colors.Transparent)));// NC_FLAG_RANGE_LIMIT                               0x08
            Dispatcher.Invoke((Action)(() => NC1_5.Background = ((data[68] & 16) == 16) ? new SolidColorBrush(Colors.LightCoral) : new SolidColorBrush(Colors.Transparent)));// NC_FLAG_NOSERIALLINK                            0x10
            Dispatcher.Invoke((Action)(() => NC1_6.Background = ((data[68] & 32) == 32) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// NC_FLAG_TARGET_REACHED                               0x20
            Dispatcher.Invoke((Action)(() => NC1_7.Background = ((data[68] & 64) == 64) ? new SolidColorBrush(Colors.DodgerBlue) : new SolidColorBrush(Colors.Transparent)));// NC_FLAG_MANUAL_CONTROL                          0x40
            Dispatcher.Invoke((Action)(() => NC1_8.Background = ((data[68] & 128) == 128) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// NC_FLAG_GPS_OK                                     0x80

            //Sidebar StatusSymbols
            Dispatcher.Invoke((Action)(() => tbSideBarStatusMotors.Background = ((data[67] & 1) ==1) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS_MOTOR_RUN                             0x01
            Dispatcher.Invoke((Action)(() => tbSideBarStatusMotors.Foreground = ((data[67] & 1) ==1) ? new SolidColorBrush(Colors.White) : new SolidColorBrush(Color.FromArgb(255,211,210,210))));// FC_STATUS_MOTOR_RUN                                0x01
            Dispatcher.Invoke((Action)(() => tbSideBarStatusMotors.BorderBrush = ((data[67] & 1) ==1) ? new SolidColorBrush(Colors.White) : new SolidColorBrush(Color.FromArgb(255, 211, 210, 210))));// FC_STATUS_MOTOR_RUN                            0x01

            Dispatcher.Invoke((Action)(() => tbSideBarStatusCF.Background = ((data[74] & 1) == 1) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS2_CAREFREE                                0x01
            Dispatcher.Invoke((Action)(() => tbSideBarStatusCF.Foreground = ((data[74] & 1) == 1) ? new SolidColorBrush(Colors.White) : new SolidColorBrush(Color.FromArgb(255, 211, 210, 210))));// FC_STATUS2_CAREFREE                                0x01
            Dispatcher.Invoke((Action)(() => tbSideBarStatusCF.BorderBrush = ((data[74] & 1) ==1) ? new SolidColorBrush(Colors.White) : new SolidColorBrush(Color.FromArgb(255, 211, 210, 210))));// FC_STATUS2_CAREFREE                                0x01

            Dispatcher.Invoke((Action)(() => tbSideBarStatusEmergencyLanding.Background = ((data[67] & 16) == 16) ? new SolidColorBrush(Colors.LightCoral) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS_EMERGENCY_LANDING                   0x10
            Dispatcher.Invoke((Action)(() => tbSideBarStatusEmergencyLanding.Foreground = ((data[67] & 16) == 16) ? new SolidColorBrush(Colors.White) : new SolidColorBrush(Color.FromArgb(255, 211, 210, 210))));// FC_STATUS_EMERGENCY_LANDING                0x10
            Dispatcher.Invoke((Action)(() => tbSideBarStatusEmergencyLanding.BorderBrush = ((data[67] & 16) == 16) ? new SolidColorBrush(Colors.White) : new SolidColorBrush(Color.FromArgb(255, 211, 210, 210))));// FC_STATUS_EMERGENCY_LANDING               0x10

            Dispatcher.Invoke((Action)(() => tbSideBarStatusAC.Background = ((data[74] & 2) ==2) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// FC_STATUS2_ALTITUDE_CONTROL                         0x02
            Dispatcher.Invoke((Action)(() => tbSideBarStatusAC.Foreground = ((data[74] & 2) ==2) ? new SolidColorBrush(Colors.White) : new SolidColorBrush(Color.FromArgb(255, 211, 210, 210))));// FC_STATUS2_ALTITUDE_CONTROL                         0x02
            Dispatcher.Invoke((Action)(() => tbSideBarStatusAC.BorderBrush = ((data[74] & 2) ==2) ? new SolidColorBrush(Colors.White) : new SolidColorBrush(Color.FromArgb(255, 211, 210, 210))));// FC_STATUS2_ALTITUDE_CONTROL                        0x02

            Dispatcher.Invoke((Action)(() => tbSideBarStatusPH.Text = ((data[68] & 4) == 4) ? "CH" : "PH"));// NC_FLAG_PH 0x02 / NC_FLAG_CH 0x04
            Dispatcher.Invoke((Action)(() => tbSideBarStatusPH.Background = (((data[68] & 2) == 2)|((data[68] & 4) == 4)) ? new SolidColorBrush(Colors.LightSeaGreen) : new SolidColorBrush(Colors.Transparent)));// NC_FLAG_PH 0x02 / NC_FLAG_CH 0x04
            Dispatcher.Invoke((Action)(() => tbSideBarStatusPH.Foreground = (((data[68] & 2) == 2)|((data[68] & 4) == 4)) ? new SolidColorBrush(Colors.White) : new SolidColorBrush(Color.FromArgb(255, 211, 210, 210))));// NC_FLAG_PH 0x02 / NC_FLAG_CH 0x04
            Dispatcher.Invoke((Action)(() => tbSideBarStatusPH.BorderBrush = (((data[68] & 2) == 2)|((data[68] & 4) == 4)) ? new SolidColorBrush(Colors.White) : new SolidColorBrush(Color.FromArgb(255, 211, 210, 210))));// NC_FLAG_PH 0x02 / NC_FLAG_CH 0x04

        }
        /// <summary>
        /// Navi-Ctrl WP data struct 'X'
        /// called by index
        /// </summary>
        /// <param name="data">the received byte array to process</param>
        void _processWPData(byte[] data)
        {
            _iWPCount = data[0];
            _bGetWPCount = false;
            if (data.Length >= 28)
            {
                Dispatcher.Invoke(() => lblWPIndex.Content = data[1].ToString());
                Dispatcher.Invoke(() => lblWPCount.Content = data[0].ToString());
                if (_bGetWP)
                {
                    if (data[1] == 1)
                    {
                        dtWaypoints.Rows.Clear();
                        Dispatcher.Invoke(() => {
                            for (int k = 0; k < MainMap.Markers.Count;)
                            {
                                GMapMarker p = MainMap.Markers[k];
                                if (p.Shape.GetType() == typeof(CustomMarkerWP))
                                    MainMap.Markers.Remove(p);
                                else
                                    k++;
                            }
                        });
                    }
                    DataRow dr = dtWaypoints.NewRow();
                    dr = Waypoints.toDataRow(data, dr);
                    dtWaypoints.Rows.Add(dr);
                    Dispatcher.Invoke(() => {
                        GMapMarker wp = new GMapMarker(new PointLatLng((double)dr[3], (double)dr[4]));
                        wp.Shape = new CustomMarkerWP(this, wp, (string)dr[2],(int)dr[1]);
                        _setMarkerColor(wp, (int)dr[1]);
                        MainMap.Markers.Add(wp);
                    });
                    Dispatcher.Invoke(() => dgvWP.Items.Refresh());
                    Dispatcher.Invoke(() => _iWPIndex = data[1]);
                    if (data[1] == data[0])
                    {
                        _bGetWP = false;
                        Dispatcher.Invoke(() => dgvWP.Items.Refresh());
                    }

                }
            }
            else
            {
                Dispatcher.Invoke(() => lblWPIndex.Content = 0);
                Dispatcher.Invoke(() => lblWPCount.Content = 0);
            }
        }
        /// <summary>
        /// OSD Menue 'L'
        /// single page called by pagenumber
        /// no autoupdate
        /// </summary>
        /// <param name="data">the received byte array to process</param>
        void _processOSDSingle(byte[] data)
        {
            if (data.Length == 84)
            {
                string sMessage = "";
                iOSDPage = data[0];
                iOSDMax = data[1];
                if (cbOSD.Items.Count != iOSDMax) _initOSDCB();
                sMessage = new string(ASCIIEncoding.ASCII.GetChars(data, 2, data.Length - 4));
                OSD(LogMsgType.Incoming, sMessage.Substring(0, 20)+ "\r", true);
                OSD(LogMsgType.Incoming, sMessage.Substring(20, 20)+ "\r", false);
                OSD(LogMsgType.Incoming, sMessage.Substring(40, 20)+ "\r", false);
                OSD(LogMsgType.Incoming, sMessage.Substring(60, 20), false);
                Dispatcher.Invoke(() => { cbOSD.SelectedValue = iOSDPage; });
              //  lblOSDPageNr.Invoke((Action)(() => lblOSDPageNr.Text = iOSDPage.ToString("[0]")));

            }
            //else
            //    OSD(LogMsgType.Incoming, "Wrong length: " + data.Length + " (should be 84)");

        }
        /// <summary>
        /// OSD Menue 'H'
        /// called by keys (0x01,0x02,0x03,0x04)
        /// autoupdate
        /// </summary>
        /// <param name="data">the received byte array to process</param>
        void _processOSDAuto(byte[] data)
        {
            if (data.Length == 81)
            {
                string sMessage = "";
                sMessage = new string(ASCIIEncoding.ASCII.GetChars(data, 0, data.Length - 1));
                OSD(LogMsgType.Incoming, sMessage.Substring(0, 20)+ "\r", true);
                OSD(LogMsgType.Incoming, sMessage.Substring(20, 20)+ "\r", false);
                OSD(LogMsgType.Incoming, sMessage.Substring(40, 20)+ "\r", false);
                OSD(LogMsgType.Incoming, sMessage.Substring(60, 20), false);

            }
            //else
            //    OSD(LogMsgType.Incoming, "Wrong length: " + data.Length + " (should be 81)");
        }

        #endregion processing received data
 
        #region controller messages
        /// <summary> send message to controller to request data
        /// for detailed info see http://wiki.mikrokopter.de/en/SerialProtocol/
        /// </summary>
        /// <param name="CMDID"> the command ID </param>
        /// <param name="address"> the address of the controller: 0-any, 1-FC, 2-NC </param>
        private void _sendControllerMessage(char CMDID, byte address)
        {
            if (serialPortCtrl.Port.IsOpen)
            {
                Stream serialStream = serialPortCtrl.Port.BaseStream;
                byte[] bytes = FlightControllerMessage.CreateMessage(CMDID, address);
                serialStream.Write(bytes, 0, bytes.Length);

            }
            else
                Log(LogMsgType.Error, "NOT CONNECTED!");
        }
        /// <summary> send message to controller to request data
        /// for detailed info see http://wiki.mikrokopter.de/en/SerialProtocol/
        /// </summary>
        /// <param name="CMDID"> the command ID </param>
        /// <param name="address"> the address of the controller: 0-any, 1-FC, 2-NC </param>
        /// <param name="data"> additional data for the request</param>
        private void _sendControllerMessage(char CMDID, byte address, byte[] data)
        {
            if (serialPortCtrl.Port.IsOpen)
            {
                Stream serialStream = serialPortCtrl.Port.BaseStream;
                byte[] bytes = FlightControllerMessage.CreateMessage(CMDID, address, data);
                serialStream.Write(bytes, 0, bytes.Length);

            }
            else
                Log(LogMsgType.Error, "NOT CONNECTED!");
        }

        /// <summary>
        /// start/stop continous polling of controller values
        /// </summary>
        /// <param name="b">start/stop switch</param>
        void _readCont(bool b)
        {
            bReadContinously = b;
            if (bReadContinously)
            {
                if (_debugDataAutorefresh) { _readDebugData(true); Thread.Sleep(10); }
                if (_blctrlDataAutorefresh) { _readBLCtrl(true); Thread.Sleep(10); }
                if (_navCtrlDataAutorefresh && _iCtrlAct == 2) { _readNavData(true); Thread.Sleep(10); }
                if (_OSDAutorefresh) { _OSDMenueAutoRefresh(); Thread.Sleep(10); }
                // Dispatcher.Invoke((Action)(() => rctConnection.Fill = Brushes.LightGreen));
                Dispatcher.Invoke(() => imageConn.Source = new BitmapImage(new Uri("Images/Data_G.png", UriKind.Relative)));
            }
            else
            {
                // Dispatcher.Invoke((Action)(() => rctConnection.Fill = Brushes.LightGray));
                Dispatcher.Invoke(() => imageConn.Source = new BitmapImage(new Uri("Images/Data_W.png", UriKind.Relative)));
                _bConnErr = false;
            }
            _iLifeCounter = 0;
        }

        private void _getVersion()
        {
            _sendControllerMessage('v', 0);
        }
        /// <summary>
        /// get FC version struct via NC
        /// by sending '1' as data (not documented in wiki...)
        /// returns HW error 255 (comment in uart1.c : tells the KopterTool that it is the FC-version)
        /// </summary>
        /// <param name="ctrl">controller number 1=FC</param>
        private void _getVersion(byte ctrl)
        {
            _sendControllerMessage('v', 0, new byte[1] { ctrl });
        }
        /// <summary>
        /// Switch back to NC by sending the 'Magic Packet' 0x1B,0x1B,0x55,0xAA,0x00
        /// </summary>
        private void _switchToNC()
        {
            if (serialPortCtrl.Port.IsOpen)
            {
                Stream serialStream = serialPortCtrl.Port.BaseStream;
                byte[] bytes = new byte[5] { 0x1B, 0x1B, 0x55, 0xAA, 0x00 };
                serialStream.Write(bytes, 0, bytes.Length);

                Thread.Sleep(100);
                _getVersion();
                Thread.Sleep(100);
               // _OSDMenue(0);
            }
            else
                Log(LogMsgType.Error, "NOT CONNECTED!");
        }
        /// <summary>
        /// switch to FC
        /// </summary>
        private void _switchToFC()
        {
            _sendControllerMessage('u', 2, new byte[1] { (byte)0 });
            Thread.Sleep(100);
            _getVersion();
            Thread.Sleep(100);
          //  _OSDMenue(0);
        }
        /// <summary>
        /// send RESET signal to FC
        /// </summary>
        private void _resetCtrl()
        {
            _sendControllerMessage('R', 1);
        }
        /// <summary>
        /// poll the debug data (4sec subscription)
        /// </summary>
        /// <param name="auto"> onetimequery(false) or autoupdate(true) with set timing interval </param>
        private void _readDebugData(bool auto)
        {
            byte interval = auto ? debugInterval : (byte)0;
            _sendControllerMessage('d', 0, new byte[1] { debugInterval });
        }
        /// <summary>
        /// poll the BL-CTRL status via NC (4sec subscription)
        /// </summary>
        /// <param name="auto"> onetimequery(false) or autoupdate(true) with set timing interval </param>
        private void _readBLCtrl(bool auto)
        {
            byte interval = auto ? blctrlInterval : (byte)0;
            _sendControllerMessage('k', 0, new byte[1] { interval });
        }
        /// <summary>
        /// poll the NC data struct (4sec subscription)
        /// </summary>
        /// <param name="auto"> onetimequery(false) or autoupdate(true) with set timing interval </param>
        private void _readNavData(bool auto)
        {
            byte interval = auto ? navctrlInterval : (byte)0;
            _sendControllerMessage('o', 2, new byte[1] { interval });
        }
        /// <summary>
        /// get the errortext for pending NC error
        /// </summary>
        private void _readNCError()
        {
            _sendControllerMessage('e', 2);
        }
        /// <summary>
        /// request the Waypoint at index
        /// </summary>
        /// <param name="index"></param>
        void _getpWP(int index)
        {
            if (serialPortCtrl.Port.IsOpen)
            {
                Stream serialStream = serialPortCtrl.Port.BaseStream;
                byte[] bytes = FlightControllerMessage.CreateMessage('x', 2, new byte[1] { (byte)index });
                serialStream.Write(bytes, 0, bytes.Length);
            }
            else
                Log(LogMsgType.Error, "NOT CONNECTED!");

        }
        void _getWP()
        {
            _bGetWPCount = true;
            _getpWP(1); //get the itemscount of wp
            while (_bGetWPCount)
                Thread.Sleep(100);
            if (_iWPCount > 0)
                _getWPList();
        }
        void _getWPList()
        {
            _bGetWP = true;
            int iTimeout=0;
            for (int j = 0; j < _iWPCount; j++)
            {
                _getpWP(j + 1);
                iTimeout = 0;
                while (_iWPIndex != j + 1 & iTimeout < _iWPTimeout * 5)
                {
                    Thread.Sleep(1);
                    iTimeout++;
                }
            }
        }
        void _sendWPList()
        {
            if (serialPortCtrl.Port.IsOpen)
            {
                byte[] bData = new byte[30];
                for (int i = 0; i < 30; i++)
                    bData[i] = 0;
                Stream serialStream = serialPortCtrl.Port.BaseStream;
                byte[] bytes = FlightControllerMessage.CreateMessage('w', 2, bData); //delete all WP on Copter by sending 'invalid'(==0) at index 0
                serialStream.Write(bytes, 0, bytes.Length);

                _iWPCount = -1;
                while (_iWPCount == -1)
                    Thread.Sleep(10);
                Dispatcher.Invoke(() => lblWPCount.Content = _iWPCount.ToString());

                int iVal;
                double dVal;
                NumberFormatInfo nfi = new NumberFormatInfo();
                nfi.NumberDecimalSeparator = ",";
                for (int i = 0; i < dtWaypoints.Rows.Count; i++)
                {
                    //longitude
                    dVal = Convert.ToDouble(dtWaypoints.Rows[i][4], nfi);
                    iVal = (int)(dVal * Math.Pow(10, 7));
                    bData[0] = (byte)(iVal & 0xff);
                    bData[1] = (byte)((iVal >> 8) & 0xff);
                    bData[2] = (byte)((iVal >> 16) & 0xff);
                    bData[3] = (byte)(iVal >> 24);
                    //latitude
                    dVal = Convert.ToDouble(dtWaypoints.Rows[i][3], nfi);
                    iVal = (int)(dVal * Math.Pow(10, 7));
                    bData[4] = (byte)(iVal & 0xff);
                    bData[5] = (byte)((iVal >> 8) & 0xff);
                    bData[6] = (byte)((iVal >> 16) & 0xff);
                    bData[7] = (byte)(iVal >> 24);
                    //altitude
                    dVal = Convert.ToDouble(dtWaypoints.Rows[i][5], nfi);
                    iVal = (int)(dVal * 10);
                    bData[8] = (byte)(iVal & 0xff);
                    bData[9] = (byte)((iVal >> 8) & 0xff);
                    bData[10] = (byte)((iVal >> 16) & 0xff);
                    bData[11] = (byte)(iVal >> 24);
                    //Status 'NEWDATA'
                    bData[12] = 1;
                    //heading
                    iVal = Convert.ToInt16(dtWaypoints.Rows[i][6]);
                    bData[13] = (byte)(iVal & 0xff);
                    bData[14] = (byte)((iVal >> 8) & 0xff);
                    //ToleranceRadius
                    bData[15] = Convert.ToByte(dtWaypoints.Rows[i][9]);
                    //HoldTime
                    bData[16] = Convert.ToByte(dtWaypoints.Rows[i][10]);
                    //Event_Flag
                    bData[17] = Convert.ToByte(dtWaypoints.Rows[i][13]);
                    //Index
                    bData[18] = Convert.ToByte((int)dtWaypoints.Rows[i][0]);
                    //Type
                    bData[19] = Convert.ToByte(dtWaypoints.Rows[i][1]);
                    //WP_EventChannelValue
                    bData[20] = Convert.ToByte(dtWaypoints.Rows[i][14]);
                    //AltitudeRate
                    bData[21] = Convert.ToByte(dtWaypoints.Rows[i][8]);
                    //Speed
                    bData[22] = Convert.ToByte(dtWaypoints.Rows[i][7]);
                    //CamAngle
                    bData[23] = (byte)Convert.ToInt16(dtWaypoints.Rows[i][12]);
                    //Name
                    byte[] name = ASCIIEncoding.ASCII.GetBytes((string)dtWaypoints.Rows[i][2]);
                    bData[24] = name.Length > 0 ? name[0] : (byte)0;
                    bData[25] = name.Length > 1 ? name[1] : (byte)0;
                    bData[26] = name.Length > 2 ? name[2] : (byte)0;
                    bData[27] = name.Length > 3 ? name[3] : (byte)0;
                    //Autotrigger
                    bData[28] = Convert.ToByte(dtWaypoints.Rows[i][11]);

                    bytes = FlightControllerMessage.CreateMessage('w', 2, bData);
                    serialStream.Write(bytes, 0, bytes.Length);

                    _iWPCount = -1;
                    while (_iWPCount == -1)
                        Thread.Sleep(10);
                    Dispatcher.Invoke(() => lblWPCount.Content = _iWPCount.ToString());
                }
            }
            else
                Log(LogMsgType.Error, "NOT CONNECTED!");

        }

        #region OSD-Menue

        /// <summary>
        /// one time query of the OSD Menue with pagenumber
        /// </summary>
        /// <param name="iMenue">Menue page</param>
        void _OSDMenue(int iMenue)
        {
            if (serialPortCtrl.Port.IsOpen)
            {
                if (iMenue > iOSDMax)
                    iMenue = 0;
                Stream serialStream = serialPortCtrl.Port.BaseStream;
                byte[] bytes = FlightControllerMessage.CreateMessage('l', 0, new byte[1] { (byte)iMenue });
                serialStream.Write(bytes, 0, bytes.Length);
            }
            else
                Log(LogMsgType.Error, "NOT CONNECTED!");

        }
        /// <summary>
        /// call the OSDMenue and start autorefresh
        ///  usually by sending a menuekey
        /// 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)
        /// therefore the value has to be negative (inverted) in order to distinguish from old (2 line) menuestyle
        /// and must not have any bits of the menue keys 0x1 0x2 0x4 0x8 (0x10?) --> 0x20 = -33
        /// </summary>
        void _OSDMenueAutoRefresh()
        {
            _sendControllerMessage('h', 0, new byte[2] { unchecked((byte)(-33)), OSDInterval });
        }
        void _OSDMenueAutoRefresh(byte key)
        {
            _sendControllerMessage('h', 0, new byte[2] { unchecked((byte)~key), OSDInterval });
        }
        /// <summary>
        /// initialize the OSD menue combobox
        /// combox is filled by numbers from 0 to max pagenumber
        /// </summary>
        void _initOSDCB()
        {
            _bCBInit = true;
            if (iOSDMax == 0)
            {
                _OSDMenue(0);
                Thread.Sleep(10);
            }
            Dispatcher.Invoke((Action)(() => cbOSD.Items.Clear()));
            for (int i = 0; i <= iOSDMax; i++)
            {
                Dispatcher.Invoke((Action)(() => cbOSD.Items.Add(i)));
            }
            Dispatcher.Invoke((Action)(() => cbOSD.SelectedItem = iOSDPage));
            _bCBInit = false;
        }
        private void btnOSDForward_Click(object sender, RoutedEventArgs e)
        {
            iOSDPage++;
            if (iOSDPage > iOSDMax)
                iOSDPage = 0;

            _OSDMenue(iOSDPage);
        }
        private void btnOSDBackward_Click(object sender, RoutedEventArgs e)
        {
            iOSDPage--;
            if (iOSDPage < 0)
                iOSDPage = iOSDMax;

            _OSDMenue(iOSDPage);
        }
        private void btnOSDLeave_Click(object sender, RoutedEventArgs e)
        {
            _OSDMenueAutoRefresh(8);
        }
        private void btnOSDEnter_Click(object sender, RoutedEventArgs e)
        {
            _OSDMenueAutoRefresh(4);
        }
        private void cbOSD_DropDownClosing(object sender, EventArgs e)
        {
            if (!_bCBInit && cbOSD.SelectedIndex > -1)
                _OSDMenue(cbOSD.SelectedIndex);
        }
        private void OSD(LogMsgType msgtype, string msg, bool bNew)
        {
            Dispatcher.Invoke(() =>
            {
                TextRange tr;
                if (bNew)
                {
                    rtfOSD.SelectAll();
                    rtfOSD.Selection.Text = string.Empty;
                }
                tr = new TextRange(rtfOSD.Document.ContentEnd, rtfOSD.Document.ContentEnd);
                tr.Text = msg;
                tr.ApplyPropertyValue(TextElement.ForegroundProperty, new SolidColorBrush(LogMsgTypeColor[(int)msgtype]));
                //     rtfOSD.AppendText("\r");
                rtfOSD.ScrollToEnd();

            });
        }

        #endregion OSD-Menue

        #endregion controller messages

        void _mediaPlayer(string file)
        {
            if (File.Exists(file))
            {
                MediaPlayer.MediaPlayer mp = new MediaPlayer.MediaPlayer();
                mp.Open(file);
                mp.Play();
            }
        }

        /// <summary>
        /// Switch between fullscreen and normal window mode
        /// save & restore scaling settings
        /// </summary>
        /// <param name="sender"></param>
        /// <param name="e"></param>
        private void imageFullscreen_MouseDown(object sender, MouseButtonEventArgs e)
        {
            if (winState.isMaximized)
            {
                winState.Restore(this);
                imageFullscreen.Source = new BitmapImage(new Uri("Images/Fullscreen.png", UriKind.Relative));
                if(_bSaveWinStateFull)
                    _saveScaleSliders(true);
                if(_bSaveWinStateNormal)
                    _setScaleSliders(false);
            }
            else
            {
                winState.Maximize(this);
                imageFullscreen.Source = new BitmapImage(new Uri("Images/RestoreScreen.png", UriKind.Relative));
                if(_bSaveWinStateNormal)
                    _saveScaleSliders(false);
                if(_bSaveWinStateFull)
                    _setScaleSliders(true);
            }
        }

        /// <summary>
        /// reset the scaling of all UI elements to default
        /// </summary>
        /// <param name="sender"></param>
        /// <param name="e"></param>
        private void buttonUIScaleReset_Click(object sender, RoutedEventArgs e)
        {
            UIScaleHorizonSlider.Value =
                UIScaleLOGSlider.Value =
                UIScaleMotorsSlider.Value =
                UIScaleOSDSlider.Value =
                UIScaleSlider.Value =
                UIScaleTopSlider.Value = 1;
        }
        /// <summary>
        /// adjust the top postion of UI elements below the top bar to fit the bottom position of the bar when scaling the top bar
        /// </summary>
        /// <param name="sender"></param>
        /// <param name="e"></param>
        private void UIScaleTopSlider_ValueChanged(object sender, RoutedPropertyChangedEventArgs<double> e)
        {
            GridSettings.Margin = new Thickness(GridSettings.Margin.Left, 36 * UIScaleTopSlider.Value, GridSettings.Margin.Right, GridSettings.Margin.Bottom);
            if (GridMotors != null)
                GridMotors.Margin = new Thickness(GridMotors.Margin.Left, 36 * UIScaleTopSlider.Value, GridMotors.Margin.Right, GridMotors.Margin.Bottom);
            if (GridSideBar != null)
                GridSideBar.Margin = new Thickness(GridSideBar.Margin.Left, 36 * UIScaleTopSlider.Value, GridSideBar.Margin.Right, GridSideBar.Margin.Bottom);
            if (GridOSD != null)
                GridOSD.Margin = new Thickness(GridOSD.Margin.Left, 36 * UIScaleTopSlider.Value, GridOSD.Margin.Right, GridOSD.Margin.Bottom);
            if (GridData != null)
                GridData.Margin = new Thickness(GridData.Margin.Left, 36 * UIScaleTopSlider.Value, GridData.Margin.Right, GridData.Margin.Bottom);
            if (GridWP != null)
                GridWP.Margin = new Thickness(GridWP.Margin.Left, 36 * UIScaleTopSlider.Value, GridWP.Margin.Right, GridWP.Margin.Bottom);
        }
        /// <summary>
        /// restore the saved scalings for the fullscreen/normal window mode
        /// </summary>
        /// <param name="bFull">the mode the window is set to</param>
        void _setScaleSliders(bool bFull)
        {
            if(bFull)
            {
                UIScaleSlider.Value = scaleFullAll;
                UIScaleTopSlider.Value = scaleFullTopBar;
                UIScaleMotorsSlider.Value = scaleFullMotors;
                UIScaleOSDSlider.Value = scaleFullOSD;
                UIScaleLOGSlider.Value = scaleFullLOG;
                UIScaleHorizonSlider.Value = scaleFullHorizon;
            }
            else
            {
                UIScaleSlider.Value = scaleNormalAll;
                UIScaleTopSlider.Value = scaleNormalTopBar;
                UIScaleMotorsSlider.Value = scaleNormalMotors;
                UIScaleOSDSlider.Value = scaleNormalOSD;
                UIScaleLOGSlider.Value = scaleNormalLOG;
                UIScaleHorizonSlider.Value = scaleNormalHorizon;
            }
        }

        /// <summary>
        /// save the scalings for the actual window mode
        /// </summary>
        /// <param name="bFull">the actual window mode</param>
        void _saveScaleSliders(bool bFull)
        {

            if (bFull)
            {
                scaleFullAll = UIScaleSlider.Value;
                scaleFullTopBar = UIScaleTopSlider.Value;
                scaleFullMotors = UIScaleMotorsSlider.Value;
                scaleFullOSD = UIScaleOSDSlider.Value;
                scaleFullLOG = UIScaleLOGSlider.Value;
                scaleFullHorizon = UIScaleHorizonSlider.Value;
            }
            else
            {
                scaleNormalAll = UIScaleSlider.Value;
                scaleNormalTopBar = UIScaleTopSlider.Value;
                scaleNormalMotors = UIScaleMotorsSlider.Value;
                scaleNormalOSD = UIScaleOSDSlider.Value;
                scaleNormalLOG = UIScaleLOGSlider.Value;
                scaleNormalHorizon = UIScaleHorizonSlider.Value;
            }
        }

        /// <summary>
        /// read settings from ini-file
        /// </summary>
        void _readIni()
        {
            if (!File.Exists(filePath + "\\MKLiveViewSettings.ini"))
                _writeIni();
            IniFile ini = new IniFile("MKLiveViewSettings.ini");
            ini.path = filePath + "\\MKLiveViewSettings.ini";
            try
            {

                string sVal = ini.IniReadValue("timings", "AutorefreshDebugData");
                if (sVal != "") _debugDataAutorefresh = Convert.ToBoolean(sVal);
                sVal = ini.IniReadValue("timings", "AutorefreshNavCtrlData");
                if (sVal != "") _navCtrlDataAutorefresh = Convert.ToBoolean(sVal);
                sVal = ini.IniReadValue("timings", "AutorefreshBLCtrlData");
                if (sVal != "") _blctrlDataAutorefresh = Convert.ToBoolean(sVal);
                sVal = ini.IniReadValue("timings", "AutorefreshOSDData");
                if (sVal != "") _OSDAutorefresh = Convert.ToBoolean(sVal);

                sVal = ini.IniReadValue("timings", "IntervalDebugData");
                if (sVal != "") debugInterval = (byte)Convert.ToInt16(sVal);
                sVal = ini.IniReadValue("timings", "IntervalNavCtrlData");
                if (sVal != "") navctrlInterval = (byte)Convert.ToInt16(sVal);
                sVal = ini.IniReadValue("timings", "IntervalBLCtrlData");
                if (sVal != "") blctrlInterval = (byte)Convert.ToInt16(sVal);
                sVal = ini.IniReadValue("timings", "IntervalOSDData");
                if (sVal != "") OSDInterval = (byte)Convert.ToInt16(sVal);

                sVal = ini.IniReadValue("topBar", "voltage");
                if (sVal != "") chkBoxTopBarShowVoltage.IsChecked = Convert.ToBoolean(sVal);
                sVal = ini.IniReadValue("topBar", "capacity");
                if (sVal != "") chkBoxTopBarShowCapacity.IsChecked = Convert.ToBoolean(sVal);
                sVal = ini.IniReadValue("topBar", "current");
                if (sVal != "") chkBoxTopBarShowCurrent.IsChecked = Convert.ToBoolean(sVal);
                sVal = ini.IniReadValue("topBar", "flightTime");
                if (sVal != "") chkBoxTopBarShowFlightTime.IsChecked = Convert.ToBoolean(sVal);
                sVal = ini.IniReadValue("topBar", "distanceHP");
                if (sVal != "") chkBoxTopBarShowDistanceHP.IsChecked = Convert.ToBoolean(sVal);
                sVal = ini.IniReadValue("topBar", "height");
                if (sVal != "") chkBoxTopBarShowHeight.IsChecked = Convert.ToBoolean(sVal);
                sVal = ini.IniReadValue("topBar", "speed");
                if (sVal != "") chkBoxTopBarShowSpeed.IsChecked = Convert.ToBoolean(sVal);
                sVal = ini.IniReadValue("topBar", "magneticField");
                if (sVal != "") chkBoxTopBarShowMF.IsChecked = Convert.ToBoolean(sVal);
                sVal = ini.IniReadValue("topBar", "satellites");
                if (sVal != "") chkBoxTopBarShowSatellites.IsChecked = Convert.ToBoolean(sVal);
                sVal = ini.IniReadValue("topBar", "rc");
                if (sVal != "") chkBoxTopBarShowRC.IsChecked = Convert.ToBoolean(sVal);

                sVal = ini.IniReadValue("style", "saveFullScreen");
                if (sVal != "") chkBoxSaveFullScreenState.IsChecked = Convert.ToBoolean(sVal);
                sVal = ini.IniReadValue("style", "saveNormalState");
                if (sVal != "") chkBoxSaveNormalState.IsChecked = Convert.ToBoolean(sVal);

                sVal = ini.IniReadValue("style", "scaleNormalAll");
                if (sVal != "") scaleNormalAll = Convert.ToDouble(sVal);
                sVal = ini.IniReadValue("style", "scaleNormalTopBar");
                if (sVal != "") scaleNormalTopBar = Convert.ToDouble(sVal);
                sVal = ini.IniReadValue("style", "scaleNormalMotors");
                if (sVal != "") scaleNormalMotors = Convert.ToDouble(sVal);
                sVal = ini.IniReadValue("style", "scaleNormalOSD");
                if (sVal != "") scaleNormalOSD = Convert.ToDouble(sVal);
                sVal = ini.IniReadValue("style", "scaleNormalLOG");
                if (sVal != "") scaleNormalLOG = Convert.ToDouble(sVal);
                sVal = ini.IniReadValue("style", "scaleNormalHorizon");
                if (sVal != "") scaleNormalHorizon = Convert.ToDouble(sVal);

                sVal = ini.IniReadValue("style", "scaleFullAll");
                if (sVal != "") scaleFullAll = Convert.ToDouble(sVal);
                sVal = ini.IniReadValue("style", "scaleFullTopBar");
                if (sVal != "") scaleFullTopBar = Convert.ToDouble(sVal);
                sVal = ini.IniReadValue("style", "scaleFullMotors");
                if (sVal != "") scaleFullMotors = Convert.ToDouble(sVal);
                sVal = ini.IniReadValue("style", "scaleFullOSD");
                if (sVal != "") scaleFullOSD = Convert.ToDouble(sVal);
                sVal = ini.IniReadValue("style", "scaleFullLOG");
                if (sVal != "") scaleFullLOG = Convert.ToDouble(sVal);
                sVal = ini.IniReadValue("style", "scaleFullHorizon");
                if (sVal != "") scaleFullHorizon = Convert.ToDouble(sVal);

                sVal = ini.IniReadValue("general", "LiPoCells");
                _LipoCells = Convert.ToInt16(sVal);
                sVal = ini.IniReadValue("general", "Motors");
                if (sVal != "") _iMotors = Convert.ToInt16(sVal);

                sVal = ini.IniReadValue("map", "followMe");
                if (sVal != "") _bFollowCopter = Convert.ToBoolean(sVal);
                sVal = ini.IniReadValue("map", "AutoSetHome");
                if (sVal != "") _bAutoHome = Convert.ToBoolean(sVal);

                sVal = ini.IniReadValue("threshold", "VoltageWarning");
                if(sVal != "") _dThresholdVoltageWarn = Convert.ToDouble(sVal);
                sVal = ini.IniReadValue("threshold", "VoltageCritical");
                if(sVal != "") _dThresholdVoltageCrit = Convert.ToDouble(sVal);
                sVal = ini.IniReadValue("threshold", "VoiceVoltageEnable");
                if(sVal != "") _bVoiceVoltPlay = Convert.ToBoolean(sVal);
                sVal = ini.IniReadValue("threshold", "VoiceSatFixEnable");
                if(sVal != "") _bVoiceSatFixPlay = Convert.ToBoolean(sVal);
                sVal = ini.IniReadValue("threshold", "VoiceMagFieldEnable");
                if(sVal != "") _bVoiceMagneticFieldPlay = Convert.ToBoolean(sVal);
                sVal = ini.IniReadValue("threshold", "DistanceWarning");
                if(sVal != "") _dThresholdDistanceWarn = Convert.ToDouble(sVal);
                sVal = ini.IniReadValue("threshold", "VoiceDistanceWarnEnable");
                if(sVal != "") _bVoiceDistancePlay = Convert.ToBoolean(sVal);
                sVal = ini.IniReadValue("threshold", "VoiceRCLevelWarnEnable");
                if(sVal != "") _bVoiceRCLevelPlay = Convert.ToBoolean(sVal);
                sVal = ini.IniReadValue("threshold", "MaxDistance");
                if(sVal != "") _dThresholdDistanceMax = Convert.ToDouble(sVal);
                sVal = ini.IniReadValue("threshold", "RCThreshold");
                if(sVal != "") _iThresholdRC = Convert.ToInt32(sVal);
                sVal = ini.IniReadValue("threshold", "MagFieldThreshold");
                if(sVal != "") _iThresholdMagField = Convert.ToInt32(sVal);
            }
            catch (Exception e)
            {

                MessageBox.Show("Error parsing ini-file!" + Environment.NewLine + e.Message,"Read ini-file" ,MessageBoxButton.OK,MessageBoxImage.Error);
            }

        }

        /// <summary>
        /// save settings to ini-file
        /// </summary>
        void _writeIni()
        {

            IniFile ini = new IniFile("MKLiveViewSettings.ini");
            ini.path = filePath + "\\MKLiveViewSettings.ini";

            try
            {

                ini.IniWriteValue("timings", "AutorefreshDebugData", _debugDataAutorefresh ? "true" : "false");
                ini.IniWriteValue("timings", "AutorefreshNavCtrlData", _navCtrlDataAutorefresh ? "true" : "false");
                ini.IniWriteValue("timings", "AutorefreshBLCtrlData", _blctrlDataAutorefresh ? "true" : "false");
                ini.IniWriteValue("timings", "AutorefreshOSDData", _OSDAutorefresh ? "true" : "false");

                ini.IniWriteValue("timings", "IntervalDebugData", debugInterval.ToString());
                ini.IniWriteValue("timings", "IntervalNavCtrlData", navctrlInterval.ToString());
                ini.IniWriteValue("timings", "IntervalBLCtrlData", blctrlInterval.ToString());
                ini.IniWriteValue("timings", "IntervalOSDData", OSDInterval.ToString());

                ini.IniWriteValue("general", "LiPoCells", _LipoCells.ToString());
                ini.IniWriteValue("general", "Motors", _iMotors.ToString());

                ini.IniWriteValue("map", "followMe", _bFollowCopter.ToString());
                ini.IniWriteValue("map", "AutoSetHome", _bAutoHome.ToString());

                ini.IniWriteValue("topBar", "voltage", chkBoxTopBarShowVoltage.IsChecked.ToString());
                ini.IniWriteValue("topBar", "capacity", chkBoxTopBarShowCapacity.IsChecked.ToString());
                ini.IniWriteValue("topBar", "current", chkBoxTopBarShowCurrent.IsChecked.ToString());
                ini.IniWriteValue("topBar", "flightTime", chkBoxTopBarShowFlightTime.IsChecked.ToString());
                ini.IniWriteValue("topBar", "distanceHP", chkBoxTopBarShowDistanceHP.IsChecked.ToString());
                ini.IniWriteValue("topBar", "height", chkBoxTopBarShowHeight.IsChecked.ToString());
                ini.IniWriteValue("topBar", "speed", chkBoxTopBarShowSpeed.IsChecked.ToString());
                ini.IniWriteValue("topBar", "magneticField", chkBoxTopBarShowMF.IsChecked.ToString());
                ini.IniWriteValue("topBar", "satellites", chkBoxTopBarShowSatellites.IsChecked.ToString());
                ini.IniWriteValue("topBar", "rc", chkBoxTopBarShowRC.IsChecked.ToString());

                ini.IniWriteValue("style", "saveFullScreen", chkBoxSaveFullScreenState.IsChecked.ToString());
                ini.IniWriteValue("style", "saveNormalState", chkBoxSaveNormalState.IsChecked.ToString());

                ini.IniWriteValue("style", "scaleNormalAll", scaleNormalAll.ToString());
                ini.IniWriteValue("style", "scaleNormalTopBar", scaleNormalTopBar.ToString());
                ini.IniWriteValue("style", "scaleNormalMotors", scaleNormalMotors.ToString());
                ini.IniWriteValue("style", "scaleNormalOSD", scaleNormalOSD.ToString());
                ini.IniWriteValue("style", "scaleNormalLOG", scaleNormalLOG.ToString());
                ini.IniWriteValue("style", "scaleNormalHorizon", scaleNormalHorizon.ToString());

                ini.IniWriteValue("style", "scaleFullAll", scaleFullAll.ToString());
                ini.IniWriteValue("style", "scaleFullTopBar", scaleFullTopBar.ToString());
                ini.IniWriteValue("style", "scaleFullMotors", scaleFullMotors.ToString());
                ini.IniWriteValue("style", "scaleFullOSD", scaleFullOSD.ToString());
                ini.IniWriteValue("style", "scaleFullLOG", scaleFullLOG.ToString());
                ini.IniWriteValue("style", "scaleFullHorizon", scaleFullHorizon.ToString());

                ini.IniWriteValue("style", "horizon", chkBoxShowHorizon.IsChecked.ToString());

                ini.IniWriteValue("threshold", "VoltageWarning", _dThresholdVoltageWarn.ToString());
                ini.IniWriteValue("threshold", "VoltageCritical", _dThresholdVoltageCrit.ToString());
                ini.IniWriteValue("threshold", "VoiceVoltageEnable", _bVoiceVoltPlay.ToString());
                ini.IniWriteValue("threshold", "VoiceSatFixEnable", _bVoiceSatFixPlay.ToString());
                ini.IniWriteValue("threshold", "VoiceMagFieldEnable", _bVoiceMagneticFieldPlay.ToString());
                ini.IniWriteValue("threshold", "VoiceDistanceWarnEnable", _bVoiceDistancePlay.ToString());
                ini.IniWriteValue("threshold", "VoiceRCLevelWarnEnable", _bVoiceRCLevelPlay.ToString());
                ini.IniWriteValue("threshold", "DistanceWarning", _dThresholdDistanceWarn.ToString());
                ini.IniWriteValue("threshold", "MaxDistance", _dThresholdDistanceMax.ToString());
                ini.IniWriteValue("threshold", "RCThreshold", _iThresholdRC.ToString());
                ini.IniWriteValue("threshold", "MagFieldThreshold", _iThresholdMagField.ToString());
            }
            catch (Exception e)
            {

                MessageBox.Show("Error writing ini-file!" + Environment.NewLine + "Please make sure that the programm is in a location where it is allowed to write" + Environment.NewLine + e.Message, "Write ini-file", MessageBoxButton.OK, MessageBoxImage.Error);
            }
        }

        #region WP
        void _readWPLFile()
        {
            Microsoft.Win32.OpenFileDialog fd = new Microsoft.Win32.OpenFileDialog();
            fd.Filter = "Waypointlists | *.wpl";
            fd.Multiselect = false;
            if (fd.ShowDialog().Value)
            {
                string file = fd.SafeFileName;
                IniFile ini = new IniFile(fd.SafeFileName);
                ini.path = fd.FileName;

                try
                {
                    string sVal = ini.IniReadValue("General", "FileVersion");
                    if (sVal == "")
                        MessageBox.Show("The file has no version declared - can't go on...", "", MessageBoxButton.OK, MessageBoxImage.Information);
                    else
                    {
                        if (Convert.ToInt16(sVal) < 3)
                            MessageBox.Show("The file version is not supported - can't go on...", "", MessageBoxButton.OK, MessageBoxImage.Information);
                        else
                        {
                            sVal = ini.IniReadValue("General", "NumberOfWaypoints");
                            if (sVal == "")
                                MessageBox.Show("The file has no number of waypoints declared - can't go on...", "", MessageBoxButton.OK, MessageBoxImage.Information);
                            else
                            {
                                int wpnum = Convert.ToInt16(sVal);
                                string wp;
                                int i;
                                NumberFormatInfo nfi = new NumberFormatInfo();
                                nfi.NumberDecimalSeparator = ".";
                                dtWaypoints.Rows.Clear();
                                for(int k = 0; k < MainMap.Markers.Count;)
                                {
                                    GMapMarker p = MainMap.Markers[k];
                                    if (p.Shape.GetType() == typeof(CustomMarkerWP))
                                        MainMap.Markers.Remove(p);
                                    else
                                        k++;
                                }
                                for (int k = 1; k <= wpnum; k++)
                                {
                                    DataRow dr = dtWaypoints.NewRow();
                                    dr.ItemArray = new object[16];
                                    object[] o = new object[16];
                                    i = 0;
                                    wp = "Point" + k.ToString();
                                    o[i] = k;
                                    i++;
                                    sVal = ini.IniReadValue(wp, "Type");
                                    if (sVal != "")
                                        o[i] = Convert.ToInt16(sVal) - 1;
                                    i++;
                                    sVal = ini.IniReadValue(wp, "Prefix");
                                    if (sVal != "")
                                        o[i] = sVal == "0" ? "P" + k.ToString() : sVal + k.ToString();
                                    i++;
                                    sVal = ini.IniReadValue(wp, "Latitude");
                                    if (sVal != "")
                                        o[i] = Convert.ToDouble(sVal, nfi);
                                    i++;
                                    sVal = ini.IniReadValue(wp, "Longitude");
                                    if (sVal != "")
                                        o[i] = Convert.ToDouble(sVal, nfi);
                                    i++;
                                    sVal = ini.IniReadValue(wp, "Altitude");
                                    if (sVal != "")
                                        o[i] = Convert.ToDouble(sVal, nfi);
                                    i++;
                                    sVal = ini.IniReadValue(wp, "Heading");
                                    if (sVal != "")
                                        o[i] = Convert.ToInt16(sVal);
                                    i++;
                                    sVal = ini.IniReadValue(wp, "Speed");
                                    if (sVal != "")
                                        o[i] = Convert.ToInt16(sVal);
                                    i++;
                                    sVal = ini.IniReadValue(wp, "ClimbRate");
                                    if (sVal != "")
                                        o[i] = Convert.ToInt16(sVal);
                                    i++;
                                    sVal = ini.IniReadValue(wp, "Radius");
                                    if (sVal != "")
                                        o[i] = Convert.ToInt16(sVal);
                                    i++;
                                    sVal = ini.IniReadValue(wp, "DelayTime");
                                    if (sVal != "")
                                        o[i] = Convert.ToInt16(sVal);
                                    i++;
                                    sVal = ini.IniReadValue(wp, "AutoTrigger");
                                    if (sVal != "")
                                        o[i] = Convert.ToInt16(sVal); ;
                                    i++;
                                    sVal = ini.IniReadValue(wp, "CAM-Nick");
                                    if (sVal != "")
                                        o[i] = Convert.ToInt16(sVal);
                                    i++;
                                    o[i] = 0;
                                    i++;
                                    sVal = ini.IniReadValue(wp, "WP_Event_Channel_Value");
                                    if (sVal != "")
                                        o[i] = Convert.ToInt16(sVal);
                                    i++;
                                    o[i] = "New";

                                    dr.ItemArray = o;
                                    dtWaypoints.Rows.Add(dr);
                                    GMapMarker wpMarker = new GMapMarker(new PointLatLng((double)o[3], (double)o[4]));
                                    wpMarker.Shape = new CustomMarkerWP(this, wpMarker, (string)dr[2], (int)o[1]);
                                    _setMarkerColor(wpMarker, (int)o[1]);
                                    MainMap.Markers.Add(wpMarker);

                                    Dispatcher.Invoke(() => lblWPIndex.Content = k.ToString());
                                    Dispatcher.Invoke(() => lblWPCount.Content = k.ToString());
                                    Dispatcher.Invoke(() => dgvWP.Items.Refresh());
                                    Thread.Sleep(10);
                                }
                            }
                        }
                    }

                }
                catch (Exception e)
                {

                    MessageBox.Show("Error parsing wpl-file!" + Environment.NewLine + e.Message, "Read wpl-file", MessageBoxButton.OK, MessageBoxImage.Error);
                }

            }
        }
        void _setMarkerColor(GMapMarker wpMarker,int iType)
        {
            Dispatcher.Invoke(() =>
            {
                switch (iType)
                {
                    case 0:
                        if (comboBoxWPColor.SelectionBoxItem != null)
                        {
                            string s = comboBoxWPColor.SelectionBoxItem.ToString();
                            ((CustomMarkerWP)(wpMarker.Shape)).setColor(s);
                        }
                        else
                            ((CustomMarkerWP)(wpMarker.Shape)).setColor("red");
                        break;
                    case 1:
                        if (comboBoxPOIColor.SelectionBoxItem != null)
                        {
                            string s = comboBoxPOIColor.SelectionBoxItem.ToString();
                            ((CustomMarkerWP)(wpMarker.Shape)).setColor(s);
                        }
                        else
                            ((CustomMarkerWP)(wpMarker.Shape)).setColor("red");
                        break;
                    case 2:
                        if (comboBoxFSColor.SelectionBoxItem != null)
                        {
                            string s = comboBoxFSColor.SelectionBoxItem.ToString();
                            ((CustomMarkerWP)(wpMarker.Shape)).setColor(s);
                        }
                        else
                            ((CustomMarkerWP)(wpMarker.Shape)).setColor("red");
                        break;
                    default:
                        ((CustomMarkerWP)(wpMarker.Shape)).setColor("red");
                        break;
                }
            });

        }
        private void comboBoxWPColor_DropDownClosed(object sender, EventArgs e)
        {
            Dispatcher.Invoke(() =>
            {
                if (comboBoxWPColor.SelectionBoxItem != null)
                {
                    for (int k = 0; k < MainMap.Markers.Count;k++)
                    {
                        GMapMarker p = MainMap.Markers[k];
                        if (p.Shape.GetType() == typeof(CustomMarkerWP))
                        {
                            if (((CustomMarkerWP)p.Shape).WPType == 0)
                            {
                                string s = comboBoxWPColor.SelectionBoxItem.ToString();
                                ((CustomMarkerWP)(p.Shape)).setColor(s);
                            }
                        }
                    }
                }
            });
        }
        private void comboBoxPOIColor_DropDownClosed(object sender, EventArgs e)
        {
            Dispatcher.Invoke(() =>
            {
                if (comboBoxPOIColor.SelectionBoxItem != null)
                {
                    for (int k = 0; k < MainMap.Markers.Count; k++)
                    {
                        GMapMarker p = MainMap.Markers[k];
                        if (p.Shape.GetType() == typeof(CustomMarkerWP))
                        {
                            if (((CustomMarkerWP)p.Shape).WPType == 1)
                            {
                                string s = comboBoxPOIColor.SelectionBoxItem.ToString();
                                ((CustomMarkerWP)(p.Shape)).setColor(s);
                            }
                        }
                    }
                }
            });

        }
        private void comboBoxFSColor_DropDownClosed(object sender, EventArgs e)
        {
            Dispatcher.Invoke(() =>
            {
                if (comboBoxFSColor.SelectionBoxItem != null)
                {
                    for (int k = 0; k < MainMap.Markers.Count; k++)
                    {
                        GMapMarker p = MainMap.Markers[k];
                        if (p.Shape.GetType() == typeof(CustomMarkerWP))
                        {
                            if (((CustomMarkerWP)p.Shape).WPType == 2)
                            {
                                string s = comboBoxFSColor.SelectionBoxItem.ToString();
                                ((CustomMarkerWP)(p.Shape)).setColor(s);
                            }
                        }
                    }
                }
            });
        }

        private void comboBoxCopterColor_DropDownClosed(object sender, EventArgs e)
        {
            Dispatcher.Invoke(() => {
                if (comboBoxCopterColor.SelectionBoxItem != null)
                {
                    string s = comboBoxCopterColor.SelectionBoxItem.ToString();
                    ((CustomMarkerCopter)(copter.Shape)).setColor(s);
                }
                else
                    ((CustomMarkerCopter)(copter.Shape)).setColor("red");
            });
        }

        private void btnLoadWPLFile_Click(object sender, RoutedEventArgs e)
        {
            _readWPLFile();
        }
        #endregion WP

        #endregion functions
    }
     /// <summary>
    /// formats the wp datatable values for display in datagrid - this is bound in the datagrid as a converter
    /// </summary>
    public class waypointsConverter : IValueConverter
    {
        public object Convert(object value, Type targetType, object parameter, CultureInfo culture)
        {
            if (value != null)
            {
                switch ((string)parameter)
                {
                    case "Latitude":
                        return value.ToString() + " °";
                    case "Longitude":
                        return value.ToString() + " °";
                    case "Radius":
                        return value.ToString() + " m";
                    case "Altitude":
                        return value.ToString() + " m";
                    case "ClimbRate":
                        return value.ToString() == "255" ? "Auto" : (System.Convert.ToDouble(value) / 10).ToString("0.0 m/s");
                    case "DelayTime":
                        return value.ToString() + " s";
                    case "Heading":
                        return Waypoints.Heading(System.Convert.ToInt32(value));
                    case "Speed":
                        return Waypoints.WPSpeed(System.Convert.ToInt16(value));
                    case "CamAngle":
                        return Waypoints.CAMAngle(System.Convert.ToInt16(value));
                    case "Type":
                        return ((Waypoints.pointType)(System.Convert.ToInt16(value))).ToString();
                    case "AutoTrigger":
                        return value.ToString() == "0" ? "- - -" : value.ToString() + " m";
                    case "Status":
                        return Waypoints.WPSpeed(System.Convert.ToInt16(value));
                }

                return value.ToString();
            }
            else return value;
        }

        public object ConvertBack(object value, Type targetType, object parameter, CultureInfo culture)
        {
            throw new NotImplementedException();
        }
    }

    public class IniFile
    {
        public string path;

        [DllImport("kernel32")]
        private static extern long WritePrivateProfileString(string section,
          string key, string val, string filePath);

        [DllImport("kernel32.dll", CharSet = CharSet.Auto)]
        static extern uint GetPrivateProfileSectionNames(IntPtr lpszReturnBuffer,
               uint nSize, string lpFileName);

        [DllImport("kernel32")]
        private static extern int GetPrivateProfileString(string section,
          string key, string def, StringBuilder retVal,
          int size, string filePath);

        public IniFile(string INIPath)
        {
            path = INIPath;
        }

        public void IniWriteValue(string Section, string Key, string Value)
        {
            WritePrivateProfileString(Section, Key, Value, this.path);
        }

        public string IniReadValue(string Section, string Key)
        {
            StringBuilder temp = new StringBuilder(255);
            int i = GetPrivateProfileString(Section, Key, "", temp, 255, this.path);
            return temp.ToString();
        }
        //Ini_sections auslesen in String-Array
        public string[] IniSectionNames()
        {

            //  uint MAX_BUFFER = 32767;
            uint MAX_BUFFER = 8388608;
            IntPtr pReturnedString = Marshal.AllocCoTaskMem((int)MAX_BUFFER);
            uint bytesReturned = GetPrivateProfileSectionNames(pReturnedString, MAX_BUFFER, this.path);
            if (bytesReturned == 0)
            {
                Marshal.FreeCoTaskMem(pReturnedString);
                return null;
            }
            string local = Marshal.PtrToStringAuto(pReturnedString, (int)bytesReturned).ToString();
            Marshal.FreeCoTaskMem(pReturnedString);
            //use of Substring below removes terminating null for split
            return local.Substring(0, local.Length - 1).Split('\0');


        }
    }

    /// <summary>
    /// Selected Win AI Function Calls
    /// </summary>
    public class WinApi
    {
        [DllImport("user32.dll", EntryPoint = "GetSystemMetrics")]
        public static extern int GetSystemMetrics(int which);
        [DllImport("user32.dll")]
        public static extern void
                SetWindowPos(IntPtr hwnd, IntPtr hwndInsertAfter,
                             int X, int Y, int width, int height, uint flags);

        private const int SM_CXSCREEN = 0;
        private const int SM_CYSCREEN = 1;
        private static IntPtr HWND_TOP = IntPtr.Zero;
        private const int SWP_SHOWWINDOW = 64; // 0x0040

        public static int ScreenX
        {
            get { return GetSystemMetrics(SM_CXSCREEN); }
        }

        public static int ScreenY
        {
            get { return GetSystemMetrics(SM_CYSCREEN); }
        }

        public static void SetWinFullScreen(IntPtr hwnd)
        {
            SetWindowPos(hwnd, HWND_TOP, -8, -7, ScreenX+15, ScreenY+14, SWP_SHOWWINDOW);
        }
    }
    /// <summary>
    /// Class used to preserve / restore state of the window
    /// </summary>
    public class WinState
    {
        private WindowState winState;
        private WindowStyle brdStyle;
        private bool topMost;
        private Rect restore;
        private bool IsMaximized = false;

        public bool isMaximized
        {
            get { return IsMaximized; }
        }
        public void Maximize(Window targetForm)
        {
            if (!IsMaximized)
            {
                IsMaximized = true;
                Save(targetForm);
                targetForm.WindowState = WindowState.Maximized;
                targetForm.WindowStyle = WindowStyle.None;
                targetForm.Topmost = true;
                WinApi.SetWinFullScreen(new WindowInteropHelper(targetForm).Handle);
            }
        }

        public void Save(Window targetForm)
        {
            winState = targetForm.WindowState;
            brdStyle = targetForm.WindowStyle;
            topMost = targetForm.Topmost;
            restore = targetForm.RestoreBounds;
        }
        public void Restore(Window targetForm)
        {
            targetForm.WindowState = winState;
            targetForm.WindowStyle = brdStyle;
            targetForm.Topmost = topMost;

            targetForm.Left = restore.Left;
            targetForm.Top = restore.Top;
            targetForm.Height = restore.Height;
            targetForm.Width = restore.Width;
            IsMaximized = false;
        }
    }

}