Subversion Repositories NaviCtrl

Rev

Rev 626 | Blame | Compare with Previous | Last modification | View Log | RSS feed

/*#######################################################################################*/
/* !!! THIS IS NOT FREE SOFTWARE !!!                                                     */
/*#######################################################################################*/
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + www.MikroKopter.com
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Software Nutzungsbedingungen (english version: see below)
// + der Fa. HiSystems GmbH, Flachsmeerstrasse 2, 26802 Moormerland - nachfolgend Lizenzgeber genannt -
// + Der Lizenzgeber räumt dem Kunden ein nicht-ausschließliches, zeitlich und räumlich* unbeschränktes Recht ein, die im den
// + Mikrocontroller verwendete Firmware für die Hardware Flight-Ctrl, Navi-Ctrl, BL-Ctrl, MK3Mag & PC-Programm MikroKopter-Tool
// + - nachfolgend Software genannt - nur für private Zwecke zu nutzen.
// + Der Einsatz dieser Software ist nur auf oder mit Produkten des Lizenzgebers zulässig.
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Die vom Lizenzgeber gelieferte Software ist urheberrechtlich geschützt. Alle Rechte an der Software sowie an sonstigen im
// + Rahmen der Vertragsanbahnung und Vertragsdurchführung überlassenen Unterlagen stehen im Verhältnis der Vertragspartner ausschließlich dem Lizenzgeber zu.
// + Die in der Software enthaltenen Copyright-Vermerke, Markenzeichen, andere Rechtsvorbehalte, Seriennummern sowie
// + sonstige der Programmidentifikation dienenden Merkmale dürfen vom Kunden nicht verändert oder unkenntlich gemacht werden.
// + Der Kunde trifft angemessene Vorkehrungen für den sicheren Einsatz der Software. Er wird die Software gründlich auf deren
// + Verwendbarkeit zu dem von ihm beabsichtigten Zweck testen, bevor er diese operativ einsetzt.
// + Die Haftung des Lizenzgebers wird - soweit gesetzlich zulässig - begrenzt in Höhe des typischen und vorhersehbaren
// + Schadens. Die gesetzliche Haftung bei Personenschäden und nach dem Produkthaftungsgesetz bleibt unberührt. Dem Lizenzgeber steht jedoch der Einwand
// + des Mitverschuldens offen.
// + Der Kunde trifft angemessene Vorkehrungen für den Fall, dass die Software ganz oder teilweise nicht ordnungsgemäß arbeitet.
// + Er wird die Software gründlich auf deren Verwendbarkeit zu dem von ihm beabsichtigten Zweck testen, bevor er diese operativ einsetzt.
// + Der Kunde wird er seine Daten vor Einsatz der Software nach dem Stand der Technik sichern.
// + Der Kunde ist darüber unterrichtet, dass der Lizenzgeber seine Daten im zur Vertragsdurchführung erforderlichen Umfang
// + und auf Grundlage der Datenschutzvorschriften erhebt, speichert, verarbeitet und, sofern notwendig, an Dritte übermittelt.
// + *) Die räumliche Nutzung bezieht sich nur auf den Einsatzort, nicht auf die Reichweite der programmierten Software.
// + #### ENDE DER NUTZUNGSBEDINGUNGEN ####'
// +  Hinweis: Informationen über erweiterte Nutzungsrechte (wie z.B. Nutzung für nicht-private Zwecke) sind auf Anfrage per Email an info(@)hisystems.de verfügbar.
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Software LICENSING TERMS
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + of HiSystems GmbH, Flachsmeerstrasse 2, 26802 Moormerland, Germany - the Licensor -
// + The Licensor grants the customer a non-exclusive license to use the microcontroller firmware of the Flight-Ctrl, Navi-Ctrl, BL-Ctrl, and MK3Mag hardware
// + (the Software) exclusively for private purposes. The License is unrestricted with respect to time and territory*.
// + The Software may only be used with the Licensor's products.
// + The Software provided by the Licensor is protected by copyright. With respect to the relationship between the parties to this
// + agreement, all rights pertaining to the Software and other documents provided during the preparation and execution of this
// + agreement shall be the property of the Licensor.
// + The information contained in the Software copyright notices, trademarks, other legal reservations, serial numbers and other
// + features that can be used to identify the program may not be altered or defaced by the customer.
// + The customer shall be responsible for taking reasonable precautions
// + for the safe use of the Software. The customer shall test the Software thoroughly regarding its suitability for the
// + intended purpose before implementing it for actual operation. The Licensor's liability shall be limited to the extent of typical and
// + foreseeable damage to the extent permitted by law, notwithstanding statutory liability for bodily injury and product
// + liability. However, the Licensor shall be entitled to the defense of contributory negligence.
// + The customer will take adequate precautions in the case, that the software is not working properly. The customer will test
// + the software for his purpose before any operational usage. The customer will backup his data before using the software.
// + The customer understands that the Licensor collects, stores and processes, and, where required, forwards, customer data
// + to third parties to the extent necessary for executing the agreement, subject to applicable data protection and privacy regulations.
// + *) The territory aspect only refers to the place where the Software is used, not its programmed range.
// + #### END OF LICENSING TERMS ####
// + Note: For information on license extensions (e.g. commercial use), please contact us at info(@)hisystems.de.
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
#include <stdio.h>
#include <stdlib.h>
#include <stdarg.h>
#include <string.h>

#include "91x_lib.h"
#include "main.h"
#include "config.h"
#include "menu.h"
#include "GPS.h"
#include "i2c.h"
#include "uart0.h"
#include "uart1.h"
#include "uart2.h"
#include "timer1.h"
#include "timer2.h"
#include "analog.h"
#include "compass.h"
#include "waypoints.h"
#include "mkprotocol.h"
#include "params.h"
#include "fifo.h"
#include "debug.h"
#include "spi_slave.h"
#include "ftphelper.h"
#include "led.h"
#include "fat16.h"
#include "crc16.h"
#include "eeprom.h"

#define LIC_CMD_READ_LICENSE     1
#define LIC_CMD_WRITE_LICENSE    2
#define LIC_CMD_ERASE_LICENSE    3

#define FALSE   0
#define TRUE    1

#define ABO_TIMEOUT 8000 // disable abo after 8 seconds
u32 UART1_AboTimeOut = 0;

NaviData_Volatile_t NaviData_Volatile;
NaviData_WP_t NaviData_WP;
NaviData_Deviation_t NaviData_Deviation;
NaviData_Home_t NaviData_Home;
NaviData_Target_t NaviData_Target;
NaviData_Flags_t NaviData_Flags;
NaviData_Tiny_t NaviData_Tiny;
NaviData_Pos_t NaviData_Failsafe;
NaviData_Out_t NaviData_Out1Trigger;
NaviData_t NaviData;

u8 UART1_Request_VersionInfo    = FALSE;
u8 UART1_Request_ExternalControl= FALSE;
u8 UART1_Request_Display                = FALSE;
u8 UART1_Request_Display1               = FALSE;
u8 UART1_Request_DebugData              = FALSE;
u8 UART1_Request_DebugLabel             = 255;
u8 UART1_Request_NaviData               = FALSE;
u8 UART1_Request_ErrorMessage   = FALSE;
u8 UART1_Request_WritePoint             = 0xFF;
u8 UART1_Request_ReadPoint              = 0;
u8 UART1_Request_Data3D             = FALSE;
u8 UART1_Request_MotorData          = FALSE;
u8 UART1_Request_Echo               = FALSE;
u8 UART1_Request_ParameterId    = 0;
u8 UART1_Request_WPLStore               = FALSE;
u8 UART1_Request_Parameter              = FALSE;
u8 UART1_Request_SystemTime             = FALSE;
u8 UART1_DisplayKeys                    = 0;
u8 UART1_DisplayLine                    = 0;
u8 UART1_ConfirmFrame                   = 0;
u8 UART1_Request_FTP                    = FALSE;
u8 UART1_Request_LicenseString  = FALSE;
u8 LastTransmittedFCStatusFlags2 = 0;
u8 UART1_ExternalControlConfirmFrame = FALSE;
u8 Send_NMEA_RMC = FALSE;
u8 NaviData_Flags_SpeakHoTT_Processed = 0;

UART_TypeDef *DebugUART = UART1;

#ifdef FOLLOW_ME
#define FOLLOW_ME_INTERVAL 200 // 5 Hz
u32 UART1_FollowMe_Timer        = 0;
Point_t FollowMe;
#endif

// the primary rx fifo
#define UART1_RX_FIFO_LEN 1024
u8 UART1_rxfifobuffer[UART1_RX_FIFO_LEN];
fifo_t UART1_rx_fifo;

// the rx buffer
#define UART1_RX_BUFFER_LEN 1024
u8 UART1_rbuffer[UART1_RX_BUFFER_LEN];
Buffer_t UART1_rx_buffer;

// the tx buffer
#define UART1_TX_BUFFER_LEN 1024
u8 UART1_tbuffer[UART1_TX_BUFFER_LEN];
Buffer_t UART1_tx_buffer;

volatile u8 SerialLinkOkay = 0;

u8 text[200];
u8 *LicensePtr = UART1_tbuffer;

