Subversion Repositories MK3Mag

Compare Revisions

Ignore whitespace Rev 64 → Rev 65

/tags/V0.22c/uart.c
0,0 → 1,655
/*#######################################################################################
MK3Mag 3D-Magnet sensor
!!! THIS IS NOT FREE SOFTWARE !!!
#######################################################################################*/
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Copyright (c) 05.2008 Holger Buss
// + Thanks to Ilja Fähnrich (P_Latzhalter)
// + Nur für den privaten Gebrauch / NON-COMMERCIAL USE ONLY
// + www.MikroKopter.com
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Die Portierung oder Nutzung der Software (oder Teile davon) auf andere Systeme (ausser der Hardware von www.mikrokopter.de) ist nur
// + mit unserer Zustimmung zulässig
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + 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.
// + AUSNAHME: Ein bei www.mikrokopter.de erworbener vorbestückter MK3Mag darf als Baugruppe auch in kommerziellen Systemen verbaut werden
// + Im Zweifelsfall bitte anfragen bei: info@mikrokopter.de
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + 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 oder Nutzung 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.
// + * porting the sources to other systems or using the software on other systems (except hardware from www.mikrokopter.de) is not allowed
// + * 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 permittet
// + 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
// + Exception: A preassembled MK3Mag, purchased from www.mikrokopter.de may be used as a part of commercial systems
// + In case of doubt please contact: info@MikroKopter.de
// + * If sources or documentations are redistributet on other webpages, our webpage (http://www.MikroKopter.de) must be
// + clearly linked as origin
// + 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 <avr/io.h>
#include <avr/interrupt.h>
#include <avr/wdt.h>
#include <avr/pgmspace.h>
#include <stdarg.h>
#include <string.h>
#include "main.h"
#include "menu.h"
#include "uart.h"
#include "timer0.h"
#include "twislave.h"
 
// slave addresses
#define FC_ADDRESS 1
#define NC_ADDRESS 2
#define MK3MAG_ADDRESS 3
 
#define FALSE 0
#define TRUE 1
 
// keep buffers as small as possible
#define TXD_BUFFER_LEN 100
#define RXD_BUFFER_LEN 30
 
volatile uint8_t txd_buffer[TXD_BUFFER_LEN];
volatile uint8_t rxd_buffer_locked = FALSE;
volatile uint8_t rxd_buffer[RXD_BUFFER_LEN];
volatile uint8_t txd_complete = TRUE;
volatile uint8_t ReceivedBytes = 0;
volatile uint8_t *pRxData = 0;
volatile uint8_t RxDataLen = 0;
 
// send flags
#define RQST_VERSION_INFO 0x01
#define RQST_DEBUG_DATA 0x02
#define RQST_DEBUG_LABEL 0x04
#define RQST_COMPASS_HEADING 0x08
#define RQST_EXTERN_CTRL 0x10
#define RQST_DISPLAY_DATA 0x20
 
 
uint8_t RequestFlags = 0x00;
uint8_t RequestDebugLabel = 0;
uint8_t ConfirmFrame = 0;
 
uint8_t DisplayLine = 0;
 
uint16_t PC_Connected = 0;
uint16_t FC_Connected = 0;
 
 
DebugOut_t DebugOut;
ExternData_t ExternData;
ExternControl_t ExternControl;
UART_VersionInfo_t UART_VersionInfo;
 
uint16_t DebugData_Timer;
uint16_t DebugData_Interval = 500;
 
