Subversion Repositories NaviCtrl

Compare Revisions

Ignore whitespace Rev 71 → Rev 72

/tags/V0.14b/uart1.c
0,0 → 1,772
/*#######################################################################################*/
/* !!! THIS IS NOT FREE SOFTWARE !!! */
/*#######################################################################################*/
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Copyright (c) 2008 Ingo Busker, Holger Buss
// + Nur für den privaten Gebrauch
// + FOR NON COMMERCIAL USE ONLY
// + www.MikroKopter.com
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Es gilt für das gesamte Projekt (Hardware, Software, Binärfiles, Sourcecode und Dokumentation),
// + dass eine Nutzung (auch auszugsweise) nur für den privaten (nicht-kommerziellen) Gebrauch zulässig ist.
// + Sollten direkte oder indirekte kommerzielle Absichten verfolgt werden, ist mit uns (info@mikrokopter.de) Kontakt
// + bzgl. der Nutzungsbedingungen aufzunehmen.
// + Eine kommerzielle Nutzung ist z.B.Verkauf von MikroKoptern, Bestückung und Verkauf von Platinen oder Bausätzen,
// + Verkauf von Luftbildaufnahmen, usw.
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Werden Teile des Quellcodes (mit oder ohne Modifikation) weiterverwendet oder veröffentlicht,
// + unterliegen sie auch diesen Nutzungsbedingungen und diese Nutzungsbedingungen incl. Copyright müssen dann beiliegen
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Sollte die Software (auch auszugesweise) oder sonstige Informationen des MikroKopter-Projekts
// + auf anderen Webseiten oder sonstigen Medien veröffentlicht werden, muss unsere Webseite "http://www.mikrokopter.de"
// + eindeutig als Ursprung verlinkt werden
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Keine Gewähr auf Fehlerfreiheit, Vollständigkeit oder Funktion
// + Benutzung auf eigene Gefahr
// + Wir übernehmen keinerlei Haftung für direkte oder indirekte Personen- oder Sachschäden
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Die PORTIERUNG der Software (oder Teile davon) auf andere Systeme (ausser der Hardware von www.mikrokopter.de) ist nur
// + mit unserer Zustimmung zulässig
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Die Funktion printf_P() unterliegt ihrer eigenen Lizenz und ist hiervon nicht betroffen
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Redistributions of source code (with or without modifications) must retain the above copyright notice,
// + this list of conditions and the following disclaimer.
// + * Neither the name of the copyright holders nor the names of contributors may be used to endorse or promote products derived
// + from this software without specific prior written permission.
// + * The use of this project (hardware, software, binary files, sources and documentation) is only permitted
// + for non-commercial use (directly or indirectly)
// + Commercial use (for excample: selling of MikroKopters, selling of PCBs, assembly, ...) is only permitted
// + with our written permission
// + * If sources or documentations are redistributet on other webpages, out webpage (http://www.MikroKopter.de) must be
// + clearly linked as origin
// + * PORTING this software (or part of it) to systems (other than hardware from www.mikrokopter.de) is NOT allowed
//
// + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// + ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
// + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// + POSSIBILITY OF SUCH DAMAGE.
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
#include <stdio.h>
#include <stdarg.h>
#include <string.h>
 
#include "91x_lib.h"
#include "ramfunc.h"
#include "menu.h"
#include "printf_P.h"
#include "GPS.h"
#include "i2c.h"
#include "uart0.h"
#include "uart1.h"
#include "uart2.h"
#include "timer.h"
#include "usb.h"
#include "main.h"
#include "waypoints.h"
#include "GPS.h"
 
// slave addresses
#define FC_ADDRESS 1
#define NC_ADDRESS 2
#define MK3MAG_ADDRESS 3
 
#define FALSE 0
#define TRUE 1
 
u8 Request_SendFollowMe = FALSE;
u8 Request_VerInfo = FALSE;
u8 Request_ExternalControl = FALSE;
u8 Request_Display = FALSE;
u8 Request_Display1 = FALSE;
u8 Request_DebugData = FALSE;
u8 Request_DebugLabel = 255;
u8 Request_ChannelOnly = FALSE;
u8 Request_NaviData = FALSE;
u8 Request_ErrorMessage = FALSE;
u8 Request_NewWaypoint = FALSE;
u8 Request_Data3D = FALSE;
 