const u8 ANALOG_LABEL[32][16] =
{
   //1234567890123456
        "AngleNick       ", //0
        "AngleRoll       ",
        "AccNick         ",
        "AccRoll         ",
        "Altitude [0.1m] ",
        "FC-Flags        ", //5
        "NC-Flags        ",
        "Voltage  [0.1V] ",
        "Current  [0.1A] ",
        "GPS Data        ",
        "CompassHeading  ", //10
        "GyroHeading     ",
        "SPI Error       ", // achtung: muss auf 12 bleiben
        "SPI Okay        ",
        "I2C Error       ",
        "I2C Okay        ", //15
        "16              ",
        "17              ",
        "18              ",
        "19              ", // SD-Card-time
        "EarthMagnet [%] ", //20
        "Ground Speed    ", //  "Z_Speed         ",
        "N_Speed         ",
        "E_Speed         ",
        "Magnet X        ",
        "Magnet Y        ", //25
        "Magnet Z        ",
        "Distance N      ",
        "Distance E      ",
        "-GPS_Nick       ",
        "-GPS_Roll       ", //30
        "Used_Sats       "
};

typedef struct
{
        u8 Index;
        u8 Status;
} __attribute__((packed)) WPL_Answer_t;
WPL_Answer_t WPL_Answer;

DebugOut_t DebugOut;
ExternControl_t ExternControl;
UART_VersionInfo_t UART_VersionInfo;
NaviData_t NaviData;
Data3D_t Data3D;

u16 Echo; // 2 bytes recieved will be sent back as echo

u32 UART1_DebugData_Timer = 0;
u32 UART1_DebugData_Interval = 0;       // in ms
u32 UART1_NaviData_Timer = 0;
u32 UART1_NaviData_Interval = 0;        // in ms
u16 UART1_NaviData_MaxBytes = 0;                // newer protocol?
u32 UART1_Data3D_Timer = 0;
u32 UART1_Data3D_Interval = 0;          // in ms
u32 UART1_MotorData_Timer = 0;
u32 UART1_MotorData_Interval = 0;               // in ms
u32 UART1_Display_Timer = 0;
u32 UART1_Display_Interval = 0;         // in ms
u32 NMEA_Timer = 0;
u32 NMEA_Interval = 0;// in ms

u8 CalculateDebugLableCrc(void)
{
        u16 i;
        u8 crc = 0;
        for(i=0;i<sizeof(ANALOG_LABEL);i++) crc += ANALOG_LABEL[0][i];
        return(crc);
}

/********************************************************/
/*            Initialization the UART1                  */
/********************************************************/
void UART1_Init (void)
{
        GPIO_InitTypeDef GPIO_InitStructure;
        UART_InitTypeDef UART_InitStructure;

        // initialize txd buffer
        Buffer_Init(&UART1_tx_buffer, UART1_tbuffer, UART1_TX_BUFFER_LEN);

        // initialize rxd buffer
        Buffer_Init(&UART1_rx_buffer, UART1_rbuffer, UART1_RX_BUFFER_LEN);

        // initialize the rx fifo, block UART IRQ geting a byte from fifo
        fifo_init(&UART1_rx_fifo, UART1_rxfifobuffer, UART1_RX_FIFO_LEN, NO_ITLine, UART1_ITLine);

        SCU_APBPeriphClockConfig(__UART1, ENABLE);  // Enable the UART1 Clock
        SCU_APBPeriphClockConfig(__GPIO3, ENABLE);  // Enable the GPIO3 Clock

        /*Configure UART1_Rx pin GPIO3.2*/
        GPIO_StructInit(&GPIO_InitStructure);
        GPIO_InitStructure.GPIO_Direction =     GPIO_PinInput;
        GPIO_InitStructure.GPIO_Pin =                   GPIO_Pin_2;
        GPIO_InitStructure.GPIO_Type =                  GPIO_Type_PushPull;
        GPIO_InitStructure.GPIO_IPInputConnected =      GPIO_IPInputConnected_Enable;
        GPIO_InitStructure.GPIO_Alternate =     GPIO_InputAlt1; // UART1_RxD
        GPIO_Init(GPIO3, &GPIO_InitStructure);

        /*Configure UART1_Tx pin GPIO3.3*/
        GPIO_StructInit(&GPIO_InitStructure);
        GPIO_InitStructure.GPIO_Direction =     GPIO_PinOutput;
        GPIO_InitStructure.GPIO_Pin =                   GPIO_Pin_3;
        GPIO_InitStructure.GPIO_Type =                  GPIO_Type_PushPull;
        GPIO_InitStructure.GPIO_Alternate =     GPIO_OutputAlt2; // UART1_TX
        GPIO_Init(GPIO3, &GPIO_InitStructure);

        /* UART1 configured as follow:
        - Word Length = 8 Bits
        - One Stop Bit
        - No parity
        - BaudRate = 57600 baud
        - Hardware flow control Disabled
        - Receive and transmit enabled
        - Receive and transmit FIFOs are Disabled
        */

        UART_StructInit(&UART_InitStructure);
        UART_InitStructure.UART_WordLength =                    UART_WordLength_8D;
        UART_InitStructure.UART_StopBits =                              UART_StopBits_1;
        UART_InitStructure.UART_Parity =                                UART_Parity_No ;
        UART_InitStructure.UART_BaudRate =                              UART1_BAUD_RATE;
        UART_InitStructure. UART_HardwareFlowControl =  UART_HardwareFlowControl_None;
        UART_InitStructure.UART_Mode =                                  UART_Mode_Tx_Rx;
        UART_InitStructure.UART_FIFO =                                  UART_FIFO_Enable;
        UART_InitStructure.UART_TxFIFOLevel =                   UART_FIFOLevel_1_2;
        UART_InitStructure.UART_RxFIFOLevel =                   UART_FIFOLevel_1_2;      // FIFO size 16 bytes, FIFO level 8 bytes

        UART_DeInit(UART1); // reset uart 1     to default
        UART_Init(UART1, &UART_InitStructure); // initialize uart 1
        // enable uart 1 interrupts selective
        UART_ITConfig(UART1, UART_IT_Receive | UART_IT_ReceiveTimeOut, ENABLE);
        UART_Cmd(UART1, ENABLE); // enable uart 1
        // configure the uart 1 interupt line
        VIC_Config(UART1_ITLine, VIC_IRQ, PRIORITY_UART1);
        // enable the uart 1 IRQ
        VIC_ITCmd(UART1_ITLine, ENABLE);

        // initialize the debug timer
        UART1_DebugData_Timer = SetDelay(UART1_DebugData_Interval);
        UART1_NaviData_Timer = SetDelay(UART1_NaviData_Interval)+500;
        NMEA_Timer = SetDelay(14000);

        // Fill Version Info Structure
        UART_VersionInfo.SWMajor = VERSION_MAJOR;
        UART_VersionInfo.SWMinor = VERSION_MINOR;
        UART_VersionInfo.SWPatch = VERSION_PATCH;
        UART_VersionInfo.ProtoMajor = VERSION_SERIAL_MAJOR;
    UART_VersionInfo.HWMajor = Version_HW & 0x7F;
    UART_VersionInfo.BL_Firmware = 255;
        UART_VersionInfo.Flags = 0;
        UART_VersionInfo.LabelTextCRC = CalculateDebugLableCrc();
        NaviData.Version = NAVIDATA_VERSION;
        UART1_PutString("\r\n UART1 init...ok");
}


/****************************************************************/
/*               USART1 receiver ISR                            */
/****************************************************************/
void UART1_IRQHandler(void)
{
        static u8 abortState = 0;
        u8 c;

        if((UART_GetITStatus(UART1, UART_IT_Receive) != RESET) || (UART_GetITStatus(UART1, UART_IT_ReceiveTimeOut) != RESET) )
        {
                // clear the pending bits!
                UART_ClearITPendingBit(UART1, UART_IT_Receive);
                UART_ClearITPendingBit(UART1, UART_IT_ReceiveTimeOut);
                // if debug UART is not UART1
                if (DebugUART != UART1)
                {       // forward received data to the debug UART tx buffer
                        while(UART_GetFlagStatus(UART1, UART_FLAG_RxFIFOEmpty) != SET)
                        {
                                // move the byte from the rx buffer of UART1 to the tx buffer of DebugUART
                                c = UART_ReceiveData(UART1);

                                // check for abort condition (ESC ESC 0x55 0xAA 0x00)
                                switch (abortState)
                                {
                                        case 0:
                                                if (c == 27) abortState++;
                                                break;
                                        case 1:
                                                if (c == 27) abortState++;
                                                else abortState = 0;
                                        break;
                                        case 2:
                                                if (c == 0x55) abortState++;
                                                else abortState = 0;
                                                break;
                                        case 3:
                                                if (c == 0xAA) abortState++;
                                                else abortState = 0;
                                                break;
                                        case 4:
                                                if (c == 0x00)
                                                {
                                                        if(DebugUART == UART0)
                                                        {
                                                                UART0_Connect_to_MKGPS(UART0_BAUD_RATE);
                                                                TIMER2_Init(); // enbable servo outputs
                                                                fifo_purge(&UART1_rx_fifo); // flush the whole fifo init buffer
                                                        }
                                                        DebugUART = UART1;
                                                }
                                                abortState = 0;
                                                break;
                                } // end switch abort state
                                // if the Debug uart is not UART1, redirect input to the Debug UART
                                if (DebugUART != UART1)
                                {
                                        // wait for space in the tx buffer of the DebugUART
                                        while(UART_GetFlagStatus(DebugUART, UART_FLAG_TxFIFOFull) == SET) {};
                                        // move byte to the tx fifo of the debug uart
                                        UART_SendData(DebugUART, c);
                                }
                        }
                }
                else  // DebugUART == UART1 (normal operation)
                {
                        while(UART_GetFlagStatus(UART1, UART_FLAG_RxFIFOEmpty) != SET)
                        { // some byes in the hardware fifo
                            // get byte from hardware fifo
                        c = UART_ReceiveData(UART1);
                                // put into the software fifo
                                if(!fifo_put(&UART1_rx_fifo, c))
                                {       // fifo overflow
                                        //fifo_purge(&UART1_rx_fifo); // flush the whole buffer
                                }
                        } // EOF while some byes in the hardware fifo
                } // eof DebugUart = UART1
        }



        VIC1->VAR = 0xFF; // write any value to VIC1 Vector address register
}