const prog_uint8_t ANALOG_LABEL[32][16] =
{
//1234567890123456
"Magnet X ", //0
"Magnet Y ",
"Magnet Z ",
"RawMagnet X ",
"RawMagnet Y ",
"RawMagnet Z ", //5
"Attitude Nick ",
"Attitude Roll ",
"Magnet X Offset ",
"Magnet X Range ",
"Magnet Y Offset ", //10
"Magnet Y Range ",
"Magnet Z Offset ",
"Magnet Z Range ",
"Calstate ",
"Heading ", //15
"User0 ",
"User1 ",
"Acc X ",
"Acc Y ",
"Acc Z ", //20
"RawAcc X ",
"RawAcc Y ",
"RawAcc Z ",
"Acc X Offset ",
"Acc Y Offset ", //25
"Acc Z Offset ",
"Heading X ",
"Heading Y ",
"Attitude Source ",
"I2C Error ", //30
"I2C Okay "
};
 
 
/****************************************************************/
/* Initialization of the USART0 */
/****************************************************************/
void USART0_Init (void)
{
uint8_t sreg = SREG;
uint16_t ubrr = (uint16_t) ((uint32_t) F_CPU/(8 * BAUD_RATE) - 1);
 
// disable all interrupts before configuration
cli();
 
// disable RX-Interrupt
UCSR0B &= ~(1 << RXCIE0);
// disable TX-Interrupt
UCSR0B &= ~(1 << TXCIE0);
 
// set direction of RXD0 and TXD0 pins
 
// set RXD0 (PD0) as an input pin tristate
DDRD &= ~(1 << DDD0);
PORTD &= ~(1 << PORTD0);
// set TXD0 (PD1) as an output pin
DDRD |= (1 << DDD1);
PORTD &= ~(1 << PORTD1);
 
 
// USART0 Baud Rate Register
// set clock divider
UBRR0H = (uint8_t)(ubrr >> 8);
UBRR0L = (uint8_t)ubrr;
 
// USART0 Control and Status Register A, B, C
 
// enable double speed operation
UCSR0A |= (1 << U2X0);
 
// set asynchronous mode
UCSR0C &= ~(1 << UMSEL01);
UCSR0C &= ~(1 << UMSEL00);
// no parity
UCSR0C &= ~(1 << UPM01);
UCSR0C &= ~(1 << UPM00);
// 1 stop bit
UCSR0C &= ~(1 << USBS0);
// 8-bit
UCSR0B &= ~(1 << UCSZ02);
UCSR0C |= (1 << UCSZ01);
UCSR0C |= (1 << UCSZ00);
 
// enable receiver and transmitter
UCSR0B |= (1 << RXEN0);
UCSR0B |= (1 << TXEN0);
 
// flush receive buffer
while ( UCSR0A & (1<<RXC0) ) UDR0;
 
// enable RX-Interrupt
UCSR0B |= (1 << RXCIE0);
// enable TX-Interrupt
UCSR0B |= (1 << TXCIE0);
 
// initialize the debug timer
DebugData_Timer = SetDelay(DebugData_Interval);
 
// unlock rxd_buffer
rxd_buffer_locked = FALSE;
pRxData = 0;
RxDataLen = 0;
 
// no bytes to send
txd_complete = TRUE;
 
 
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;
 
// send version info at startup
USART0_putchar ('\n');
USART0_putchar ('C');
USART0_putchar ('P');
USART0_putchar (':');
USART0_putchar ('V');
USART0_putchar ('0' + VERSION_MAJOR);
USART0_putchar ('.');
USART0_putchar ('0' + VERSION_MINOR/10);
USART0_putchar ('0' + VERSION_MINOR%10);
USART0_putchar ('a' + VERSION_PATCH);
USART0_putchar ('\n');
 
// restore global interrupt flags
SREG = sreg;
}
 
// ---------------------------------------------------------------------------------
void USART0_EnableTXD(void)
{
DDRD |= (1<<DDD1); // set TXD pin as output
PORTD &= ~(1 << PORTD1);
UCSR0B |= (1 << TXEN0); // enable TX in USART
//changing the interrupt flag yields to strange effects
//UCSR0B |= (1 << TXCIE0); // enable TX-Interrupt
}
 
// ---------------------------------------------------------------------------------
void USART0_DisableTXD(void)
{
while(!txd_complete){ };
//changing the interrupt flag yields to strange effects
//UCSR0B &= ~(1 << TXCIE0); // disable TX-Interrupt
UCSR0B &= ~(1 << TXEN0); // disable TX in USART
DDRD &= ~(1<<DDD1); // set TXD pin as input
PORTD &= ~(1 << PORTD1);
}
 
/****************************************************************/
/* USART0 transmitter ISR */
/****************************************************************/
ISR(USART_TX_vect)
{
static uint16_t ptr_txd_buffer = 0;
uint8_t tmp_tx;
if(!txd_complete) // transmission not completed
{
ptr_txd_buffer++; // die [0] wurde schon gesendet
tmp_tx = txd_buffer[ptr_txd_buffer];
// if terminating character or end of txd buffer was reached
if((tmp_tx == '\r') || (ptr_txd_buffer == TXD_BUFFER_LEN))
{
ptr_txd_buffer = 0; // reset txd pointer
txd_complete = TRUE; // stop transmission
}
UDR0 = tmp_tx; // send current byte will trigger this ISR again
}
// transmission completed
else ptr_txd_buffer = 0;
}
 