u8 DisplayLine = 0;
 
UART_TypeDef *DebugUART = UART1;
 
volatile u8 txd_buffer[TXD_BUFFER_LEN];
volatile u8 rxd_buffer_locked = FALSE;
volatile u8 rxd_buffer[RXD_BUFFER_LEN];
volatile u8 txd_complete = TRUE;
volatile u8 ReceivedBytes = 0;
volatile u8 CntCrcError = 0;
volatile u8 *pRxData = NULL;
volatile u8 RxDataLen = 0;
 
u8 text[100];
 
u8 PcAccess = 100;
u8 MotorTest[4] = {0,0,0,0};
u8 ConfirmFrame = 0;
 
DebugOut_t DebugOut;
ExternControl_t ExternControl;
UART_VersionInfo_t UART_VersionInfo;
NaviData_t NaviData;
Waypoint_t FollowMe;
Data3D_t Data3D;
 
u32 DebugData_Timer;
u32 DebugData_Interval = 1000; // in ms
u32 NaviData_Timer;
u32 NaviData_Interval = 1000; // in ms
u32 Data3D_Timer = 0; // in ms
u32 Data3D_Interval = 0;
 
static u16 ptr_txd_buffer = 0;
 
const u8 ANALOG_LABEL[32][16] =
{
//1234567890123456
"AngleNick ", //0
"AngleRoll ",
"AccNick ",
"AccRoll ",
" ",
" ", //5
" ",
" ",
" ",
"GPS Data ",
"CompassHeading ", //10
"GyroHeading ",
"SPI Error ",
"SPI Okay ",
"I2C Error ",
"I2C Okay ", //15
" ",// "FC_Kalman_K ",
"ACC_Speed_N ",
"ACC_Speed_E ",
" ",// "GPS ACC ",
" ",// "MAXDrift ", //20
"N_Speed ",
"E_Speed ",
" ",// "KalmDist_N ",
" ",// "KalmDist_E ",
" ",//25
" ",
"Distance N ",
"Distance E ",
"GPS_Nick ",
"GPS_Roll ", //30
"Used_Sats "
};
 
 
/********************************************************/
/* Initialization the UART1 */
/********************************************************/
void UART1_Init (void)
{
GPIO_InitTypeDef GPIO_InitStructure;
UART_InitTypeDef UART_InitStructure;
 
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_IPConnected = GPIO_IPConnected_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 = 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;
 
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 as an IRQ with priority 4 (0 is highest)
VIC_Config(UART1_ITLine, VIC_IRQ, 4);
// enable the uart 1 IRQ
VIC_ITCmd(UART1_ITLine, ENABLE);
// initialize the debug timer
DebugData_Timer = SetDelay(DebugData_Interval);
NaviData_Timer = SetDelay(NaviData_Interval)+500;
// unlock rxd_buffer
rxd_buffer_locked = FALSE;
pRxData = NULL;
RxDataLen = 0;
// no bytes to send
txd_complete = TRUE;
// 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.ProtoMinor = VERSION_SERIAL_MINOR;
 
SerialPutString("\r\nUART1 init...ok");
}
 
 
/****************************************************************/
/* USART1 receiver ISR */
/****************************************************************/
void UART1_IRQHandler(void)
{
static u16 crc;
static u8 ptr_rxd_buffer = 0;
static u8 crc1, crc2;
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)
{
// wait for space in the tx buffer of the DebugUART
while(UART_GetFlagStatus(DebugUART, UART_FLAG_TxFIFOFull) == 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)
{
DebugUART = UART1;
UART0_Connect_to_MKGPS();
}
abortState = 0;
break;
}
 