/**************************************************************/
/* Process incomming data from debug uart                     */
/**************************************************************/
void UART1_ProcessRxData(void)
{
        // return on forwarding uart  or unlocked rx buffer
        u8 c;
        if(DebugUART != UART1) return;
        // if rx buffer is not locked
        if(UART1_rx_buffer.Locked == FALSE)
        {
                //collect data from primary rx fifo
                while(fifo_get(&UART1_rx_fifo, &c))
                {
                        // break if complete frame is collected
                        if(MKProtocol_CollectSerialFrame(&UART1_rx_buffer, c)) break;
                }
        }
        if(UART1_rx_buffer.Locked == FALSE) return;

        Point_t * pPoint = NULL;
        SerialMsg_t SerialMsg;

        // analyze header first
        MKProtocol_DecodeSerialFrameHeader(&UART1_rx_buffer, &SerialMsg);
        if( SerialMsg.Address == FC_ADDRESS )
        {
                switch(SerialMsg.CmdID)
                {
//                      case 'v': // version
                        case 'b': // extern control
                                          UART1_ExternalControlConfirmFrame = 1;
                        case 'y': // serial poti values
                                Buffer_Copy(&UART1_rx_buffer, &UART2_tx_buffer); //forward to FC
                                Buffer_Clear(&UART1_rx_buffer); // free rc buffer for next frame
                                return; //end process rx data
                        break;
                }
        }

        MKProtocol_DecodeSerialFrameData(&UART1_rx_buffer, &SerialMsg); // decode serial frame in rxd buffer
    if(SerialMsg.CmdID != 'z') SerialLinkOkay = 250;      // reset SerialTimeout, but not in case of the "ping"
        switch(SerialMsg.Address) // check for Slave Address
        {
                case NC_ADDRESS:  // own Slave Address
                switch(SerialMsg.CmdID)
                {
                        case 't': // request for the GPS time
                                UART1_Request_SystemTime  = TRUE;
                                break;

                        case 'm': // request for the license string
                                UART1_Request_LicenseString = SerialMsg.pData[0];
                                if((UART1_Request_LicenseString == LIC_CMD_WRITE_LICENSE) && (UART_VersionInfo.HWMajor >= 20))
                                 {
                                  memcpy(LicensePtr, &SerialMsg.pData[1],LICENSE_SIZE_TEXT); // copy ftp parameter
                                 }
                                break;
                        case 'f': // ftp command
                                UART1_Request_FTP = SerialMsg.pData[0];
                                //if (UART1_Request_FTP == FTP_CMD_SET_CWD || UART1_Request_FTP == FTP_CMD_GET_FILE)
                                memcpy(&FTP_data, &SerialMsg.pData[1], sizeof(FTP_data)); // copy ftp parameter
                        break;

                        case 'z': // connection checker
                                memcpy(&Echo, SerialMsg.pData, sizeof(Echo)); // copy echo pattern
                                UART1_Request_Echo = TRUE;
                                break;

                        case 'e': // request for the text of the error status
                                UART1_Request_ErrorMessage = TRUE;
                                break;

                        case 's'://  new target position
                                pPoint = (Point_t*)SerialMsg.pData;
                                if(pPoint->Position.Status == NEWDATA)
                                {
                                        //if(!(FC.StatusFlags & FC_STATUS_FLY)) PointList_Clear(); // flush the list
                                        //pPoint->Index = 1; // must be one after empty list
                                        PointList_SetAt(pPoint);
                                        if(FC.StatusFlags & FC_STATUS_FLY) PointList_WPActive(TRUE);
                                        GPS_pWaypoint = PointList_WPBegin(); // updates POI index
                                        BeepTime = 50;
                                }
                                else
                                if((pPoint->Position.Status == SIMULATION) && !(FC.RealStatusFlags & FC_STATUS_MOTOR_RUN))
                                {
                                if(pPoint->Event_Flag & SIMULATION_MOTOR_ON)
                                 {
                                  GPSPos_Copy(&(pPoint->Position), &SimulationPosition); // update hold position
                                  CompassDirectionAtMotorStart = SimulatedDirection*10;
                                 }
                                if(!(SimulationFlags & SIMULATION_MOTOR_ON) && (pPoint->Event_Flag & SIMULATION_MOTOR_ON))
                                 {
                                  SimulationFlags = pPoint->Event_Flag | SIMULATION_MOTOR_START; // dann steht da noch nicht "SIMULATION_MOTOR_ON" drin
                                  SpeakHoTT = SPEAK_STARTING;
                                 }
                                else
                                if(!(pPoint->Event_Flag & SIMULATION_MOTOR_ON) && (SimulationFlags & SIMULATION_MOTOR_ON))
                                 {
                                  SimulationFlags = pPoint->Event_Flag;
                                  SpeakHoTT = SPEAK_MK_OFF;
                                  BeepTime = 50;
                                 }
                                 else
                                  SimulationFlags = pPoint->Event_Flag | (SimulationFlags & SIMULATION_MOTOR_START);
                                }
                                break;
                        case 'u': // redirect debug uart
                                switch(SerialMsg.pData[0])
                                {
                                        case UART_FLIGHTCTRL:
                                                UART2_Init();                           // initialize UART2 to FC pins
                                                fifo_purge(&UART1_rx_fifo);
                                                TIMER2_Deinit();                        // reduce irq load
                                                DebugUART = UART2;
                                                break;
                                        case UART_MK3MAG:
                                                if(FC.StatusFlags & FC_STATUS_MOTOR_RUN) break; // not if the motors are running
                                                UART0_Connect_to_MK3MAG();      // mux UART0 to MK3MAG pins
                                                GPSData.Status = INVALID;
                                                fifo_purge(&UART1_rx_fifo);
                                                DebugUART = UART0;
                                                break;
                                        case UART_MKGPS:
                                                if(FC.StatusFlags & FC_STATUS_MOTOR_RUN) break; // not if the motors are running
                                                TIMER2_Deinit();                        // disable servo outputs to reduce irq load
                                                UART0_Connect_to_MKGPS(UART0_BAUD_RATE);        // connect UART0 to MKGPS pins
                                                GPSData.Status = INVALID;
                                                fifo_purge(&UART1_rx_fifo);
                                                DebugUART = UART0;
                                                break;
                                        default:
                                                break;
                                }
                                break;

                        case 'w'://  Set point in list at index
                                {
                                        pPoint = (Point_t*)SerialMsg.pData;

                                        if((pPoint->Position.Status == INVALID) && (pPoint->Index == 0))
                                        {
                                                PointList_Clear();
                                                GPS_pWaypoint = PointList_WPBegin();
                                                UART1_Request_WritePoint = 0; // return new point count
                                                NewWaypointsReceived = 1;
                                        }
                                        else
                                        {  // update WP in list at index
                                                if(pPoint->Index > MaxNumberOfWaypoints)
                                                {
                                                        UART1_Request_WritePoint = 254;
                                                        pPoint->Index = MaxNumberOfWaypoints;
                                                }
                                                else UART1_Request_WritePoint = PointList_SetAt(pPoint);
                                                if(FC.StatusFlags & FC_STATUS_FLY) PointList_WPActive(TRUE);
                                                SpeakWaypointRached = 1;        // Speak once when the last Point is reached
                                                if(UART1_Request_WritePoint == pPoint->Index)
                                                {
                                                        BeepTime = 500;
                                                    if(UART1_Request_WritePoint == 1) SpeakNextWaypoint = 1;            // Speak once as soon as the Points are active
                                                }
                                        }
                                }
                                break;

                        case 'x'://  Read Waypoint from List
                                UART1_Request_ReadPoint = SerialMsg.pData[0];
                                break;

                        case 'i':// Store WP List to file
                                memcpy((u8*)&WPL_Store, SerialMsg.pData, sizeof(WPL_Store_t));
                                WPL_Store.Name[11] = 0; // make sure the name string is terminated
                                WPL_Answer.Index = WPL_Store.Index; // echo Index in cmd answer
                                WPL_Answer.Status = PointList_WriteToFile(&WPL_Store);
                                UART1_Request_WPLStore = TRUE;
                                break;

                        case 'j':// Set/Get NC-Parameter
                                switch(SerialMsg.pData[0])
                                {
                                        case 0: // get
                                        break;

                                        case 1: // set
                                        {
                                                s16 value;
                                                value = SerialMsg.pData[2] + (s16)SerialMsg.pData[3] * 0x0100;
                                                NCParams_SetValue(SerialMsg.pData[1], &value);
                                        }
                                        break;
                                       
                                        default:
                                        break;
                                }
                                UART1_Request_ParameterId = SerialMsg.pData[1];
                                UART1_Request_Parameter = TRUE;
                                break;
                        default:
                                // unsupported command recieved
                                break;
                } // case NC_ADDRESS
                // "break;" is missing here to fall thru to the common commands

                default:  // and any other Slave Address

                switch(SerialMsg.CmdID) // check CmdID
                {
                        case 'a':// request for the labels of the analog debug outputs
                                UART1_Request_DebugLabel = SerialMsg.pData[0];
                                if(UART1_Request_DebugLabel > 31) UART1_Request_DebugLabel = 31;
                                break;
                        /*
                        case 'b': // submit extern control
                                memcpy(&ExternControl, SerialMsg.pData, sizeof(ExternControl));
                                UART1_ConfirmFrame = ExternControl.Frame;
                                break;
                        */

                        case 'd': // request for debug data;
                                UART1_DebugData_Interval = (u32) SerialMsg.pData[0] * 10;
                                if(UART1_DebugData_Interval > 0) UART1_Request_DebugData = TRUE;
                                UART1_AboTimeOut = SetDelay(ABO_TIMEOUT);
                                break;

                        case 'c': // request for 3D data;
                                UART1_Data3D_Interval = (u32) SerialMsg.pData[0] * 10;
                                if(UART1_Data3D_Interval > 0) UART1_Request_Data3D = TRUE;
                                UART1_AboTimeOut = SetDelay(ABO_TIMEOUT);
                                break;

                        case 'k': // request for Motor data;
                                UART1_MotorData_Interval = (u32) SerialMsg.pData[0] * 10;
                                if(UART1_MotorData_Interval > 0) UART1_Request_MotorData = TRUE;
                                UART1_AboTimeOut = SetDelay(ABO_TIMEOUT);
                                break;

                        case 'h':// reqest for display line
                                if((SerialMsg.pData[0]& 0x80) == 0x00)// old format
                                {
                                        UART1_DisplayLine = 2;
                                        UART1_Display_Interval = 0;
                                        UART1_Request_Display = TRUE;
                                }
                                else
                                {
                                        UART1_DisplayKeys |= ~SerialMsg.pData[0];
                                        UART1_Display_Interval = (u32) SerialMsg.pData[1] * 10;
                                        UART1_DisplayLine = 4;
                                        UART1_AboTimeOut = SetDelay(ABO_TIMEOUT);
                                        if(UART1_Display_Interval) UART1_Request_Display = TRUE;
                                }
                                break;

                        case 'l':// reqest for display columns
                                MenuItem = SerialMsg.pData[0];
                                UART1_Request_Display1 = TRUE;
                                break;

                        case 'o': // request for navigation information
                                UART1_NaviData_Interval = (u32) SerialMsg.pData[0] * 10;
                                if(SerialMsg.DataLen > 2) UART1_NaviData_MaxBytes = SerialMsg.pData[1] * 256 + SerialMsg.pData[2];
                                else UART1_NaviData_MaxBytes = 0;
                                if(UART1_NaviData_Interval > 0) UART1_Request_NaviData = TRUE;
                                UART1_AboTimeOut = SetDelay(ABO_TIMEOUT);
                                break;

                        case 'v': // request for version info
                                if(SerialMsg.DataLen > 0 && SerialMsg.pData[0] == 1) UART1_Request_VersionInfo = 1;
                                else UART1_Request_VersionInfo = 2;
                                break;
                        default:
                                // unsupported command recieved
                                break;
                }
                break; // default:
        }
        Buffer_Clear(&UART1_rx_buffer); // free rc buffer for next frame
}