/****************************************************************/
/* USART0 receiver ISR */
/****************************************************************/
ISR(USART_RX_vect)
{
static uint16_t crc;
uint8_t crc1, crc2;
uint8_t c;
static uint8_t ptr_rxd_buffer = 0;
 
c = UDR0; // catch the received byte
 
if(rxd_buffer_locked) return; // if rxd buffer is locked immediately return
 
// the rxd buffer is unlocked
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) // collect incomming bytes
{
if(c != '\r') // no termination character
{
rxd_buffer[ptr_rxd_buffer++] = c; // copy byte to rxd buffer
crc += c; // update crc
}
else // termination character was 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[ptr_rxd_buffer] = '\r'; // set termination character
ReceivedBytes = ptr_rxd_buffer + 1;// store number of received bytes
rxd_buffer_locked = TRUE; // lock the rxd buffer
// if 2nd byte is an 'R' enable watchdog that will result in an reset
if(rxd_buffer[2] == 'R') {wdt_enable(WDTO_250MS);} // Reset-Commando
}
else
{ // checksum invalid
rxd_buffer_locked = FALSE; // unlock rxd buffer
}
ptr_rxd_buffer = 0; // reset rxd buffer pointer
}
}
else // rxd buffer overrun
{
ptr_rxd_buffer = 0; // reset rxd buffer
rxd_buffer_locked = FALSE; // unlock rxd buffer
}
}
 
 
// --------------------------------------------------------------------------
void AddCRC(uint16_t datalen)
{
uint16_t 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';
txd_complete = FALSE;
UDR0 = txd_buffer[0]; // initiates the transmission (continued in the TXD ISR)
}
 
 
 
// --------------------------------------------------------------------------
void SendOutData(uint8_t cmd, uint8_t address, uint8_t numofbuffers, ...) // uint8_t *pdata, uint8_t len, ...
{
va_list ap;
uint16_t pt = 0;
uint8_t a,b,c;
uint8_t ptr = 0;
 
uint8_t *pdata = 0;
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, uint8_t*);
len = va_arg(ap, int);
ptr = 0;
numofbuffers--;
}
 