if (DebugUART != UART1) UART_SendData(DebugUART, c);
}
}
else // DebugUART == UART1 (normal operation)
{
while ((UART_GetFlagStatus(UART1, UART_FLAG_RxFIFOEmpty) != SET) && (!rxd_buffer_locked))
{ // some byes in the fifo and rxd buffer not locked
// get byte from fifo
c = UART_ReceiveData(UART1);
if((ptr_rxd_buffer == 0) && (c == '#')) // if rxd buffer is empty and syncronisation character is received
{
rxd_buffer[ptr_rxd_buffer++] = c; // copy 1st byte to buffer
crc = c; // init crc
}
#if 0
else if (ptr_rxd_buffer == 1) // handle address
{
rxd_buffer[ptr_rxd_buffer++] = c; // copy byte to rxd buffer
crc += c; // update crc
}
#endif
else if (ptr_rxd_buffer < RXD_BUFFER_LEN) // rxd buffer not full
{
if (c != '\r') // no termination character received
{
rxd_buffer[ptr_rxd_buffer++] = c; // copy byte to rxd buffer
crc += c; // update crc
}
else // termination character received
{
// the last 2 bytes are no subject for checksum calculation
// they are the checksum itself
crc -= rxd_buffer[ptr_rxd_buffer-2];
crc -= rxd_buffer[ptr_rxd_buffer-1];
// calculate checksum from transmitted data
crc %= 4096;
crc1 = '=' + crc / 64;
crc2 = '=' + crc % 64;
// compare checksum to transmitted checksum bytes
if((crc1 == rxd_buffer[ptr_rxd_buffer-2]) && (crc2 == rxd_buffer[ptr_rxd_buffer-1]))
{ // checksum valid
rxd_buffer_locked = TRUE; // lock the rxd buffer
ReceivedBytes = ptr_rxd_buffer + 1; // store number of received bytes
rxd_buffer[ptr_rxd_buffer] = '\r'; // set termination character
// if 2nd byte is an 'R' start bootloader
if(rxd_buffer[2] == 'R')
{
PowerOff();
VIC_DeInit();
Execute_Bootloader(); // Reset-Commando - Bootloader starten
}
} // eof checksum valid
else
{ // checksum invalid
rxd_buffer_locked = FALSE; // unlock rxd buffer
} // eof checksum invalid
ptr_rxd_buffer = 0; // reset rxd buffer pointer
} // eof termination character received
} // rxd buffer not full
else // rxd buffer overrun
{
ptr_rxd_buffer = 0; // reset rxd buffer pointer
rxd_buffer_locked = FALSE; // unlock rxd buffer
} // eof rxd buffer overrrun
} // some byes in the fifo and rxd buffer not locked
} // eof DebugUart = UART1
}
}
 
/**************************************************************/
/* Transmit tx buffer via debug uart */
/**************************************************************/
void UART1_Transmit(void)
{
u8 tmp_tx;
// if something has to be send and the txd fifo is not full
if((!txd_complete) && (UART_GetFlagStatus(UART1, UART_FLAG_TxFIFOFull) == RESET))
{
tmp_tx = txd_buffer[ptr_txd_buffer]; // read byte from txd buffer
// if terminating character or end of txd buffer reached
if((tmp_tx == '\r') || (ptr_txd_buffer == TXD_BUFFER_LEN))
{
ptr_txd_buffer = 0; // reset txd buffer pointer
txd_complete = TRUE;// set complete flag
}
UART_SendData(UART1, tmp_tx); // put character to txd fifo
// set pointer to next byte
ptr_txd_buffer++;
}
}
 
/**************************************************************/
/* Add CRC and initiate transmission via debug uart */
/**************************************************************/
void AddCRC(u16 datalen)
{
u16 tmpCRC = 0, i;
for(i = 0; i < datalen; i++)
{
tmpCRC += txd_buffer[i];
}
tmpCRC %= 4096;
txd_buffer[i++] = '=' + tmpCRC / 64;
txd_buffer[i++] = '=' + tmpCRC % 64;
txd_buffer[i++] = '\r';
 
ptr_txd_buffer = 0;
txd_complete = FALSE;
UART_SendData(UART1, txd_buffer[ptr_txd_buffer++]); // send first byte, to be continued in the txd irq
}
 
 
 