/*****************************************************/
/*                   Send a character                */
/*****************************************************/
s16 UART1_Putchar(char c)
{
        u32 timeout = 10000;
        if (c == '\n') UART1_Putchar('\r');
        // wait until txd fifo is not full
        while(UART_GetFlagStatus(UART1, UART_FLAG_TxFIFOFull) != RESET) if(--timeout == 0) return(0);
        // transmit byte
        UART_SendData(UART1, c);
        #ifdef FOLLOW_ME
        if(TransmitAlsoToFC) UART_SendData(UART2, c);
        #endif
        return (0);
}

/*****************************************************/
/*       Send a string to the debug uart              */
/*****************************************************/
void UART1_PutString(u8 *s)
{
        if(s == NULL) return;
        while (*s != '\0' && DebugUART == UART1)
        {
                UART1_Putchar(*s);
                s ++;
        }
}


/**************************************************************/
/*         Transmit tx buffer via debug uart                  */
/**************************************************************/
void UART1_Transmit(void)
{
        u8 tmp_tx;
        if(DebugUART != UART1) return;
        // if something has to be send and the txd fifo is not full
        if(UART1_tx_buffer.Locked == TRUE)
        {
                // while there is some space in the tx fifo
                while(UART_GetFlagStatus(UART1, UART_FLAG_TxFIFOFull) != SET)
                {
                        tmp_tx = UART1_tx_buffer.pData[UART1_tx_buffer.Position++]; // read next byte from txd buffer
                        UART_SendData(UART1, tmp_tx); // put character to txd fifo
                        #ifdef FOLLOW_ME
                        if(TransmitAlsoToFC)
                        {
                                UART_SendData(UART2, tmp_tx); // put character to txd fifo
                        }
                        #endif
                        // if terminating character or end of txd buffer reached
                        if((tmp_tx == '\0') || (UART1_tx_buffer.Position == UART1_tx_buffer.DataBytes))
                        {
                                Buffer_Clear(&UART1_tx_buffer); // clear txd buffer
                                #ifdef FOLLOW_ME
                                TransmitAlsoToFC = 0;
                                #endif
                                break; // end while loop
                        }
                }
        }
}

//$GPGGA,HHMMSS.ss,BBBB.BBBB,b,LLLLL.LLLL,l,Q,NN,D.D,H.H,h,G.G,g,A.A,RRRR*PP
//$GPGGA,191410,4735.5634,N,00739.3538,E,1,04,4.4,351.5,M,48.0,M,,*45
//$GPGGA,092120.20,,,,,0,00,99.99,,,,,,*6C
//http://www.kowoma.de/gps/zusatzerklaerungen/NMEA.htm

void CreateNmeaGGA(void)
{
        u8 array[200], i = 0, crc = 0, x;
        s32 tmp1, tmp2;

        i += sprintf(array, "$GPGGA,");
        // +++++++++++++++++++++++++++++++++++++++++++
        if(SystemTime.Valid)
        {
                i += sprintf(&array[i], "%02d%02d%02d.%02d,", SystemTime.Hour, SystemTime.Min, SystemTime.Sec, SystemTime.mSec/10);
        }
        else
        {
                i += sprintf(&array[i], ",");
        }
        // +++++++++++++++++++++++++++++++++++++++++++
        if(GPSData.Flags & FLAG_GPSFIXOK)
        {
                tmp1 = abs(GPSData.Position.Latitude)/10000000L;
                i += sprintf(&array[i],"%02d",(s16)tmp1);

                tmp1 = abs(GPSData.Position.Latitude)%10000000L;
                tmp1 *= 6; // in Minuten
                tmp2 = tmp1 / 1000000L;
                i += sprintf(&array[i],"%02d", (u16)tmp2);
                tmp2 = tmp1 % 1000000L;
                tmp2 /= 100; // zwei Stellen zu viel
                i += sprintf(&array[i],".%04d,", (u16)tmp2);

                if(GPSData.Position.Latitude >= 0) i += sprintf(&array[i],"N,");
                else i += sprintf(&array[i],"S,");
                // +++++++++++++++++++++++++++++++++++++++++++

                tmp1 = abs(GPSData.Position.Longitude)/10000000L;
                i += sprintf(&array[i],"%03d", (u16)tmp1);

                tmp1 = abs(GPSData.Position.Longitude)%10000000L;
                tmp1 *= 6; // in Minuten
                tmp2 = tmp1 / 1000000L;
                i += sprintf(&array[i],"%02d", (u16)tmp2);
                tmp2 = tmp1 % 1000000L;
                tmp2 /= 100; // zwei Stellen zu viel
                i += sprintf(&array[i],".%04d,", (u16)tmp2);


                if(GPSData.Position.Longitude >= 0) i += sprintf(&array[i],"E,");
                else i += sprintf(&array[i],"W,");
                i += sprintf(&array[i],"%d,",GPSData.SatFix);
                i += sprintf(&array[i],"%d,",GPSData.NumOfSats);
                i += sprintf(&array[i],"%d.%d,",(s16)(GPSData.Position_Accuracy/100),abs(GPSData.Position_Accuracy%100));
                //  i += sprintf(&array[i],"%d.%d,M,",GPSData.Position.Altitude/1000,abs(GPSData.Position.Altitude%1000)/100);
                tmp1 = NaviData.Altimeter / 2; // in dm
                i += sprintf(&array[i],"%d.%d,M,",(s16)tmp1 / 10,abs((s16)tmp1 % 10));
                i += sprintf(&array[i],",,,*");
        }
        else
        {
                i += sprintf(&array[i], ",,,,%d,00,99.99,,,,,,*",GPSData.NumOfSats);
        }
        for(x = 1; x < i-1; x++)
        {
                crc ^= array[x];
        }
        i += sprintf(&array[i], "%02x%c%c",crc,0x0d,0x0a);
        AddSerialData(&UART1_tx_buffer,array,i);

        // +++++++++++++++++++++++++++++++++++++++++++
}

//$GPRMC,162614.123,A,5230.5900,N,01322.3900,E,10.0,90.0,131006,1.2,E,A*13
//$GPRMC,HHMMSS.sss,A,BBBB.BBBB,b,LLLLL.LLLL,l,GG.G,RR.R,DDMMYY,M.M,m,F*PP