while(len)
{
if(len)
{
a = pdata[ptr++];
len--;
if((!len) && numofbuffers)
{
pdata = va_arg(ap, uint8_t*);
len = va_arg(ap, int);
ptr = 0;
numofbuffers--;
}
}
else a = 0;
if(len)
{
b = pdata[ptr++];
len--;
if((!len) && numofbuffers)
{
pdata = va_arg(ap, uint8_t*);
len = va_arg(ap, int);
ptr = 0;
numofbuffers--;
}
}
else b = 0;
if(len)
{
c = pdata[ptr++];
len--;
if((!len) && numofbuffers)
{
pdata = va_arg(ap, uint8_t*);
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
}
 
 
// --------------------------------------------------------------------------
void Decode64(void)
{
uint8_t a,b,c,d;
uint8_t x,y,z;
uint8_t ptrIn = 3;
uint8_t ptrOut = 3;
uint8_t len = ReceivedBytes - 6;
 
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;
}
 
 
 
// --------------------------------------------------------------------------
int16_t USART0_putchar (int8_t c)
{
// if tx is not enabled return immediatly
if(!(UCSR0B & (1 << TXEN0))) return (0);
if (c == '\n') USART0_putchar('\r');
// wait until previous character was send
loop_until_bit_is_set(UCSR0A, UDRE0);
// send character
UDR0 = c;
return (0);
}
 
 
// --------------------------------------------------------------------------
void USART0_ProcessRxData(void)
{
// if data in the rxd buffer are not locked immediately return
if(!rxd_buffer_locked) return;
 
Decode64(); // decode data block in rxd_buffer
 
switch(rxd_buffer[1]-'a') // check Slave Address
{
case MK3MAG_ADDRESS:
 
switch(rxd_buffer[2]) // check for CmdID
{
case 'w': // old style
case 'k': // Attitude info from FC
memcpy(&ExternData, (uint8_t*)pRxData, sizeof(ExternData));
RequestFlags |= RQST_COMPASS_HEADING;
AttitudeSource = ATTITUDE_SOURCE_UART;
Orientation = ExternData.Orientation;
FC_Connected = 255;
break;
 
default:
// unsupported command
break;
} // case MK3MAG_ADDRESS:
 
default: // any Slave Address
 
switch(rxd_buffer[2]) // check for CmdID
{
case 'b': // extern control
memcpy(&ExternControl, (uint8_t*)pRxData, sizeof(ExternControl));
#define KEY1 0x01
#define KEY2 0x02
#define KEY3 0x04
#define KEY4 0x08
#define KEY5 0x10
// use right arrow at display for switching the calstate
if(ExternControl.RemoteButtons & KEY2)
{
ExternData.CalState++;
if(ExternData.CalState == 6) ExternData.CalState = 0;
}
ConfirmFrame = ExternControl.Frame;
PC_Connected = 2000;
break;
 
case 'd': // request for the debug data
DebugData_Interval = (uint16_t) pRxData[0] * 10;
if(DebugData_Interval>0) RequestFlags |= RQST_DEBUG_DATA;
PC_Connected = 2000;
break;
 
case 'v': // request version and board release
RequestFlags |= RQST_VERSION_INFO;
PC_Connected = 2000;
break;
 
case 'h': // request display data
RemoteKeys |= pRxData[0];
if(RemoteKeys) DisplayLine = 0;
RequestFlags |= RQST_DISPLAY_DATA;
PC_Connected = 2000;
break;
 
case 'a':// Labels of the Analog Debug outputs
RequestDebugLabel = pRxData[0];
RequestFlags |= RQST_DEBUG_LABEL;
PC_Connected = 2000;
break;
 
case 'g':// get extern control data
RequestFlags |= RQST_EXTERN_CTRL;
PC_Connected = 2000;
break;
 
default:
// unsupported command
break;
}
break; // default:
}
// unlock the rxd buffer after processing
pRxData = 0;
RxDataLen = 0;
rxd_buffer_locked = FALSE;
}
 
 
 
//---------------------------------------------------------------------------------------------
void USART0_TransmitTxData(void)
{
if(!(UCSR0B & (1 << TXEN0))) return;
 
if(!txd_complete) return;
 
if((RequestFlags & RQST_DEBUG_LABEL) && txd_complete)
{
uint8_t label[16];
memcpy_P(label, ANALOG_LABEL[RequestDebugLabel], 16); // read lable from flash to sram buffer
SendOutData('A', MK3MAG_ADDRESS, 2, (uint8_t *)&RequestDebugLabel, sizeof(RequestDebugLabel), label, 16);
RequestDebugLabel = 0xFF;
RequestFlags &= ~RQST_DEBUG_LABEL;
}
else if(ConfirmFrame && txd_complete)
{
SendOutData('B', MK3MAG_ADDRESS, 1, (uint8_t *) &ConfirmFrame, sizeof(ConfirmFrame));
ConfirmFrame = 0;
}
else if(( ((DebugData_Interval > 0) && CheckDelay(DebugData_Timer)) || (RequestFlags & RQST_DEBUG_DATA)) && txd_complete)
{
SetDebugValues();
SendOutData('D', MK3MAG_ADDRESS, 1, (uint8_t *) &DebugOut, sizeof(DebugOut));
DebugData_Timer = SetDelay(DebugData_Interval);
RequestFlags &= ~RQST_DEBUG_DATA;
}
else if((RequestFlags & RQST_DISPLAY_DATA) && txd_complete)
{
LCD_PrintMenu();
SendOutData('H', FC_ADDRESS, 2, &DisplayLine, sizeof(DisplayLine), &DisplayBuff[DisplayLine * 20], 20);
DisplayLine++;
if(DisplayLine >= 4) DisplayLine = 0;
RequestFlags &= ~RQST_DISPLAY_DATA;
}
else if((RequestFlags & RQST_EXTERN_CTRL) && txd_complete)
{
SendOutData('G', MK3MAG_ADDRESS, 1, (uint8_t *) &ExternControl,sizeof(ExternControl));
RequestFlags &= ~RQST_EXTERN_CTRL;
}
else if((RequestFlags & RQST_COMPASS_HEADING) && txd_complete)
{
SendOutData('K', FC_ADDRESS, 1, (uint8_t *) &Heading, sizeof(Heading)); // send compass heading to FC
RequestFlags &= ~RQST_COMPASS_HEADING;
}
else if((RequestFlags & RQST_VERSION_INFO) && txd_complete)
{
SendOutData('V', MK3MAG_ADDRESS, 1, (uint8_t *) &UART_VersionInfo, sizeof(UART_VersionInfo));
RequestFlags &= ~RQST_VERSION_INFO;
}
}
 
 
void USART0_Print(int8_t *msg)
{
uint8_t i = 0;
while(msg[i] != 0)
{
USART0_putchar(msg[i++]);
}
}