/**************************************************************/
/* Code output data */
/**************************************************************/
void SendOutData(u8 cmd, u8 Address, u8 numofbuffers , ...) //u8 *data, u8 len, ....
{
va_list ap;
 
u16 pt = 0;
u8 a,b,c;
u8 ptr = 0;
 
u8* pdata = NULL;
int len = 0;
 
txd_buffer[pt++] = '#'; // Start character
txd_buffer[pt++] = 'a' + Address; // Address (a=0; b=1,...)
txd_buffer[pt++] = cmd; // Command
 
va_start(ap, numofbuffers);
if(numofbuffers)
{
pdata = va_arg(ap, u8*);
len = va_arg(ap, int);
ptr = 0;
numofbuffers--;
}
while(len)
{
if(len)
{
a = pdata[ptr++];
len--;
if((!len) && numofbuffers) // try to jump to next buffer
{
pdata = va_arg(ap, u8*);
len = va_arg(ap, int);
ptr = 0;
numofbuffers--;
}
}
else a = 0;
if(len)
{
b = pdata[ptr++];
len--;
if((!len) && numofbuffers) // try to jump to next buffer
{
pdata = va_arg(ap, u8*);
len = va_arg(ap, int);
ptr = 0;
numofbuffers--;
}
}
else b = 0;
if(len)
{
c = pdata[ptr++];
len--;
if((!len) && numofbuffers) // try to jump to next buffer
{
pdata = va_arg(ap, u8*);
len = va_arg(ap, int);
ptr = 0;
numofbuffers--;
}
}
else c = 0;
txd_buffer[pt++] = '=' + (a >> 2);
txd_buffer[pt++] = '=' + (((a & 0x03) << 4) | ((b & 0xf0) >> 4));
txd_buffer[pt++] = '=' + (((b & 0x0f) << 2) | ((c & 0xc0) >> 6));
txd_buffer[pt++] = '=' + ( c & 0x3f);
}
va_end(ap);
AddCRC(pt); // add checksum after data block and initates the transmission
}
 
 
/**************************************************************/
/* Decode data */
/**************************************************************/
void Decode64(void)
{
u8 a,b,c,d;
u8 x,y,z;
u8 ptrIn = 3; // start with first data byte in rx buffer
u8 ptrOut = 3;
u8 len = ReceivedBytes - 6; // must be a multiple of 4 (3 bytes at begin and 3 bytes at end are no payload )
while(len)
{
a = rxd_buffer[ptrIn++] - '=';
b = rxd_buffer[ptrIn++] - '=';
c = rxd_buffer[ptrIn++] - '=';
d = rxd_buffer[ptrIn++] - '=';
//if(ptrIn > ReceivedBytes - 3) break;
 
x = (a << 2) | (b >> 4);
y = ((b & 0x0f) << 4) | (c >> 2);
z = ((c & 0x03) << 6) | d;
 
if(len--) rxd_buffer[ptrOut++] = x; else break;
if(len--) rxd_buffer[ptrOut++] = y; else break;
if(len--) rxd_buffer[ptrOut++] = z; else break;
}
pRxData = &rxd_buffer[3];
RxDataLen = ptrOut - 3;
}
 