void CreateNmeaRMC(void)
{
        u8 array[200], i = 0, crc = 0, x;
        s16 tmp_int;
        s32 tmp1, tmp2;
        // +++++++++++++++++++++++++++++++++++++++++++
        i += sprintf(array, "$GPRMC,");
        // +++++++++++++++++++++++++++++++++++++++++++
        if(SystemTime.Valid)
        {
                i += sprintf(&array[i], "%02d%02d%02d.%03d,", SystemTime.Hour, SystemTime.Min, SystemTime.Sec, SystemTime.mSec);
        }
        else
        {
                i += sprintf(&array[i], ",");
        }
        if(GPSData.Flags & FLAG_GPSFIXOK)
        {
                // +++++++++++++++++++++++++++++++++++++++++++
                tmp1 = abs(GPSData.Position.Latitude)/10000000L;
                i += sprintf(&array[i],"A,%02d", (s16)tmp1); // Status: A = Okay  V = Warnung

                tmp1 = abs(GPSData.Position.Latitude)%10000000L;
                tmp1 *= 6; // in Minuten
                tmp2 = tmp1 / 1000000L;
                i += sprintf(&array[i],"%02d", (s16)tmp2);
                tmp2 = tmp1 % 1000000L;
                tmp2 /= 100; // zwei Stellen zu viel
                i += sprintf(&array[i],".%04d,", (s16)tmp2);
                if(GPSData.Position.Latitude >= 0) i += sprintf(&array[i],"N,");
                else i += sprintf(&array[i],"S,");
                // +++++++++++++++++++++++++++++++++++++++++++
                tmp1 = abs(GPSData.Position.Longitude)/10000000L;
                i += sprintf(&array[i],"%03d", (s16)tmp1);

                tmp1 = abs(GPSData.Position.Longitude)%10000000L;
                tmp1 *= 6; // in Minuten
                tmp2 = tmp1 / 1000000L;
                i += sprintf(&array[i],"%02d", (s16)tmp2);
                tmp2 = tmp1 % 1000000L;
                tmp2 /= 100; // zwei Stellen zu viel
                i += sprintf(&array[i],".%04d,", (s16)tmp2);
                if(GPSData.Position.Longitude >= 0) i += sprintf(&array[i],"E,");
                else i += sprintf(&array[i],"W,");
                // +++++++++++++++++++++++++++++++++++++++++++
                tmp_int = GPSData.Speed_Ground; // in cm/sek
                tmp_int *= 90;
                tmp_int /= 463;
                i += sprintf(&array[i],"%02d.%d,",tmp_int/10,tmp_int%10); // in Knoten
                // +++++++++++++++++++++++++++++++++++++++++++
                i += sprintf(&array[i],"%03d.%d,",GyroCompassCorrected/10,GyroCompassCorrected%10);
                // +++++++++++++++++++++++++++++++++++++++++++
                if(SystemTime.Valid)
                {
                        i += sprintf(&array[i], "%02d%02d%02d,",SystemTime.Day,SystemTime.Month,SystemTime.Year);
                }
                else
                {
                        i += sprintf(&array[i], ",");
                }
                // +++++++++++++++++++++++++++++++++++++++++++
                i += sprintf(&array[i],"%d.%1d,", abs(GeoMagDec)/10,abs(GeoMagDec)%10);
                if(GeoMagDec < 0) i += sprintf(&array[i], "W,"); else i += sprintf(&array[i], "E,");
                // +++++++++++++++++++++++++++++++++++++++++++
                if(GPSData.Flags & FLAG_DIFFSOLN) i += sprintf(&array[i], "D*");
                else i += sprintf(&array[i], "A*");
        }
        else // kein Satfix
        {
                i += sprintf(&array[i], "V,,,,,,,,,,N*");
        }
        // +++++++++++++++++++++++++++++++++++++++++++
        //  CRC
        // +++++++++++++++++++++++++++++++++++++++++++
        for(x=1; x<i-1; x++)
        {
                crc ^= array[x];
        }
        i += sprintf(&array[i], "%02x%c%c",crc,0x0d,0x0a);
        // +++++++++++++++++++++++++++++++++++++++++++
        AddSerialData(&UART1_tx_buffer,array,i);
        // +++++++++++++++++++++++++++++++++++++++++++
/*



                GPSData.Flags =         (GPSData.Flags & 0xf0) | (UbxSol.Flags & 0x0f); // we take only the lower bits
                GPSData.NumOfSats =                     UbxSol.numSV;
                GPSData.SatFix =                                UbxSol.GPSfix;
                GPSData.Position_Accuracy =             UbxSol.PAcc;
                GPSData.Speed_Accuracy =                UbxSol.SAcc;
                SetGPSTime(&SystemTime); // update system time
                // NAV POSLLH
                GPSData.Position.Status =               INVALID;
                GPSData.Position.Longitude =    UbxPosLlh.LON;
                GPSData.Position.Latitude =     UbxPosLlh.LAT;
                GPSData.Position.Altitude =     UbxPosLlh.HMSL;
                GPSData.Position.Status =               NEWDATA;
                // NAV VELNED
                GPSData.Speed_East =                    UbxVelNed.VEL_E;
                GPSData.Speed_North =                   UbxVelNed.VEL_N;
                GPSData.Speed_Top       =                       -UbxVelNed.VEL_D;
                GPSData.Speed_Ground =                  UbxVelNed.GSpeed;
                GPSData.Heading =                               UbxVelNed.Heading;
                SystemTime.Year = 0;
                SystemTime.Month = 0;
                SystemTime.Day = 0;
                SystemTime.Hour = 0;
                SystemTime.Min = 0;
                SystemTime.Sec = 0;
                SystemTime.mSec = 0;
                SystemTime.Valid = 0;

                FromFlightCtrl.GyroHeading / 10;//NaviData.HomePositionDeviation.Bearing / 2;
                        if(GPSData.Position.Latitude < 0) ToFlightCtrl.Param.Byte[5]  = 1; // 1 = S
                        else ToFlightCtrl.Param.Byte[5]  = 0; // 1 = S
                        i1 = abs(GPSData.Position.Latitude)/10000000L;
                        i2 = abs(GPSData.Position.Latitude)%10000000L;



                        if(!(NCFlags & NC_FLAG_GPS_OK)) {i1 = 0; i2 = 0;}
                        i1 *= 100;
                        i1 += i2 / 100000;
                        i2  = i2 % 100000;
                        i2 /= 10;
                        ToFlightCtrl.Param.Byte[6]  = i1 % 256;
                        ToFlightCtrl.Param.Byte[7]  = i1 / 256;
                        ToFlightCtrl.Param.Byte[8]  = i2 % 256;
                        ToFlightCtrl.Param.Byte[9]  = i2 / 256;
                        break;
                case 1:
                        ToFlightCtrl.Param.Byte[11] = HOTT_GPS_PACKET_ID;
                        ToFlightCtrl.Param.Byte[0] = 11+3;      // index          +3, weil bei HoTT V4 3 Bytes eingeschoben wurden
                        ToFlightCtrl.Param.Byte[1] = 8-1;       // how many
                        //-----------------------------
                        if(GPSData.Position.Longitude < 0) ToFlightCtrl.Param.Byte[2]  = 1; // 1 = E
                        else ToFlightCtrl.Param.Byte[2]  = 0; // 1 = S
                        i1 = abs(GPSData.Position.Longitude)/10000000L;
                        i2 = abs(GPSData.Position.Longitude)%10000000L;

*/

}

u16 SendTriggerPos(void)
{
 u16 sent = 0;                                 
 NaviData_Out1Trigger.Index = 18;
 sent = MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'O', NC_ADDRESS, 1 , (u8 *)&NaviData_Out1Trigger, sizeof(NaviData_Out1Trigger)) + 1;
 Out1TriggerUpdateNewData = 0;
// BeepTime = 50; // beep
 return(sent);
}