/**************************************************************/
/* Process incomming data from debug uart */
/**************************************************************/
void UART1_ProcessRxData(void)
{
// if data in the rxd buffer are not locked immediately return
if((!rxd_buffer_locked) || (DebugUART != UART1) ) return;
Waypoint_t * pWaypoint = NULL;
 
 
 
PcAccess = 255;
Decode64(); // decode data block in rxd buffer
switch(rxd_buffer[1] - 'a') // check for Slave Address
{
case NC_ADDRESS: // own Slave Address
 
switch(rxd_buffer[2])
{
case 'e': // request for the text of the error status
Request_ErrorMessage = TRUE;
break;
 
case 's':// new target position
pWaypoint = (Waypoint_t*)&pRxData[0];
BeepTime = 300;
if(pWaypoint->Position.Status == NEWDATA)
{
WPList_Clear(); // empty WPList
WPList_Append(pWaypoint);
GPS_pWaypoint = WPList_Begin();
}
break;
 
case 'u': // redirect debug uart
switch(pRxData[0])
{
case UART_FLIGHTCTRL:
UART2_Init(); // initialize UART2 to FC pins
DebugUART = UART2;
break;
case UART_MK3MAG:
if(FC.MKFlags & MKFLAG_MOTOR_RUN) break; // not if the motors are running
UART0_Connect_to_MK3MAG(); // mux UART0 to MK3MAG pins
GPSData.Status = INVALID;
DebugUART = UART0;
break;
case UART_MKGPS:
if(FC.MKFlags & MKFLAG_MOTOR_RUN) break; // not if the motors are running
UART0_Connect_to_MKGPS(); // connect UART0 to MKGPS pins
GPSData.Status = INVALID;
DebugUART = UART0;
break;
}
break;
 
case 'w':// new PCPosition for GPSTargetList
pWaypoint = (Waypoint_t*)&pRxData[0];
if(pWaypoint->Position.Status == INVALID)
{ // clear WP List
WPList_Clear();
GPS_pWaypoint = WPList_Begin();
//SerialPutString("\r\nClear WP List\r\n");
}
else if (pWaypoint->Position.Status == NEWDATA)
{ // app current WP to the list
WPList_Append(pWaypoint);
BeepTime = 500;
//SerialPutString("\r\nAdd WP to List\r\n");
}
Request_NewWaypoint = 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(rxd_buffer[2]) // check CmdID
{
case 'a':// request for the labels of the analog debug outputs
Request_DebugLabel = pRxData[0];
if(Request_DebugLabel > 31) Request_DebugLabel = 31;
break;
 
case 'b': // submit extern control
memcpy(&ExternControl, (u8*)&pRxData[0], sizeof(ExternControl));
ConfirmFrame = ExternControl.Frame;
break;
 
case 'd': // request for debug data;
DebugData_Interval = (u32) pRxData[0] * 10;
if(DebugData_Interval > 0) Request_DebugData = TRUE;
break;
 
case 'c': // request for 3D data;
Data3D_Interval = (u32) pRxData[0] * 10;
if(Data3D_Interval > 0) Request_Data3D = TRUE;
break;
 
case 'g':// request for external control data
Request_ExternalControl = TRUE;
break;
 
case 'h':// reqest for display line
RemoteKeys |= pRxData[0];
if(RemoteKeys != 0) DisplayLine = 0;
Request_Display = TRUE;
break;
 
case 'l':// reqest for display columns
MenuItem = pRxData[0];
Request_Display1 = TRUE;
break;
 
case 'o': // request for navigation information
NaviData_Interval = (u32) pRxData[0] * 10;
if(NaviData_Interval > 0) Request_NaviData = TRUE;
break;
 
case 'v': // request for version info
Request_VerInfo = TRUE;
break;
default:
// unsupported command recieved
break;
}
break; // default:
}
// unlock the rxd buffer after processing
pRxData = NULL;
RxDataLen = 0;
rxd_buffer_locked = FALSE;
}
 
 
/*****************************************************/
/* Send a character */
/*****************************************************/
s16 uart_putchar (char c)
{
if (c == '\n') uart_putchar('\r');
// wait until txd fifo is not full
while (UART_GetFlagStatus(UART1, UART_FLAG_TxFIFOFull) != RESET);
// transmit byte
UART_SendData(UART1, c);
return (0);
}
 
/*****************************************************/
/* Send a string to the debug uart */
/*****************************************************/
void SerialPutString(u8 *s)
{
if(s == NULL) return;
while (*s != '\0' && DebugUART == UART1)
{
uart_putchar(*s);
s ++;
}
}
 
 
 
/**************************************************************/
/* Send the answers to incomming commands at the debug uart */
/**************************************************************/
void UART1_TransmitTxData(void)
{
if(!txd_complete || (DebugUART != UART1) ) return;
 
if(Request_DebugLabel != 0xFF)
{
SendOutData('A', NC_ADDRESS, 2, &Request_DebugLabel, sizeof(Request_DebugLabel), (u8 *) ANALOG_LABEL[Request_DebugLabel], 16);
Request_DebugLabel = 0xFF;
}
if(ConfirmFrame && txd_complete)
{
SendOutData('B', NC_ADDRESS, 1, &ConfirmFrame, sizeof(ConfirmFrame));
ConfirmFrame = 0;
}
if( (( (DebugData_Interval > 0) && CheckDelay(DebugData_Timer)) || Request_DebugData) && txd_complete)
{
SendOutData('D', NC_ADDRESS, 1,(u8 *)&DebugOut, sizeof(DebugOut));
DebugData_Timer = SetDelay(DebugData_Interval);
Request_DebugData = FALSE;
}
 
if((( (Data3D_Interval > 0) && CheckDelay(Data3D_Timer) ) || Request_Data3D) && txd_complete)
{
SendOutData('C', NC_ADDRESS, 1,(u8 *)&Data3D, sizeof(Data3D));
Data3D_Timer = SetDelay(Data3D_Interval);
Request_Data3D = FALSE;
}
 
if(Request_ExternalControl && txd_complete)
{
SendOutData('G', NC_ADDRESS, 1, (u8 *)&ExternControl, sizeof(ExternControl));
Request_ExternalControl = FALSE;
}
if(Request_Display && txd_complete)
{
LCD_PrintMenu();
SendOutData('H', NC_ADDRESS, 2, &DisplayLine, sizeof(DisplayLine), (u8*)&DisplayBuff[DisplayLine * 20], 20);
DisplayLine++;
if(DisplayLine >= 4) DisplayLine = 0;
Request_Display = FALSE;
}
if(Request_Display1 && txd_complete)
{
LCD_PrintMenu();
SendOutData('L', NC_ADDRESS, 3, (u8*)&MenuItem, sizeof(MenuItem), (u8*)&MaxMenuItem, sizeof(MaxMenuItem),(u8*)DisplayBuff, sizeof(DisplayBuff));
Request_Display1 = FALSE;
}
if(Request_VerInfo && txd_complete)
{
SendOutData('V', NC_ADDRESS,1, (u8 *)&UART_VersionInfo, sizeof(UART_VersionInfo));
Request_VerInfo = FALSE;
}
if(( (NaviData_Interval && CheckDelay(NaviData_Timer) ) || Request_NaviData) && txd_complete)
{
NaviData.Errorcode = ErrorCode;
SendOutData('O', NC_ADDRESS,1, (u8 *)&NaviData, sizeof(NaviData));
if (DebugUART == UART1) SendOutData0('O', NC_ADDRESS,1, (u8 *)&NaviData, sizeof(NaviData));
NaviData_Timer = SetDelay(NaviData_Interval);
Request_NaviData = FALSE;
}
if(Request_ErrorMessage && txd_complete)
{
SendOutData('E', NC_ADDRESS, 1, (u8 *)&ErrorMSG, sizeof(ErrorMSG));
Request_ErrorMessage = FALSE;
}
if(Request_SendFollowMe && txd_complete && (GPSData.NumOfSats >= 4)) // sending for "Follow me"
{
GPS_CopyPosition(&(GPSData.Position),&(FollowMe.Position));
FollowMe.Position.Status = NEWDATA;
FollowMe.Heading = -1;
FollowMe.ToleranceRadius = 1;
FollowMe.HoldTime = 60;
FollowMe.Event_Flag = 0;
FollowMe.reserve[0] = 0; // reserve
FollowMe.reserve[1] = 0; // reserve
FollowMe.reserve[2] = 0; // reserve
FollowMe.reserve[3] = 0; // reserve
SendOutData('s', NC_ADDRESS, 1, (u8 *)&FollowMe, sizeof(FollowMe));
Request_SendFollowMe = FALSE;
}
 
if(Request_NewWaypoint && txd_complete)
{
u8 WPNumber = WPList_GetCount();
SendOutData('W', NC_ADDRESS, 1, &WPNumber, sizeof(WPNumber));
Request_NewWaypoint = FALSE;
}
 
}