u16 TransmitNavigationData(u16 MaxBytesPerSecond, u8 clear) // returns the minumum pause time in ms
{
static u8 state = 0, count_flags = 2, count_target = 3, count_home = 4, count_wp = 5 , count_tiny = 6, count_fs = 7;
static u16 CRC_Home = 0, CRC_Target = 0, CRC_Flags = 0, CRC_Wp = 0, CRC_Fs = 0;
u16 pause, sent = 0, crc_home, crc_target, crc_flags, crc_wp, crc_fs;

 if(clear)
 {
        state = 0;
        CRC_Home++;
        CRC_Target++;
        CRC_Flags++;
        CRC_Wp++;
        CRC_Fs++;
        NaviData_Flags_SpeakHoTT_Processed = 1; // allow update in SPI now
        return(1);
 }
while(!sent)
 {
//      if(Out1TriggerUpdateNewData && MaxBytesPerSecond > 200)   // (only if the data link can transmit more than 200Bytes per secons) -> it wouldn't fit into the data-flow if there are too few bytes available
//     sent += SendTriggerPos(); // dann passen die 35 Bytes noch ohne Verzögerung

                switch(state++)
                {
                 case 0:
                 case 6:
                 case 5:
// belegt 35 ASCII-Zeichen
                                NaviData_Flags.Index = 11;
                                NaviData_Flags.ActualLongitude = NaviData.CurrentPosition.Longitude;
                                NaviData_Flags.ActualLatitude = NaviData.CurrentPosition.Latitude;
                                NaviData_Flags.Altimeter = NaviData.Altimeter;
                                NaviData_Flags.GroundSpeed = NaviData.GroundSpeed / 10;
                                NaviData_Flags.OSDStatusFlags = (FC.StatusFlags & OSD_FLAG_MASK1) | (FC.StatusFlags2 & OSD_FLAG_MASK2);
                                NaviData_Flags.OSDStatusFlags2 = (FC.StatusFlags & ~OSD_FLAG_MASK1) | (FC.StatusFlags2 & ~OSD_FLAG_MASK2);
                                NaviData_Flags.NCFlags = NaviData.NCFlags;
                                NaviData_Flags.Errorcode = ErrorCode;
                                NaviData_Flags.ReserveFlags = 0;
                                //NaviData_Flags.SpeakHoTT = FC.FromFC_SpeakHoTT; -> in SPI.c
                                NaviData_Flags.VarioCharacter = FromFC_VarioCharacter;
                                NaviData_Flags.GPS_ModeCharacter = NC_GPS_ModeCharacter;
                                NaviData_Flags.BL_MinOfMaxPWM = BL_MinOfMaxPWM;
                                crc_flags = CRC16((unsigned char*)(&NaviData_Flags.OSDStatusFlags2), sizeof(NaviData_Flags) - START_PAYLOAD_DATA); // update crc for the license structure
                                if((crc_flags != CRC_Flags) || (--count_flags == 0))
                                {
                                 sent += MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'O', NC_ADDRESS, 1 , (u8 *)&NaviData_Flags, sizeof(NaviData_Flags)) + 1;
                                 CRC_Flags = crc_flags;
                                 count_flags = 11*2;
                                }
                                NaviData_Flags_SpeakHoTT_Processed = 1; // allow update in SPI now
                                break;
                 case 1:
                 case 7:
// belegt 43 ASCII-Zeichen
                                NaviData_Target.Index = 12;
                                NaviData_Target.ActualLongitude = NaviData.CurrentPosition.Longitude;
                                NaviData_Target.ActualLatitude = NaviData.CurrentPosition.Latitude;
                                NaviData_Target.Altimeter = NaviData.Altimeter;
                                NaviData_Target.GroundSpeed = NaviData.GroundSpeed / 10;
                                NaviData_Target.OSDStatusFlags = (FC.StatusFlags & OSD_FLAG_MASK1) | (FC.StatusFlags2 & OSD_FLAG_MASK2);
                                NaviData_Target.TargetLongitude = NaviData.TargetPosition.Longitude;
                                NaviData_Target.TargetLatitude = NaviData.TargetPosition.Latitude;
                                NaviData_Target.TargetAltitude = NaviData.TargetPosition.Altitude;
                                NaviData_Target.RC_Quality = NaviData.RC_Quality;
                                crc_target = CRC16((unsigned char*)(&NaviData_Target.TargetLongitude), sizeof(NaviData_Target) - START_PAYLOAD_DATA); // update crc for the license structure
                            if((crc_target != CRC_Target) || (--count_target == 0))
                                {
                                 sent += MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'O', NC_ADDRESS, 1 , (u8 *)&NaviData_Target, sizeof(NaviData_Target)) + 1;
                                 CRC_Target = crc_target;
                                 count_target = 10*2;
                                }
                                break;
                 case 2:
                 case 8:
// belegt 31 ASCII-Zeichen
                                NaviData_WP.Index = 15;
                                NaviData_WP.ActualLongitude = NaviData.CurrentPosition.Longitude;
                                NaviData_WP.ActualLatitude = NaviData.CurrentPosition.Latitude;
                                NaviData_WP.Altimeter = NaviData.Altimeter;
                                NaviData_WP.GroundSpeed = NaviData.GroundSpeed / 10;
                                NaviData_WP.OSDStatusFlags = (FC.StatusFlags & OSD_FLAG_MASK1) | (FC.StatusFlags2 & OSD_FLAG_MASK2);
                                NaviData_WP.WaypointIndex = NaviData.WaypointIndex;
                                NaviData_WP.WaypointNumber = NaviData.WaypointNumber;
                                NaviData_WP.TargetHoldTime = NaviData.TargetHoldTime;
                                // NaviData_WP.WP_Eventchannel = FC_WP_EventChannel; -> happends already in SPI.c
                                crc_wp = CRC16((unsigned char*)(&NaviData_WP.WaypointIndex), sizeof(NaviData_WP) - START_PAYLOAD_DATA); // update crc for the license structure
                                if((crc_wp != CRC_Wp) || (--count_wp == 0))
                                {
                         sent += MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'O', NC_ADDRESS, 1 , (u8 *)&NaviData_WP, sizeof(NaviData_WP)) + 1;
                                 CRC_Wp = crc_wp;
                                 count_wp = 12*2;
                                }
                                break;
                 case 3:
                 case 9:
// 35 ASCII-Zeichen
                                NaviData_Failsafe.Index = 17;
                                NaviData_Failsafe.ActualLongitude = NaviData.CurrentPosition.Longitude;
                                NaviData_Failsafe.ActualLatitude = NaviData.CurrentPosition.Latitude;
                                NaviData_Failsafe.Altimeter = NaviData.Altimeter;
                                NaviData_Failsafe.GroundSpeed = NaviData.GroundSpeed / 10;
                                NaviData_Failsafe.OSDStatusFlags = (FC.StatusFlags & OSD_FLAG_MASK1) | (FC.StatusFlags2 & OSD_FLAG_MASK2);
                                NaviData_Failsafe.Longitude = GPS_FailsafePosition.Longitude;
                                NaviData_Failsafe.Latitude = GPS_FailsafePosition.Latitude;
                                crc_fs = CRC16((unsigned char*)(&NaviData_Failsafe.Longitude), sizeof(NaviData_Pos_t) - START_PAYLOAD_DATA); // update crc for the license structure
                                if((crc_fs != CRC_Fs) || (--count_fs == 0))
                                {
                                 sent += MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'O', NC_ADDRESS, 1 , (u8 *)&NaviData_Failsafe, sizeof(NaviData_Failsafe)) + 1;
                                 CRC_Fs = crc_fs;
                                 count_fs = 20*2;
                                }
                                break;
                 case 4:
                 case 10:
// belegt 43 ASCII-Zeichen
                                NaviData_Home.Index = 13;
                                NaviData_Home.ActualLongitude = NaviData.CurrentPosition.Longitude;
                                NaviData_Home.ActualLatitude = NaviData.CurrentPosition.Latitude;
                                NaviData_Home.Altimeter = NaviData.Altimeter;
                                NaviData_Home.GroundSpeed = NaviData.GroundSpeed / 10;
                                NaviData_Home.OSDStatusFlags = (FC.StatusFlags & OSD_FLAG_MASK1) | (FC.StatusFlags2 & OSD_FLAG_MASK2);
                                NaviData_Home.HomeLongitude = NaviData.HomePosition.Longitude;
                                NaviData_Home.HomeLatitude = NaviData.HomePosition.Latitude;
                                NaviData_Home.HomeAltitude = NaviData.HomePosition.Altitude;
                                NaviData_Home.WP_OperatingRadius = MaxWP_Radius_in_m;
                                crc_home = CRC16((unsigned char*)(&NaviData_Home.HomeLongitude), sizeof(NaviData_Home_t) - START_PAYLOAD_DATA); // update crc for the license structure
                                if((crc_home != CRC_Home) || (--count_home == 0))
                                {
                                 sent += MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'O', NC_ADDRESS, 1 , (u8 *)&NaviData_Home, sizeof(NaviData_Home)) + 1;
                                 CRC_Home = crc_home;
                                 count_home = 25;
                                }
                                break;
                 case 11:
// belegt 39 ASCII-Zeichen
                                NaviData_Deviation.Index = 14;
                                NaviData_Deviation.ActualLongitude = NaviData.CurrentPosition.Longitude;
                                NaviData_Deviation.ActualLatitude = NaviData.CurrentPosition.Latitude;
                                NaviData_Deviation.Altimeter = NaviData.Altimeter;
                                NaviData_Deviation.GroundSpeed = NaviData.GroundSpeed / 10;
                                NaviData_Deviation.OSDStatusFlags = (FC.StatusFlags & OSD_FLAG_MASK1) | (FC.StatusFlags2 & OSD_FLAG_MASK2);
                                NaviData_Deviation.FlyingTime = NaviData.FlyingTime;
                                NaviData_Deviation.DistanceToHome = NaviData.HomePositionDeviation.Distance;
                                NaviData_Deviation.HeadingToHome = NaviData.HomePositionDeviation.Bearing/2;
                                NaviData_Deviation.DistanceToTarget = NaviData.TargetPositionDeviation.Distance;
                                NaviData_Deviation.HeadingToTarget = NaviData.TargetPositionDeviation.Bearing/2;
                                NaviData_Deviation.AngleNick = NaviData.AngleNick;
                                NaviData_Deviation.AngleRoll = NaviData.AngleRoll;
                                NaviData_Deviation.SatsInUse = NaviData.SatsInUse;
                            sent += MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'O', NC_ADDRESS, 1 , (u8 *)&NaviData_Deviation, sizeof(NaviData_Deviation)) + 1;
                                break;
                 case 12:
// belegt 43 ASCII-Zeichen
                                NaviData_Volatile.Index = 16;
                                NaviData_Volatile.ActualLongitude = NaviData.CurrentPosition.Longitude;
                                NaviData_Volatile.ActualLatitude = NaviData.CurrentPosition.Latitude;
                                NaviData_Volatile.Altimeter = NaviData.Altimeter;
                                NaviData_Volatile.GroundSpeed = NaviData.GroundSpeed / 10;
                                NaviData_Volatile.OSDStatusFlags = (FC.StatusFlags & OSD_FLAG_MASK1) | (FC.StatusFlags2 & OSD_FLAG_MASK2);
                                NaviData_Volatile.UBat = FC.BAT_Voltage;
                                NaviData_Volatile.Current = NaviData.Current;
                                NaviData_Volatile.UsedCapacity = NaviData.UsedCapacity;
                                NaviData_Volatile.Variometer = NaviData.Variometer;
                                NaviData_Volatile.Heading = NaviData.Heading / 2;
                                NaviData_Volatile.CompassHeading = NaviData.CompassHeading / 2;
                                NaviData_Volatile.Gas = NaviData.Gas;
                                NaviData_Volatile.SetpointAltitude = NaviData.SetpointAltitude;
                                sent += MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'O', NC_ADDRESS, 1 , (u8 *)&NaviData_Volatile, sizeof(NaviData_Volatile)) + 1;
                        break;
                 case 13:
// belegt 27 ASCII-Zeichen
                                NaviData_Tiny.Index = 10;
                                NaviData_Tiny.ActualLongitude = NaviData.CurrentPosition.Longitude;
                                NaviData_Tiny.ActualLatitude = NaviData.CurrentPosition.Latitude;
                                NaviData_Tiny.Altimeter = NaviData.Altimeter;
                                NaviData_Tiny.GroundSpeed = NaviData.GroundSpeed / 10;
                                NaviData_Tiny.OSDStatusFlags = (FC.StatusFlags & OSD_FLAG_MASK1) | (FC.StatusFlags2 & OSD_FLAG_MASK2);
                                if(--count_tiny == 0)
                                 {
                                        sent += MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'O', NC_ADDRESS, 1 , (u8 *)&NaviData_Tiny, sizeof(NaviData_Tiny)) + 1;
                                        count_tiny = 200; // just to make sure that it comes sometimes
                                 }
                        break;
                 default: state = 0;
                                break;
                }
 }
        pause = (sent * 1000) / MaxBytesPerSecond;

        UART1_Request_NaviData = FALSE;
        LastTransmittedFCStatusFlags2 = NaviData.FCStatusFlags2;
return(pause);
// Clear at timeout:
// NaviData_WP.WP_Eventchannel
}

/**************************************************************/
/* Send the answers to incomming commands at the debug uart   */
/**************************************************************/
void UART1_TransmitTxData(void)
{
static u8 motorindex1 = 255, motorindex2 = 0;
        if(DebugUART != UART1) return;

        if(CheckDelay(UART1_AboTimeOut))
        {
                UART1_DebugData_Interval = 0;
                UART1_NaviData_Interval = 0;
                UART1_NaviData_MaxBytes = 0;
                UART1_Data3D_Interval = 0;
                UART1_Display_Interval = 0;
                UART1_MotorData_Interval = 0;
                UART1_NaviData_Timer = SetDelay(500);
                UART1_AboTimeOut = SetDelay(100);
                TransmitNavigationData(0,1); // clear the CRC values
        }
/*
#define CHK_MIN_INTERVAL(a,b) {if(a && a < b) a = b;}
UART1_NaviData_Interval = 500;
CHK_MIN_INTERVAL(UART1_DebugData_Interval,500);
CHK_MIN_INTERVAL(UART1_NaviData_Interval,1000);
CHK_MIN_INTERVAL(UART1_Data3D_Interval,255);
CHK_MIN_INTERVAL(UART1_Display_Interval,1500);
CHK_MIN_INTERVAL(UART1_MotorData_Interval,750);
*/

        UART1_Transmit(); // output pending bytes in tx buffer
        if((UART1_tx_buffer.Locked == TRUE)) return;

        if(UART1_Request_Parameter && (UART1_tx_buffer.Locked == FALSE))
        {
                s16 ParamValue;
                NCParams_GetValue(UART1_Request_ParameterId, &ParamValue);
                MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'J', NC_ADDRESS, 2, &UART1_Request_ParameterId, sizeof(UART1_Request_ParameterId), &ParamValue, sizeof(ParamValue)); // answer the param request
                UART1_Request_Parameter = FALSE;
        }
        else if(UART1_Request_Echo && (UART1_tx_buffer.Locked == FALSE))
        {
                MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'Z', NC_ADDRESS, 1, &Echo, sizeof(Echo)); // answer the echo request
                Echo = 0; // reset echo value
                UART1_Request_Echo = FALSE;
        }
        else if(UART1_Request_FTP && (UART1_tx_buffer.Locked == FALSE))
        {
                u8 errorcode = FTP_ERROR_NONE;
        if(FC.StatusFlags & FC_STATUS_MOTOR_RUN) errorcode = FTP_ERROR_MOTOR_RUN;
                else if (!Partition.IsValid) errorcode = FTP_ERROR_NO_SDCARD;

                if (!errorcode) CheckFTPCommand(UART1_Request_FTP);
                else
                {
                        u8 cmd = FTP_CMD_ERROR;
                        MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'F', NC_ADDRESS, 2, &cmd, 1, &errorcode, 1);
                }

                UART1_Request_FTP = FALSE;
        }
        else if((UART1_Request_WritePoint!= 0xFF) && (UART1_tx_buffer.Locked == FALSE))
        {
                MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'W', NC_ADDRESS, 1, &UART1_Request_WritePoint, sizeof(UART1_Request_WritePoint));
                UART1_Request_WritePoint = 0xFF;
        }
        else if((UART1_Request_ReadPoint) && (UART1_tx_buffer.Locked == FALSE))
        {
                u8 PointCount = PointList_GetCount();
                if (UART1_Request_ReadPoint <= PointCount)
                {
                        MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'X', NC_ADDRESS, 3, &PointCount, 1, &UART1_Request_ReadPoint, 1, PointList_GetAt(UART1_Request_ReadPoint), sizeof(Point_t));
                }
                else
                {
                        MKProtocol_CreateSerialFrame(&UART1_tx_buffer,'X', NC_ADDRESS, 1, &PointCount, sizeof(PointCount));
                }
                UART1_Request_ReadPoint = 0;
        }
        else if((UART1_Request_DebugLabel != 0xFF) && (UART1_tx_buffer.Locked == FALSE))
        {
                MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'A', NC_ADDRESS, 2, &UART1_Request_DebugLabel, sizeof(UART1_Request_DebugLabel), (u8 *) ANALOG_LABEL[UART1_Request_DebugLabel], 16);
                UART1_Request_DebugLabel = 0xFF;
        }
        else if(UART1_ExternalControlConfirmFrame && (UART1_tx_buffer.Locked == FALSE))
        {
                MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'B', NC_ADDRESS, 1,(u8 *)&UART1_ExternalControlConfirmFrame, sizeof(UART1_ExternalControlConfirmFrame));
                UART1_ExternalControlConfirmFrame = 0;
        }
        else
        if((UART1_NaviData_Interval > 0) && Out1TriggerUpdateNewData && UART1_NaviData_MaxBytes > 200)    // (only if the data link can transmit more than 200Bytes per secons) -> it wouldn't fit into the data-flow if there are too few bytes available
         {
          //sent +=
          SendTriggerPos(); // dann passen die 35 Bytes noch ohne Verzögerung
         }
        else if(( ((UART1_NaviData_Interval > 0) && CheckDelay(UART1_NaviData_Timer) ) || UART1_Request_NaviData) && (UART1_tx_buffer.Locked == FALSE))
        {
          u16 time = 0;
//UART1_NaviData_MaxBytes = 250;
      if(UART1_NaviData_MaxBytes == 0) // Transmit the big NC Data frame
           {
                NaviData.Errorcode = ErrorCode;
                MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'O', NC_ADDRESS, 1 , (u8 *)&NaviData, sizeof(NaviData));
                LastTransmittedFCStatusFlags2 = NaviData.FCStatusFlags2;
                UART1_NaviData_Timer = SetDelay(UART1_NaviData_Interval);
           }
           else
           if(CheckDelay(UART1_NaviData_Timer))
           {
// Wert =  50 -> Sekunden laufen in 2 s-Abstand (im Wegpunkteflug mit aktivem Countdown in 3-4s)
// Wert = 100 -> Sekunden laufen in 1-2 s-Abstand (im Wegpunkteflug mit aktivem Countdown in 2s)
// Wert = 150 -> Sekunden laufen flüssig (im Wegpunkteflug mit aktivem Countdown und gleichzeitig Target verschieben manchmal in 2s)
// Wert = 200 -> Sekunden laufen flüssig
// Wert >= 250 -> optimal
//UART1_NaviData_MaxBytes = 45;
            time = TransmitNavigationData(UART1_NaviData_MaxBytes,0);
                if(UART1_NaviData_Interval > time) time = UART1_NaviData_Interval;
                UART1_NaviData_Timer = SetDelay(time);
           }
        UART1_Request_NaviData = FALSE;
        }
        else if( (( (UART1_DebugData_Interval > 0) && CheckDelay(UART1_DebugData_Timer)) || UART1_Request_DebugData) && (UART1_tx_buffer.Locked == FALSE))
        {
                MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'D', NC_ADDRESS, 1,(u8 *)&DebugOut, sizeof(DebugOut));
                UART1_DebugData_Timer = SetDelay(UART1_DebugData_Interval);
                UART1_Request_DebugData = FALSE;
        }
        else if((( (UART1_Data3D_Interval > 0) && CheckDelay(UART1_Data3D_Timer) ) || UART1_Request_Data3D) && (UART1_tx_buffer.Locked == FALSE))
        {
                Data3D.StickNick = FC.StickNick;
                Data3D.StickRoll = FC.StickRoll;
        Data3D.StickYaw = FC.StickYaw;
        Data3D.StickGas = FC.StickGas;
                Data3D.AngleNick = FromFlightCtrl.AngleNick;            // in 0.1 deg
                Data3D.AngleRoll = FromFlightCtrl.AngleRoll;            // in 0.1 deg
                Data3D.Heading   = FromFlightCtrl.GyroHeading;          // in 0.1 deg
                Data3D.Altimeter = FC.Altimeter;                                        // in 5cm -> 20 = 1m
                MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'C', NC_ADDRESS, 1,(u8 *)&Data3D, sizeof(Data3D));
                UART1_Data3D_Timer = SetDelay(UART1_Data3D_Interval);
                UART1_Request_Data3D = FALSE;
        }
        else if((((UART1_MotorData_Interval > 0) && CheckDelay(UART1_MotorData_Timer) ) || UART1_Request_MotorData) && (UART1_tx_buffer.Locked == FALSE))
        {
                do
                {
                 motorindex1++;
                 motorindex1%=12;
         if(!motorindex1) {motorindex2++;  motorindex2 %= 12;};
                 if(motorindex1 == motorindex2) break;
                }
                while((Motor[motorindex1].State & 0x80) != 0x80); // skip unused Motors

                MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'K', NC_ADDRESS, 2, &motorindex1, sizeof(motorindex1),(u8 *)&Motor[motorindex1], sizeof(Motor_t));
            UART1_MotorData_Timer = SetDelay(UART1_MotorData_Interval);
                UART1_Request_MotorData = FALSE;
        }
        else if(UART1_Request_WPLStore)
        {
                /*
                s8 txt[50];
                sprintf(txt, "\r\nWPL Overwride = %d, Type = %d, Index = %d, Status = %d\r\n",  WPL_Store.OverwriteFile,  WPL_Store.Type, WPL_Answer.Index, WPL_Answer.Status);
                UART1_PutString(txt);
                */

                MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'I', NC_ADDRESS, 1,(u8 *)&(WPL_Answer), sizeof(WPL_Answer_t));
                UART1_Request_WPLStore = FALSE;                
        }
        else if((((NMEA_Interval > 0) && CheckDelay(NMEA_Timer))) && (UART1_tx_buffer.Locked == FALSE))
        {
                CreateNmeaGGA();
                Send_NMEA_RMC = TRUE;   // das muss noch da hinter
                NMEA_Timer = SetDelay(NMEA_Interval);
        }
        else if(Send_NMEA_RMC == TRUE && (UART1_tx_buffer.Locked == FALSE))
        {
          CreateNmeaRMC();
          Send_NMEA_RMC = FALSE;
        }

        /*
        else if(UART1_ConfirmFrame && (UART1_tx_buffer.Locked == FALSE))
        {
                MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'B', NC_ADDRESS, 1, &UART1_ConfirmFrame, sizeof(UART1_ConfirmFrame));
                UART1_ConfirmFrame = 0;
        }
        */

        /*
        else if(UART1_Request_ExternalControl && (UART1_tx_buffer.Locked == FALSE))
        {
                MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'G', NC_ADDRESS, 1, (u8 *)&ExternControl, sizeof(ExternControl));
                UART1_Request_ExternalControl = FALSE;
        }
        */

        else if( (( (UART1_Display_Interval > 0) && CheckDelay(UART1_Display_Timer)) || UART1_Request_Display) && (UART1_tx_buffer.Locked == FALSE))
        {
                if(UART1_DisplayLine > 3)
                {
                        Menu_Update(UART1_DisplayKeys);
                        UART1_DisplayKeys = 0;
                        MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'H', NC_ADDRESS, 1, (u8*)DisplayBuff, sizeof(DisplayBuff));
                }
                else
                {
                        UART1_DisplayLine = 2;
                        sprintf(text,"!!! incompatible !!!");
                        MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'H', NC_ADDRESS, 2, &UART1_DisplayLine, sizeof(UART1_DisplayLine), (u8*)&text, 20);
                        if(UART1_DisplayLine++ > 3) UART1_DisplayLine = 0;
                }
                UART1_Display_Timer = SetDelay(UART1_Display_Interval);
                UART1_Request_Display = FALSE;
        }
        else if(UART1_Request_Display1 && (UART1_tx_buffer.Locked == FALSE))
        {
                Menu_Update(0);
                MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'L', NC_ADDRESS, 3, (u8*)&MenuItem, sizeof(MenuItem), (u8*)&MaxMenuItem, sizeof(MaxMenuItem),(u8*)DisplayBuff, sizeof(DisplayBuff));
                UART1_Request_Display1 = FALSE;
        }
        else if(UART1_Request_VersionInfo == 1 && (UART1_tx_buffer.Locked == FALSE)) // get FC-Versions
        {
                UART_VersionInfo_t version_tmp;
                version_tmp.SWMajor = FC_Version.Major;
                version_tmp.SWMinor = FC_Version.Minor;
                version_tmp.SWPatch = FC_Version.Patch;
                version_tmp.HWMajor = FC_Version.Hardware;
                version_tmp.HardwareError[0] = 0xff; // tells the KopterTool that it is the FC-version
                version_tmp.HardwareError[1] = 0xff; // tells the KopterTool that it is the FC-version
                version_tmp.ProtoMajor = UART_VersionInfo.ProtoMajor;
                version_tmp.BL_Firmware = UART_VersionInfo.BL_Firmware;
                version_tmp.Flags = 0;
                version_tmp.LabelTextCRC = 0;//UART_VersionInfo.DebugTextCRC;
                MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'V', NC_ADDRESS,1, (u8 *)&version_tmp, sizeof(version_tmp));
                UART1_Request_VersionInfo = FALSE;
        }
        else if(UART1_Request_VersionInfo == 2 && (UART1_tx_buffer.Locked == FALSE)) // get NC-Versions
        {
                MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'V', NC_ADDRESS,1, (u8 *)&UART_VersionInfo, sizeof(UART_VersionInfo));
                UART1_Request_VersionInfo = FALSE;
        }
        else if(UART1_Request_SystemTime && (UART1_tx_buffer.Locked == FALSE))
        {
                MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'T', NC_ADDRESS,1, (u8 *)&SystemTime, sizeof(SystemTime));
                UART1_Request_SystemTime = FALSE;
        }
        else if(UART1_Request_ErrorMessage && (UART1_tx_buffer.Locked == FALSE))
        {
                MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'E', NC_ADDRESS, 1, (u8 *)&ErrorMSG, sizeof(ErrorMSG));
                UART1_Request_ErrorMessage = FALSE;
        }
        else if(UART1_Request_LicenseString && (UART1_tx_buffer.Locked == FALSE))
        {
                u8 result = 1, cmd = 0;
                if(UART1_Request_LicenseString == LIC_CMD_READ_LICENSE)  
                {
                  result = LIC_CMD_READ_LICENSE;
                  MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'M', NC_ADDRESS, 2, &result, 1, LicensePtr, LICENSE_SIZE);
                }
                else
                if((UART1_Request_LicenseString == LIC_CMD_ERASE_LICENSE) && !(FC.StatusFlags & FC_STATUS_MOTOR_RUN) && (UART_VersionInfo.HWMajor >= 20))
                 {
                  result = LIC_CMD_ERASE_LICENSE;
                  DeleteLicenseInEEPROM();
                  CheckLicense(GET_LICENSE);
                  MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'M', NC_ADDRESS, 1, &result, 1);
                 }
                else
                if((UART1_Request_LicenseString == LIC_CMD_WRITE_LICENSE) && !(FC.StatusFlags & FC_STATUS_MOTOR_RUN) && (UART_VersionInfo.HWMajor >= 20))
                {
                  cmd = LIC_CMD_WRITE_LICENSE;
                  if(CheckLicense(CHECK_ONLY))  //new license is okay
                  {
                   WriteLicenseToEEPROM(EEPROM_LICENSE_DATA_KOMPATIBEL);
                   result = 1;
                  }
                  else //new license is NOT okay
                  {
                   ClearLicenseText();
                   result = 0;
                   CheckLicense(GET_LICENSE);  // fetch a license if available
                  }
                  MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'M', NC_ADDRESS, 2, &cmd, 1,&result, 1 );
                }
                UART1_Request_LicenseString = 0;
        }
#ifdef FOLLOW_ME
        else if(CheckDelay(UART1_FollowMe_Timer) && (UART1_tx_buffer.Locked == FALSE))
        {
                if((GPSData.Status != INVALID) && (GPSData.SatFix == SATFIX_3D) && (GPSData.Flags & FLAG_GPSFIXOK) && (GPSData.NumOfSats >= 4))
                {
                        TransmitAlsoToFC = 1;
                        // update FollowMe content
                        FollowMe.Position.Longitude     = GPSData.Position.Longitude;
                        FollowMe.Position.Latitude      = GPSData.Position.Latitude;
                        FollowMe.Position.Status = NEWDATA;
                        FollowMe.Position.Altitude = 1;
                        // 0  -> no Orientation
                        // 1-360 -> CompassCourse Setpoint
                        // -1 -> points to  WP1 -> itself
                FollowMe.Heading = -1;
                        FollowMe.ToleranceRadius = 1;
                        FollowMe.HoldTime = 60;
                        FollowMe.Event_Flag = 1;
                        FollowMe.Index = 1; // 0 = Delete List, 1 place at first entry in the list
                        FollowMe.Type = POINT_TYPE_WP;
                        FollowMe.WP_EventChannelValue = 100;  // set servo value
                        FollowMe.AltitudeRate = 0;                        // do not change height
                        FollowMe.Speed = 0;                             // rate to change the Position (0 = max)
                        FollowMe.CamAngle = 255;                // Camera servo angle in degree (255 -> POI-Automatic)
                        FollowMe.Name[0] = 'F';             // Name of that point (ASCII)
                        FollowMe.Name[1] = 'O';             // Name of that point (ASCII)
                        FollowMe.Name[2] = 'L';             // Name of that point (ASCII)
                        FollowMe.Name[3] = 'L';             // Name of that point (ASCII)
                        FollowMe.reserve[0] = 0;                // reserve
                        FollowMe.reserve[1] = 0;                // reserve
                        MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 's', NC_ADDRESS, 1, (u8 *)&FollowMe, sizeof(FollowMe));
                }
                UART1_FollowMe_Timer = SetDelay(FOLLOW_ME_INTERVAL); // set new update time
        }
#endif
#ifdef DEBUG                                                                                                                    // only include functions if DEBUG is defined
        else if(SendDebugOutput && (UART1_tx_buffer.Locked == FALSE))
        {
                MKProtocol_CreateSerialFrame(&UART1_tx_buffer,'0', NC_ADDRESS, 1, (u8 *) &tDebug, sizeof(tDebug));
                SendDebugOutput = 0;
        }
#endif
        UART1_Transmit(); // output pending bytes in tx buffer
}