BootSteuerung und deren Programmierung

 

Die Schaltung basiert auf einem AtMega16 Microcontroller, programmiert wurde in C und AvrStudio5.

Die Aufgaben der Schaltung bestehen in der Steuerung grundsätzlicher Funktionen wie Lenkung, Gas, Bilgenpumpe und Empfangen der GPS-Datensätze eines GPS-Moduls sowie der Bereitstellung einer Schnittstelle damit per PocketPC sowie Steuerbox gesteuert werden kann. Die Steuerung erfolgt komplett autonom vom Microcontroller, die Befehle für die Lenkung und das Gas werden entweder per RS232 vom PocketPC empfangen oder über die manuelle Steuerbox.

Weiter sollte der PocketPC zukünftig eine Art Autopilot darstellen wozu es natürlich nötig ist, dass dieser alle Zustände und die GPS-Signale vom Microcontroller abfragen und diesem auch Befehle senden kann. (Per kabelgebundenem RS232, evtl. sogar über Bluetooth..) Die „Logik“ und Funktionalität des Autopiloten im Microcontroller abzubilden sprengt definitiv meinen bisherigen Horizont und vermutlich auch die Kapazitäten des AtMega16, deshalb wird dies alles im PocketPC in einem C# Programm umgesetzt.

Die Software auf dem Microcontroller sollte also folgende Möglichkeiten bieten:

  • 2 serielle Schnittstellen. (PocketPC und GPS)
  • 2 PWM-Kanäle (Steuersignal für Gas-Servo und Leistungsregelung für Lenkmotor)
  • 3 Relais-Ausgänge (Bilgenpumpe, Lenkung links/rechts)
  • 3 Digitale, 1 analoger Eingang für die Signale der manuellen Steuerbox (Taster links/rechts, Gas-Poti, Aktivieren der manuellen Steuerung)
  • diverse Eingänge für Zustandserfassung von Tastern und Sensoren (Wasserstand, Endschalter der Lenkung etc.)
  • mehrere CountJobs für Verzögerungsschaltungen (Bilgenpumpenlaufzeit beschränken, Wiedereinschaltzeit festlegen etc.)
  • Erkennen von Befehlen über die serielle Schnittstelle und entsprechende Reaktion (Befehlsliste siehe unten)
  • Speichern der Einstellungen und Lenkpositionen im EEPROM (Damit nach Stromunterbruch nicht alles weg ist)

Der bisherige Code ist kompiliert knapp 11Kb groß, womit auf dem AtMega16 noch ein paar Kb frei wären für weitere Ideen und Funktionen. Der SRAM ist allerdings so gut wie ausgereizt weshalb bei Erweiterungen vermutlich auf den AtMega32 ausgewichen werden muss.. ODER der Programmcode optimiert werden muss.. da wär sicher noch so einiges drin aber mal eins nach dem anderen 😉

Nachfolgend die Befehlsliste die bisher unterstützt wird (Stand 25.07.2011)

Der erste Befehlteil steht für die Art des Befehls. (R – Lesen, X – Ausführen, S – Einstellen)

Befehl Teil1 Befehl Teil2 Befehl Teil3 Beschreibung
R G ein@ GPS EIN
R G aus@ GPS AUS
R A ein@ ANALOG EINGÄNGE AUSGEBEN
R D ein@ DIGITAL EINGÄNGE AUSGEBEN
R D aus@ DIGITAL AUSGÄNGE STATUS AUSGEBEN
R S ram@ EINSTELLUNGEN AUS RAM AUSGEBEN
R S epr@ EINSTELLUNGEN AUS EEPROM AUSGEBEN
R R ddr@ DATA DIRECTION REGISTER AUSGEBEN
R V var@ VARIABLEN AUSGEBEN (Gas-Servostellung, Anschlag etc.)
R V cnt@ WERTE DER COUNTJOBVARIABLEN AUSGEBEN
X R lie@ RELAIS LINKS
X R ree@ RELAIS RECHTS
X R lia@ RELAIS LINKS
X R rea@ RELAIS RECHTS
X R rep@ RELAIS RECHTS PULS
X R lip@ RELAIS LINKS PULS
X P ein@ PUMPE EIN
X P aus@ PUMPE AUS
X S epr@ EINSTELLUNGEN NEU AUS EEPROM IN RAM LADEN
S P dea@ PUMPE AUTOMATIK DEAKTIV
S P act@ PUMPE AUTOMATIK AKTIV
S G 0000-1024 SETZE PWM GAS
S L 0000-1024 SETZE PWM LENKUNG
S S psc[0-3] SETZE PWM LENKUNG PRESCALER (0->256,1->128,2->64,3->32)
S S save EINSTELLUNGEN IM EEPROM SPEICHERN
S T low@ SETZE GAS TRIM LOW
S T hig@ SETZE GAS TRIM HIGH
S T res@ RESET GAS TRIM SETTINGS
S S s[000-255] DEFINIERE PULS DAUER LENKUNG
S M act@ MANUELLE STEUERUNG AKTIVIEREN
S M dea@ MANUELLE STEUERUNG DEAKTIVIEREN
S C a[000-255] STARTE COUNTJOB3 MIT WERT (sendet im angegebenen Intervall Variablenwerte+Informationen über RS232)
S C dea@ STOPPT COUNTJOB3

 

Nachfolgend zum Selbststudium der komplette Quellcode der BootSteuerung:

/*
 * Atmega16_Bootsteuerung.c
 *
 * Created: 02.06.2011 22:53:38
 *  Author: Stefan
 */

#define F_CPU 7372800UL
#include <avr/io.h>
#include <util/delay.h>
#include <avr/interrupt.h>
#include <avr/eeprom.h>
#include "i2cmaster.h"
#include "mem-check.h"
#include <avr/wdt.h>

#ifndef SIGNAL
#include <avr/signal.h>
#endif // SIGNAL

#define CMPS10  0xC0
#define REMOTE  0xE6
#define BOOT_UEBERWACHUNG 0xE8
#define RGBCTRL 0x50

#define REMOTE_INTERVAL 10
#define GPS_OUTPUT_INTERVAL 60
#define UEB_OUTPUT_INTERVAL 240

#define SERVO_PROTECT_COUNTER_VAL 10

//-----------Count Jobs
#define CJ_d3_DEFAULT 100 //46080 //Countjob A Dauer ~ 1 Minute
#define CJ_d2_DEFAULT 32 //9600  //wenn d1 = 1
//--------------------

//-----------Settings EEPROM POSITIONS
#define EEPROM_l_prescaler 0
#define EEPROM_pwm_l_startval 1
#define EEPROM_pwm_g_startval 2
#define EEPROM_l_stepdur 3
#define EEPROM_gas_trim_high 4
#define EEPROM_gas_trim_low 5
#define EEPROM_autopump_active 6
#define EEPROM_manual_override 7
//------------------------------------

//----------GPS PARSER
// Message Codes
#define NMEA_NODATA		0	// No data. Packet not available, bad, or not decoded
#define NMEA_GPGGA		1	// Global Positioning System Fix Data
#define NMEA_GPVTG		2	// Course over ground and ground speed
#define NMEA_GPGLL		3	// Geographic position - latitude/longitude
#define NMEA_GPGSV		4	// GPS satellites in view
#define NMEA_GPGSA		5	// GPS DOP and active satellites
#define NMEA_GPRMC		6	// Recommended minimum specific GPS data
#define NMEA_UNKNOWN	0xFF// Packet received but not known
#define GPSBUFFSIZE		83
//double pi = 3.141592653589793238462643;
//_-----------------------------------

//NOTIFY_FLAG BITS
#define NOTIFY_NEW_CA_ACTION 0
#define NOTIFY_NEW_SETTING 1

//-----SOFTWARE UART
#include "uart.h"

// Folgende Zeile einkommentieren, falls FIFO verwendet werden soll
//#include "fifo.h"

#define BAUDRATE 4800

#define nop() __asm volatile ("nop")

#ifdef SUART_TXD
    #define SUART_TXD_PORT PORTB
    #define SUART_TXD_DDR  DDRB
    #define SUART_TXD_BIT  PB1
    static volatile uint16_t outframe;
#endif // SUART_TXD

#ifdef SUART_RXD
    #define SUART_RXD_PORT PORTB
    #define SUART_RXD_PIN  PINB
    #define SUART_RXD_DDR  DDRB
    #define SUART_RXD_BIT  PB0
    static volatile uint16_t inframe;
    static volatile uint8_t inbits, received;

    #ifdef _FIFO_H_
        #define INBUF_SIZE 4
        static uint8_t inbuf[INBUF_SIZE];
        fifo_t infifo;
    #else // _FIFO_H_
        static volatile uint8_t indata;
    #endif // _FIFO_H_
#endif // SUART_RXD
//END SOFTWARE UART

//HARDWARE USART CONFIG
#define USART_BAUDRATE 9600 //115200funzt bis 460800 allerdings nicht bei BT-Conn -< max 9600
#define BAUD_PRESCALE (((F_CPU+USART_BAUDRATE*8) / (USART_BAUDRATE * 16UL)) - 1)
//------------

volatile unsigned char lastchar = 0;
volatile unsigned char cmda[6];
volatile unsigned char okbuffer[GPSBUFFSIZE];
volatile unsigned char tempbuffer[GPSBUFFSIZE];
volatile unsigned char buffcount = 0;
volatile uint8_t newgpssentence = 0;
volatile uint8_t gps_active = 1;
volatile uint8_t i2c_active = 1;
volatile uint8_t i2c_errors_active = 1;
volatile uint8_t gps_output_active = 1;
volatile uint8_t parsing_in_progress = 0;
volatile unsigned char pumping = 0;
volatile unsigned char pumping_forbidden = 0;
char tbuff[6];
volatile unsigned char finalpos_reached = 0;
volatile int8_t nick = 0;
volatile int8_t roll = 0;
volatile uint16_t course = 0;

//settingvars
volatile unsigned char pwm_l_prescaler = 4;
volatile unsigned char pwm_l_startval = 0;
volatile unsigned char pwm_g_startval = 0;
volatile unsigned char l_stepdur = 15;
volatile unsigned char gas_trim_high = 252;
volatile unsigned char gas_trim_low = 223;
volatile unsigned char autopump_active = 1;
volatile unsigned char manual_override = 0;
volatile unsigned char manual_phone_override = 0;
volatile uint8_t motor_allowed = 0;
volatile uint8_t steeringmode = 0; //0->by relais, 1->by motor driver

//count jobs
volatile unsigned char cj_active = 0;
volatile uint16_t cj1_d3 = CJ_d3_DEFAULT;
volatile uint16_t cj1_d2 = CJ_d2_DEFAULT;
volatile uint8_t cj1_d1 = 0;
volatile uint16_t cj2_d3 = CJ_d3_DEFAULT;
volatile uint16_t cj2_d2 = CJ_d2_DEFAULT;
volatile uint16_t cj2_d1 = 0;
volatile uint16_t cj3_d3 = CJ_d3_DEFAULT;
volatile uint16_t cj3_d2 = CJ_d2_DEFAULT;
volatile uint8_t cj3_d1 = 0;
//

//VARS FOR GPS PARSER
//GPGGA data
char Lat[10];
char Long[11];
//char GPSTime[7];
char NS;
char EW;
char FixQuality;
char Altitude[8];
uint8_t lat_deg = 0;
uint8_t lat_min = 0;
uint16_t lat_sec = 0;
uint8_t long_deg = 0;
uint8_t long_min = 0;
uint16_t long_sec = 0;
uint8_t UsedSatellites = 0;
uint8_t HDOP = 0;
uint8_t GPSThour = 0;
uint8_t GPSTmin = 0;
uint8_t GPSTsec = 0;
uint8_t GPSTday = 0;
uint8_t GPSTmon = 0;
uint8_t GPSTyear = 0;

// GPRMC data
char Speed[6];//in knots
char Heading[7];
uint16_t iSpeed = 0;
uint16_t iHeading = 0;
//char GPSDate[7];
char GPSStatus;

// GPGSV data
uint8_t SatsinView = 0;

// Remote vars
uint8_t notify_flag = 0;
uint8_t notify_immunity_flag = 0;
int8_t ca_corrlevel = 0;
int8_t ca_coursechange_level = 0;
int8_t ca_required_action = 0;
int8_t ca_steer = 0;
int8_t manual_steer = 0;
uint8_t ca_active = 0;
uint8_t gas_pwm_from_i2c = 0;

// RGBCTRL vars
uint8_t rgb_red = 255;
uint8_t rgb_green = 255;
uint8_t rgb_blue = 255;
uint8_t rgb_test = 0;
uint8_t rgb_sound = 0;

// Ueberw vars
volatile uint16_t ueb_voltage = 0;
volatile uint8_t ueb_batalarm = 0;
volatile uint8_t ueb_wsens_high = 0;
volatile uint8_t ueb_wsens_low = 0;
volatile uint8_t ueb_pumping = 0;
volatile uint8_t ueb_pumpstate = 0;
volatile uint8_t ueb_autopump_active = 0;
volatile uint8_t ueb_nosms = 0;
volatile uint8_t ueb_deny_reco = 0;
volatile uint8_t ueb_pumpstarts = 0;
volatile uint16_t ueb_pumprunned = 0;
volatile uint8_t ueb_phone_res1 = 0;
volatile uint8_t ueb_phone_res2 = 0;
volatile uint8_t ueb_sent_sms = 0;
volatile uint16_t ueb_all_sms = 0;
volatile uint8_t ueb_phone_init = 0;

volatile uint8_t remote_iv = 0;
volatile uint8_t do_i2c = 0;
volatile uint8_t do_gps = 0;
volatile uint8_t do_ueb = 0;
volatile uint8_t last_ocr_val = 0;
volatile uint8_t servo_protect_counter = 0;

//SOFTWARE UART
void uart_init()
{
    uint8_t tifr = 0;
    uint8_t sreg = SREG;
    cli();

    // Mode #4 für Timer1
    // und volle MCU clock
    // IC Noise Cancel
    // IC on Falling Edge
    TCCR1A = 0;
    TCCR1B = (1 << WGM12) | (1 << CS10) | (0 << ICES1) | (1 << ICNC1);

    // OutputCompare für gewünschte Timer1 Frequenz
	OCR1A = (uint16_t) ((uint32_t) F_CPU/BAUDRATE);

#ifdef SUART_RXD
    SUART_RXD_DDR  &= ~(1 << SUART_RXD_BIT);
    SUART_RXD_PORT |=  (1 << SUART_RXD_BIT);
    TIMSK |= (1 << TICIE1);
    tifr  |= (1 << ICF1) | (1 << OCF1B);
#else
    TIMSK &= ~(1 << TICIE1);
#endif // SUART_RXD

#ifdef SUART_TXD
    tifr |= (1 << OCF1A);
    SUART_TXD_PORT |= (1 << SUART_TXD_BIT);
    SUART_TXD_DDR  |= (1 << SUART_TXD_BIT);
    outframe = 0;
#endif // SUART_TXD

    TIFR = tifr;

    SREG = sreg;

#ifdef _FIFO_H_
   fifo_init (&infifo,   inbuf, INBUF_SIZE);
#endif // _FIFO_H_

}

#ifdef SUART_TXD
void uart_putc (const char c)
{
    do
    {
        sei(); nop(); cli(); // yield();
    } while (outframe);

    // frame = *.P.7.6.5.4.3.2.1.0.S   S=Start(0), P=Stop(1), *=Endemarke(1)
    outframe = (3 << 9) | (((uint8_t) c) << 1);

    TIMSK |= (1 << OCIE1A);
    TIFR   = (1 << OCF1A);

    sei();
}
#endif // SUART_TXD

#ifdef SUART_TXD
//SIGNAL (SIG_OUTPUT_COMPARE1A)
ISR(TIMER1_COMPA_vect)
{
    uint16_t data = outframe;

    if (data & 1)      SUART_TXD_PORT |=  (1 << SUART_TXD_BIT);
    else               SUART_TXD_PORT &= ~(1 << SUART_TXD_BIT);

    if (1 == data)
    {
        TIMSK &= ~(1 << OCIE1A);
    }

    outframe = data >> 1;
}
#endif // SUART_TXD

#ifdef SUART_RXD
//SIGNAL (SIG_INPUT_CAPTURE1)
ISR(TIMER1_CAPT_vect)
{
    uint16_t icr1  = ICR1;
    uint16_t ocr1a = OCR1A;

    // Eine halbe Bitzeit zu ICR1 addieren (modulo OCR1A) und nach OCR1B
    uint16_t ocr1b = icr1 + ocr1a/2;
    if (ocr1b >= ocr1a)
        ocr1b -= ocr1a;
    OCR1B = ocr1b;

    TIFR = (1 << OCF1B);
    TIMSK = (TIMSK & ~(1 << TICIE1)) | (1 << OCIE1B);
    inframe = 0;
    inbits = 0;
}
#endif // SUART_RXD

#ifdef SUART_RXD
//SIGNAL (SIG_OUTPUT_COMPARE1B)
ISR(TIMER1_COMPB_vect)
{
    uint16_t data = inframe >> 1;

    if (SUART_RXD_PIN & (1 << SUART_RXD_BIT))
        data |= (1 << 9);

    uint8_t bits = inbits+1;

    if (10 == bits)
    {
        if ((data & 1) == 0)
            if (data >= (1 << 9))
            {
#ifdef _FIFO_H_
                _inline_fifo_put (&infifo, data >> 1);
#else
                indata = data >> 1;
#endif // _FIFO_H_
                received = 1;
				if(buffcount < 85)
				{
					if(indata == '$')
					{
						tempbuffer[buffcount] = '\0';
						//*okbuffer = (int)tempbuffer;
						if(parsing_in_progress==0)
						{
						uint8_t xc = 0;
						for(xc=0;xc<=buffcount;xc++)
							okbuffer[xc] = tempbuffer[xc];

						newgpssentence = 1;
						}
						else
						{
							huart_puts("UI");
						}
						buffcount = 0;
						tempbuffer[buffcount] = indata;
						buffcount++;
					}
					else
					{
						tempbuffer[buffcount] = indata;
						buffcount++;
					}

				}
				else
				{
					//*okbuffer = (int)tempbuffer;
					//newgpssentence = 1;
					buffcount = 0;
				}
            }

        TIMSK = (TIMSK & ~(1 << OCIE1B)) | (1 << TICIE1);
        TIFR = (1 << ICF1);
    }
    else
    {
        inbits = bits;
        inframe = data;
    }
}
#endif // SUART_RXD

#ifdef SUART_RXD
#ifdef _FIFO_H_

int uart_getc_wait()
{
    return (int) fifo_get_wait (&infifo);
}

int uart_getc_nowait()
{
    return fifo_get_nowait (&infifo);
}

#else // _FIFO_H_

int uart_getc_wait()
{
    while (!received)   {}
    received = 0;

    return (int) indata;
}

int uart_getc_nowait()
{
    if (received)
    {
        received = 0;
        return (int) indata;
    }

    return -1;
}

#endif // _FIFO_H_
#endif // SUART_RXD



//END SOFTWARE UART


void huart_init()
{
		cli();
		UCSRB |= (1 << RXEN) | (1 << TXEN);
		UCSRC |= (1 << URSEL) | (1<<USBS) | (1 << UCSZ0) | (1 << UCSZ1); // Use 8-bit character sizes
		UBRRL = BAUD_PRESCALE; 			// Load lower 8-bits of the baud rate value into the low byte of the UBRR register
		UBRRH = (BAUD_PRESCALE >> 8);   // Load upper 8-bits of the baud rate value into the high byte of the UBRR register
		UCSRB |= (1 << RXCIE);
		sei();
}

// Ein Zeichen senden
void huart_putc(unsigned char c)
{
    while(!(UCSRA & (1 << UDRE)));      // warte, bis UDR bereit

    UDR = c;                      // sende Zeichen
}

// Einen String senden
void huart_puts (char *s)
{
    while (*s)
    {   // so lange *s != NULL
        huart_putc(*s);
        s++;
    }
}

unsigned int huart_getch()
{
	 	while ((UCSRA & (1 << RXC)) == 0); 		// Do nothing until data has been received and is ready to be read from UDR
		return(UDR);
}

//SETTING MANAGEMENT
void save_settings_to_eeprom()
{
	eeprom_update_byte( (uint8_t*)EEPROM_l_prescaler, (uint8_t)pwm_l_prescaler);
	eeprom_update_byte( (uint8_t*)EEPROM_pwm_l_startval, (uint8_t)pwm_l_startval );
	eeprom_update_byte( (uint8_t*)EEPROM_pwm_g_startval, (uint8_t)pwm_g_startval);
	eeprom_update_byte( (uint8_t*)EEPROM_l_stepdur, (uint8_t)l_stepdur);
	eeprom_update_byte( (uint8_t*)EEPROM_gas_trim_high, (uint8_t)gas_trim_high);
	eeprom_update_byte( (uint8_t*)EEPROM_gas_trim_low, (uint8_t)gas_trim_low);
	eeprom_update_byte( (uint8_t*)EEPROM_autopump_active, (uint8_t)autopump_active);
	eeprom_update_byte( (uint8_t*)EEPROM_manual_override, (uint8_t)manual_override);
}

void load_settings_from_eeprom()
{
	pwm_l_prescaler = eeprom_read_byte( (uint8_t*)EEPROM_l_prescaler );
	pwm_l_startval = eeprom_read_byte( (uint8_t*)EEPROM_pwm_l_startval );
	pwm_g_startval = eeprom_read_byte( (uint8_t*)EEPROM_pwm_g_startval );
	l_stepdur = eeprom_read_byte( (uint8_t*)EEPROM_l_stepdur );
	gas_trim_high = eeprom_read_byte( (uint8_t*)EEPROM_gas_trim_high );
	gas_trim_low = eeprom_read_byte( (uint8_t*)EEPROM_gas_trim_low );
	autopump_active = eeprom_read_byte( (uint8_t*)EEPROM_autopump_active );
	manual_override = eeprom_read_byte( (uint8_t*)EEPROM_manual_override );
}

void read_settings_from_eeprom()
{
	huart_puts("\r\n");
	huart_puts("#EEPROM@");
	utoa(eeprom_read_byte( (uint8_t*)EEPROM_l_prescaler ),tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(eeprom_read_byte( (uint8_t*)EEPROM_pwm_l_startval ),tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(eeprom_read_byte( (uint8_t*)EEPROM_pwm_g_startval ),tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(eeprom_read_byte( (uint8_t*)EEPROM_l_stepdur ),tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(eeprom_read_byte( (uint8_t*)EEPROM_gas_trim_high ),tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(eeprom_read_byte( (uint8_t*)EEPROM_gas_trim_low ),tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(eeprom_read_byte( (uint8_t*)EEPROM_autopump_active ),tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(eeprom_read_byte( (uint8_t*)EEPROM_manual_override ),tbuff,10);
	huart_puts(tbuff);
	huart_puts("\r\n");
}

void read_settings_from_ram()
{
	huart_puts("\r\n");
	huart_puts("#RAM@");
	utoa(pwm_l_prescaler,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(pwm_l_startval,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(pwm_g_startval,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(l_stepdur,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(gas_trim_high,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(gas_trim_low,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(autopump_active,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(manual_override,tbuff,10);
	huart_puts(tbuff);
	huart_puts("\r\n");
}

void submit_ueberw_status()
{
	huart_puts("\r\n");
	huart_puts("@UEB@");
	utoa(autopump_active,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(ueb_voltage,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(ueb_batalarm,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(ueb_wsens_high,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(ueb_wsens_low,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(ueb_pumping,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(ueb_pumpstate,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(ueb_nosms,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(ueb_deny_reco,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(ueb_pumpstarts,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(ueb_pumprunned,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(ueb_phone_res1,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(ueb_phone_res2,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(ueb_sent_sms,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(ueb_all_sms,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(ueb_phone_init,tbuff,10);
	huart_puts(tbuff);
	huart_puts("\r\n");
}

void submit_runtime_vars()
{
	huart_puts("\r\n");
	huart_puts("@VAR@");
	utoa(pwm_g_startval,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(manual_override,tbuff,10);
	huart_puts(tbuff);
	huart_puts("\r\n");
}

void nmeaProcessGPGGA2(char* packet)
{
	uint8_t i;
	uint8_t GPIndex=0;
	char gbuff[6];

		//start parsing just after "GPGGA,"
	i = 7;
	// attempt to reject empty packets right away
	if((packet[i]==',') && (packet[i+1]==',')) return;


	// get UTC time [hhmmss.sss]
	int8_t scanlimit = 6;
	while(packet[i] != ',')				// next field: Time - changed to parse time into separate vars - deactivated in GPSRMC
	{
		if(scanlimit > 0)
		{
			if(i >= GPSBUFFSIZE || GPIndex >5)
			{

				//huart_puts("XA!");
				//huart_puts("\r\n");
				return; //stop parsing as something seems to be gone wrong
			}
			gbuff[GPIndex]=packet[i];
			GPIndex++;
			i++;
			scanlimit--;
		}
		else
		{
			i++;
		}
	}
	//parse time to vars
	tbuff[0] = gbuff[0];
	tbuff[1] = gbuff[1];
	tbuff[2] = '\0';
	GPSThour = atoi(tbuff);
	tbuff[0] = gbuff[2];
	tbuff[1] = gbuff[3];
	tbuff[2] = '\0';
	GPSTmin = atoi(tbuff);
	tbuff[0] = gbuff[4];
	tbuff[1] = gbuff[5];
	tbuff[2] = '\0';
	GPSTsec = atoi(tbuff);

	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field:Latitude
	{
	Lat[GPIndex]=packet[i];
	i++;
	GPIndex++;
					if(i >= GPSBUFFSIZE || GPIndex>9)
					{
						//huart_puts("XB!");
						//huart_puts("\r\n");
						return; //stop parsing as something seems to be gone wrong
					}
	}
	Lat[GPIndex]= '\0';

	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field: N/S
	{
	//do nothing
		if(i >= GPSBUFFSIZE)
		{
			//huart_puts("XC!");
			//huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
	i++;
	GPIndex++;
	}
	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field:Longitude
	{
	Long[GPIndex]=packet[i];
	i++;
	GPIndex++;
					if(i >= GPSBUFFSIZE || GPIndex>10)
					{
						//huart_puts("XD!");
						//huart_puts("\r\n");
						return; //stop parsing as something seems to be gone wrong
					}
	}
	Long[GPIndex]= '\0';

	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field: E/W
	{
	//do nothing
	i++;
	GPIndex++;
		if(i >= GPSBUFFSIZE)
		{
			//huart_puts("XE!");
			//huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
	}
	i++;
	GPIndex=0;

	while(packet[i] != ',')				// next field:Fix Quality
	{
	FixQuality=packet[i];
	i++;
	GPIndex++;
		if(i >= GPSBUFFSIZE)
		{
			//huart_puts("XF!");
			//huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
	}


	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field:No of satellites
	{
	gbuff[GPIndex] = packet[i];
	i++;
	GPIndex++;
		if(i >= GPSBUFFSIZE)
		{
			//huart_puts("XG!");
			//huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
	}
	gbuff[GPIndex] = '\0';
	UsedSatellites = atoi(gbuff);

	i++;
	GPIndex=0;
	scanlimit = 5;
	while(packet[i] != ',')				// next field:horizontal dilution of position
	{
		if(scanlimit > 0)
		{
			if(i >= GPSBUFFSIZE || GPIndex>5)
			{
				//huart_puts("XH!");
				//huart_puts("\r\n");
				return; //stop parsing as something seems to be gone wrong
			}
			if(packet[i] == '.')
			{
				scanlimit = 0;
				i++;
			}
			else
			{
				gbuff[GPIndex]=packet[i];
				i++;
				GPIndex++;
				scanlimit--;
			}
		}
		else
		{
			i++;
		}
	}
	gbuff[GPIndex]= '\0';
	HDOP = atoi(gbuff);


	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field:Altitude in meters above sea level
	{
	Altitude[GPIndex]=packet[i];
	i++;
	GPIndex++;
		if(i >= GPSBUFFSIZE || GPIndex > 7)
		{
			//huart_puts("XI!");
			//huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
	}
	Altitude[GPIndex]= '\0';
	//GPIndex=0;
	// next field: longitude					//this method can be used to access a variable directly
	//for(int i=25;i<35;i++)
	//{
	//Long[GPIndex]=packet[i];
	//GPIndex++;
	//}
	// get latitude [ddmm.mmmmm]
	//latitude = strtod(&packet[i], &endptr);

	//minutesfrac = modf(latitude/100, &degrees);
	//latitude= degrees + (minutesfrac*100)/60;
	//latitude *= (pi/180);
	//convert longitude to 3 int fields
	gbuff[0] = Long[0];
	gbuff[1] = Long[1];
	gbuff[2] = Long[2];
	gbuff[3] = '\0';
	long_deg = atoi(gbuff);
	gbuff[0] = Long[3];
	gbuff[1] = Long[4];
	gbuff[2] = '\0';
	long_min = atoi(gbuff);
	gbuff[0] = Long[6];
	gbuff[1] = Long[7];
	gbuff[2] = Long[8];
	gbuff[3] = Long[9];
	gbuff[4] = '\0';
	long_sec = atoi(gbuff);
	long_sec = long_sec*6; //divide trough 1000 to get seconds

	//convert latitude to 3 int fields
	gbuff[0] = Lat[0];
	gbuff[1] = Lat[1];
	gbuff[2] = '\0';
	lat_deg = atoi(gbuff);
	gbuff[0] = Lat[2];
	gbuff[1] = Lat[3];
	gbuff[2] = '\0';
	lat_min = atoi(gbuff);
	gbuff[0] = Lat[5];
	gbuff[1] = Lat[6];
	gbuff[2] = Lat[7];
	gbuff[3] = Lat[8];
	gbuff[4] = '\0';
	lat_sec = atoi(gbuff);
	lat_sec = lat_sec*6; // divide trough 1000 to get seconds
}

void nmeaProcessGPGGA2_debug(char* packet)
{
	/*uint8_t i;
	uint8_t GPIndex=0;
	char gbuff[6];

		//start parsing just after "GPGGA,"
	i = 7;
	// attempt to reject empty packets right away
	if((packet[i]==',') && (packet[i+1]==',')) return;


	// get UTC time [hhmmss.sss]
	int8_t scanlimit = 6;
	while(packet[i] != ',')				// next field: Time - changed to parse time into separate vars - deactivated in GPSRMC
	{
		if(scanlimit > 0)
		{
			if(i >= GPSBUFFSIZE || GPIndex >5)
			{

				huart_puts("XA!");
				huart_puts("\r\n");
				return; //stop parsing as something seems to be gone wrong
			}
			gbuff[GPIndex]=packet[i];
			GPIndex++;
			i++;
			scanlimit--;
		}
		else
		{
			i++;
		}
	}
	//parse time to vars
	tbuff[0] = gbuff[0];
	tbuff[1] = gbuff[1];
	tbuff[2] = '\0';
	GPSThour = atoi(tbuff);
	tbuff[0] = gbuff[2];
	tbuff[1] = gbuff[3];
	tbuff[2] = '\0';
	GPSTmin = atoi(tbuff);
	tbuff[0] = gbuff[4];
	tbuff[1] = gbuff[5];
	tbuff[2] = '\0';
	GPSTsec = atoi(tbuff);

	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field:Latitude
	{
	Lat[GPIndex]=packet[i];
	i++;
	GPIndex++;
					if(i >= GPSBUFFSIZE || GPIndex>9)
					{
						huart_puts("XB!");
						huart_puts("\r\n");
						return; //stop parsing as something seems to be gone wrong
					}
	}
	Lat[GPIndex]= '\0';

	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field: N/S
	{
	//do nothing
		if(i >= GPSBUFFSIZE)
		{
			huart_puts("XC!");
			huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
	i++;
	GPIndex++;
	}
	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field:Longitude
	{
	Long[GPIndex]=packet[i];
	i++;
	GPIndex++;
					if(i >= GPSBUFFSIZE || GPIndex>10)
					{
						huart_puts("XD!");
						huart_puts("\r\n");
						return; //stop parsing as something seems to be gone wrong
					}
	}
	Long[GPIndex]= '\0';

	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field: E/W
	{
	//do nothing
	i++;
	GPIndex++;
		if(i >= GPSBUFFSIZE)
		{
			huart_puts("XE!");
			huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
	}
	i++;
	GPIndex=0;

	while(packet[i] != ',')				// next field:Fix Quality
	{
	FixQuality=packet[i];
	i++;
	GPIndex++;
		if(i >= GPSBUFFSIZE)
		{
			huart_puts("XF!");
			huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
	}


	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field:No of satellites
	{
	gbuff[GPIndex] = packet[i];
	i++;
	GPIndex++;
		if(i >= GPSBUFFSIZE)
		{
			huart_puts("XG!");
			huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
	}
	gbuff[GPIndex] = '\0';
	UsedSatellites = atoi(gbuff);

	i++;
	GPIndex=0;
	scanlimit = 5;
	while(packet[i] != ',')				// next field:horizontal dilution of position
	{
		if(scanlimit > 0)
		{
			if(i >= GPSBUFFSIZE || GPIndex>5)
			{
				huart_puts("XH!");
				huart_puts("\r\n");
				return; //stop parsing as something seems to be gone wrong
			}
			if(packet[i] == '.')
			{
				scanlimit = 0;
				i++;
			}
			else
			{
				gbuff[GPIndex]=packet[i];
				i++;
				GPIndex++;
				scanlimit--;
			}
		}
		else
		{
			i++;
		}
	}
	gbuff[GPIndex]= '\0';
	HDOP = atoi(gbuff);


	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field:Altitude in meters above sea level
	{
	Altitude[GPIndex]=packet[i];
	i++;
	GPIndex++;
		if(i >= GPSBUFFSIZE || GPIndex > 7)
		{
			huart_puts("XI!");
			huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
	}
	Altitude[GPIndex]= '\0';
	//GPIndex=0;
	// next field: longitude					//this method can be used to access a variable directly
	//for(int i=25;i<35;i++)
	//{
	//Long[GPIndex]=packet[i];
	//GPIndex++;
	//}
	// get latitude [ddmm.mmmmm]
	//latitude = strtod(&packet[i], &endptr);

	//minutesfrac = modf(latitude/100, &degrees);
	//latitude= degrees + (minutesfrac*100)/60;
	//latitude *= (pi/180);
	//convert longitude to 3 int fields
	gbuff[0] = Long[0];
	gbuff[1] = Long[1];
	gbuff[2] = Long[2];
	gbuff[3] = '\0';
	long_deg = atoi(gbuff);
	gbuff[0] = Long[3];
	gbuff[1] = Long[4];
	gbuff[2] = '\0';
	long_min = atoi(gbuff);
	gbuff[0] = Long[6];
	gbuff[1] = Long[7];
	gbuff[2] = Long[8];
	gbuff[3] = Long[9];
	gbuff[4] = '\0';
	long_sec = atoi(gbuff);
	long_sec = long_sec*6; //divide trough 1000 to get seconds

	//convert latitude to 3 int fields
	gbuff[0] = Lat[0];
	gbuff[1] = Lat[1];
	gbuff[2] = '\0';
	lat_deg = atoi(gbuff);
	gbuff[0] = Lat[2];
	gbuff[1] = Lat[3];
	gbuff[2] = '\0';
	lat_min = atoi(gbuff);
	gbuff[0] = Lat[5];
	gbuff[1] = Lat[6];
	gbuff[2] = Lat[7];
	gbuff[3] = Lat[8];
	gbuff[4] = '\0';
	lat_sec = atoi(gbuff);
	lat_sec = lat_sec*6; // divide trough 1000 to get seconds

	utoa(i,tbuff,10);
	huart_puts("1x");
	huart_puts(tbuff);
	huart_puts("\r\n");*/
}

void nmeaProcessGPGSV2(char* packet)
{
	uint8_t i = 7;
	uint8_t GPIndex=0;
	char gbuff[3];

	if(packet[i]==',' && packet[i+1]==',')
		return;

	while(packet[i] != ',')				// first field: number of messages (up to 3)
	{
		//skip
		i++;
	}
	i++;
	//GPIndex = 0;

	while(packet[i] != ',')				// next field: this message number
	{
		//skip
		i++;
	}
	i++;
	//GPIndex = 0;
	while(packet[i] != ',')				// next field: satellites in view
	{
		if(i >= GPSBUFFSIZE || GPIndex > 2)
		{
			//huart_puts("XJ!");
			//huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
		gbuff[GPIndex]=packet[i];
		i++;
		GPIndex++;
	}
	gbuff[GPIndex] = '\0';
	SatsinView = atoi(gbuff);

	//BREAK here as we only want satellites in view information
	return;
}

void nmeaProcessGPGSV2_debug(char* packet)
{
	/*uint8_t i = 7;
	uint8_t GPIndex=0;
	char gbuff[3];

	if(packet[i]==',' && packet[i+1]==',')
		return;

	while(packet[i] != ',')				// first field: number of messages (up to 3)
	{
		//skip
		i++;
	}
	i++;
	//GPIndex = 0;

	while(packet[i] != ',')				// next field: this message number
	{
		//skip
		i++;
	}
	i++;
	//GPIndex = 0;
	while(packet[i] != ',')				// next field: satellites in view
	{
		if(i >= GPSBUFFSIZE || GPIndex > 2)
		{
			huart_puts("XJ!");
			huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
		gbuff[GPIndex]=packet[i];
		i++;
		GPIndex++;
	}
	gbuff[GPIndex] = '\0';
	SatsinView = atoi(gbuff);

	utoa(i,tbuff,10);
	huart_puts("2x");
	huart_puts(tbuff);
	huart_puts("\r\n");
	//BREAK here as we only want satellites in view information
	return;*/
}

void nmeaProcessGPRMC2(char* packet)
{
	uint8_t i;
	uint8_t GPIndex=0;
	char gbuff[6];
	uint8_t helpidx=0;


	//start parsing just after "GPRMC,"
	i = 7;
	// attempt to reject empty packets right away
	if(packet[i]==',' && packet[i+1]==',')
		return;

	// get UTC time [hhmmss.sss]
	//int8_t scanlimit = 6;
	while(packet[i] != ',')				// next field: Time -> deactivated -> is parsed at GPGSA-sentence
	{
		/*if(scanlimit > 0)
		{
			GPSTime[GPIndex]=packet[i];
			i++;
			GPIndex++;
			scanlimit--;
		}
		else
		{*/
			i++;
		//}
	}
	//GPSTime[GPIndex]= '\0';

	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field: Navigation warning
	{
		if(i >= GPSBUFFSIZE || GPIndex > 2)
		{
			//huart_puts("XK!");
			//huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
	GPSStatus = packet[i];
	i++;
	GPIndex++;
	}

	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field:Latitude
	{
		if(i >= GPSBUFFSIZE || GPIndex > 9)
		{
			//huart_puts("XL!");
			//huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
	Lat[GPIndex]=packet[i];
	i++;
	GPIndex++;
	}
	Lat[GPIndex]= '\0';

	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field:N/S
	{
	//NS[GPIndex]=packet[i];
		if(i >= GPSBUFFSIZE || GPIndex > 7)
		{
			//huart_puts("XM!");
			//huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
	NS = packet[i];
	i++;
	GPIndex++;
	}
	//NS[GPIndex]= '\0';


	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field:Longitude
	{
		if(i >= GPSBUFFSIZE || GPIndex > 10)
		{
			//huart_puts("XN!");
			//huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
	Long[GPIndex]=packet[i];
	i++;
	GPIndex++;
	}
	Long[GPIndex]= '\0';

	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field:E/W
	{
	//EW[GPIndex]=packet[i];
		if(i >= GPSBUFFSIZE || GPIndex > 7)
		{
			//huart_puts("XO!");
			//huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
	EW = packet[i];
	i++;
	GPIndex++;
	}
	//EW[GPIndex]= '\0';

	i++;
	GPIndex=0;
	helpidx=0;

	// get
	while(packet[i] != ',')				// next field: speed
	{
		if(i >= GPSBUFFSIZE || GPIndex > 5 || helpidx > 5)
		{
			//huart_puts("XP!");
			//huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
		Speed[GPIndex]=packet[i];
		gbuff[helpidx]=packet[i];
		i++;
		GPIndex++;
		if(packet[i] != '.')
			helpidx++;
	}
	Speed[GPIndex]= '\0';
	gbuff[helpidx]= '\0';
	//convert to int representation iSpeed
	iSpeed = atoi(gbuff);

	i++;
	GPIndex=0;
	helpidx=0;
	while(packet[i] != ',')				// next field:Course made good
	{
		if(i >= GPSBUFFSIZE || GPIndex > 6)
		{
			//huart_puts("XQ!");
			//huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
		Heading[GPIndex]=packet[i];
		gbuff[helpidx]=packet[i];
		i++;
		GPIndex++;
		if(packet[i] != '.')
			helpidx++;
	}
	Heading[GPIndex]= '\0';
	gbuff[helpidx]= '\0';
	//convert to int representation iHeading
	iHeading = atoi(gbuff);

	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field:Date
	{
		if(i >= GPSBUFFSIZE || GPIndex > 5)
		{
			//huart_puts("XR!");
			//huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
		gbuff[GPIndex]=packet[i];
		i++;
		GPIndex++;
	}
	//GPSDate[GPIndex]= '\0';
	//parse time to vars
	tbuff[0] = gbuff[0];
	tbuff[1] = gbuff[1];
	tbuff[2] = '\0';
	GPSTday = atoi(tbuff);
	tbuff[0] = gbuff[2];
	tbuff[1] = gbuff[3];
	tbuff[2] = '\0';
	GPSTmon = atoi(tbuff);
	tbuff[0] = gbuff[4];
	tbuff[1] = gbuff[5];
	tbuff[2] = '\0';
	GPSTyear = atoi(tbuff);
}

void nmeaProcessGPRMC2_debug(char* packet)
{
	/*uint8_t i;
	uint8_t GPIndex=0;
	char gbuff[6];
	uint8_t helpidx=0;


	//start parsing just after "GPRMC,"
	i = 7;
	// attempt to reject empty packets right away
	if(packet[i]==',' && packet[i+1]==',')
		return;

	// get UTC time [hhmmss.sss]
	//int8_t scanlimit = 6;
	while(packet[i] != ',')				// next field: Time -> deactivated -> is parsed at GPGSA-sentence
	{
		//if(scanlimit > 0)
		//{
		//	GPSTime[GPIndex]=packet[i];
		//	i++;
		//	GPIndex++;
		//	scanlimit--;
		//}
		//else
		//{
			i++;
		//}
	}
	//GPSTime[GPIndex]= '\0';

	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field: Navigation warning
	{
		if(i >= GPSBUFFSIZE || GPIndex > 2)
		{
			huart_puts("XK!");
			huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
	GPSStatus = packet[i];
	i++;
	GPIndex++;
	}

	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field:Latitude
	{
		if(i >= GPSBUFFSIZE || GPIndex > 9)
		{
			huart_puts("XL!");
			huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
	Lat[GPIndex]=packet[i];
	i++;
	GPIndex++;
	}
	Lat[GPIndex]= '\0';

	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field:N/S
	{
	//NS[GPIndex]=packet[i];
		if(i >= GPSBUFFSIZE || GPIndex > 7)
		{
			huart_puts("XM!");
			huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
	NS = packet[i];
	i++;
	GPIndex++;
	}
	//NS[GPIndex]= '\0';


	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field:Longitude
	{
		if(i >= GPSBUFFSIZE || GPIndex > 10)
		{
			huart_puts("XN!");
			huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
	Long[GPIndex]=packet[i];
	i++;
	GPIndex++;
	}
	Long[GPIndex]= '\0';

	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field:E/W
	{
	//EW[GPIndex]=packet[i];
		if(i >= GPSBUFFSIZE || GPIndex > 7)
		{
			huart_puts("XO!");
			huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
	EW = packet[i];
	i++;
	GPIndex++;
	}
	//EW[GPIndex]= '\0';

	i++;
	GPIndex=0;
	helpidx=0;

	// get
	while(packet[i] != ',')				// next field: speed
	{
		if(i >= GPSBUFFSIZE || GPIndex > 5 || helpidx > 5)
		{
			huart_puts("XP!");
			huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
		Speed[GPIndex]=packet[i];
		gbuff[helpidx]=packet[i];
		i++;
		GPIndex++;
		if(packet[i] != '.')
			helpidx++;
	}
	Speed[GPIndex]= '\0';
	gbuff[helpidx]= '\0';
	//convert to int representation iSpeed
	iSpeed = atoi(gbuff);

	i++;
	GPIndex=0;
	helpidx=0;
	while(packet[i] != ',')				// next field:Course made good
	{
		if(i >= GPSBUFFSIZE || GPIndex > 6)
		{
			huart_puts("XQ!");
			huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
		Heading[GPIndex]=packet[i];
		gbuff[helpidx]=packet[i];
		i++;
		GPIndex++;
		if(packet[i] != '.')
			helpidx++;
	}
	Heading[GPIndex]= '\0';
	gbuff[helpidx]= '\0';
	//convert to int representation iHeading
	iHeading = atoi(gbuff);

	i++;
	GPIndex=0;
	while(packet[i] != ',')				// next field:Date
	{
		if(i >= GPSBUFFSIZE || GPIndex > 5)
		{
			huart_puts("XR!");
			huart_puts("\r\n");
			return; //stop parsing as something seems to be gone wrong
		}
		gbuff[GPIndex]=packet[i];
		i++;
		GPIndex++;
	}
	//GPSDate[GPIndex]= '\0';
	//parse time to vars
	tbuff[0] = gbuff[0];
	tbuff[1] = gbuff[1];
	tbuff[2] = '\0';
	GPSTday = atoi(tbuff);
	tbuff[0] = gbuff[2];
	tbuff[1] = gbuff[3];
	tbuff[2] = '\0';
	GPSTmon = atoi(tbuff);
	tbuff[0] = gbuff[4];
	tbuff[1] = gbuff[5];
	tbuff[2] = '\0';
	GPSTyear = atoi(tbuff);

	utoa(i,tbuff,10);
	huart_puts("3x");
	huart_puts(tbuff);
	huart_puts("\r\n");*/
}

uint8_t nmea_Parse(void)//(cBuffer* rxBuffer)
{
		uint8_t foundpacket = NMEA_NODATA;

//
						//uint8_t len = strlen(okbuffer);
						/*if(len > 50)
						{
						huart_puts("XLEN");
						utoa(len,tbuff,10);
						huart_puts(tbuff);
						huart_puts("\r\n");
						}	*/
						//

		// check message type and process appropriately
		if(!strncmp(okbuffer,"$GPGGA", 6))
		{
			// process packet of this type
			parsing_in_progress = 1;
			nmeaProcessGPGGA2((char *)okbuffer);
			// report packet type
			foundpacket = NMEA_GPGGA;
		}
		else if(!strncmp(okbuffer, "$GPRMC", 6))
		{
			// process packet of this type
			parsing_in_progress = 1;
			nmeaProcessGPRMC2((char *)okbuffer);
			// report packet type
			foundpacket = NMEA_GPRMC;
		}
		else if(!strncmp(okbuffer, "$GPGSV", 6))
		{
			// process packet of this type
			parsing_in_progress = 1;
			nmeaProcessGPGSV2((char *)okbuffer);
			// report packet type
			foundpacket = NMEA_GPGSV;
		}
		parsing_in_progress = 0;
		return foundpacket;
}

void submit_essential_gps_data()
{
	huart_puts("@GPS@");
	utoa(lat_deg,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(lat_min,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(lat_sec,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(long_deg,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(long_min,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(long_sec,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	huart_puts(Speed);
	huart_putc(',');
	huart_puts(Heading);
	huart_putc(',');
	huart_putc(EW);
	huart_putc(',');
	huart_putc(NS);
	huart_putc(',');
	huart_putc(FixQuality);
	huart_putc(',');
	huart_putc(GPSStatus);
	huart_putc(',');
	utoa(SatsinView,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(UsedSatellites,tbuff,10);
	huart_puts(tbuff);
	huart_puts("\r\n");
}

void submit_parsed_gps_data()
{
	/*huart_puts("\r\n");
	huart_puts("Long: ");
	huart_puts(Long);
	huart_puts("\r\n");
	huart_puts("Lat: ");
	huart_puts(Lat);
	huart_puts("\r\n");
	huart_puts("Time: ");
	//huart_puts(GPSTime);
	//huart_puts(" ");
	utoa(GPSThour,tbuff,10);
	huart_puts(tbuff);
	huart_putc(':');
	utoa(GPSTmin,tbuff,10);
	huart_puts(tbuff);
	huart_putc(':');
	utoa(GPSTsec,tbuff,10);
	huart_puts(tbuff);
	huart_puts("\r\n");
	huart_puts("NS: ");
	huart_putc(NS);
	huart_puts("\r\n");
	huart_puts("EW: ");
	huart_putc(EW);
	huart_puts("\r\n");
	huart_puts("Fix: ");
	//itoa(FixQuality,tbuff,10);
	//huart_puts(tbuff);
	huart_putc(FixQuality);
	huart_puts("\r\n");
	huart_puts("Alt: ");
	huart_puts(Altitude);
	huart_puts("\r\n");
	huart_puts("Spd: ");
	huart_puts(Speed);
	huart_puts("\r\n");
	huart_puts("Hdg: ");
	huart_puts(Heading);
	huart_puts("\r\n");
	huart_puts("Date: ");
	//huart_puts(GPSDate);
	//huart_puts(" ");
	utoa(GPSTday,tbuff,10);
	huart_puts(tbuff);
	huart_putc('.');
	utoa(GPSTmon,tbuff,10);
	huart_puts(tbuff);
	huart_putc('.');
	utoa(GPSTyear,tbuff,10);
	huart_puts(tbuff);
	huart_puts("\r\n");
	huart_puts("HDOP: ");
	utoa(HDOP,tbuff,10);
	huart_puts(tbuff);
	huart_puts("\r\n");
	huart_puts("State: ");
	huart_putc(GPSStatus);
	huart_puts("\r\n");
	huart_puts("SaU: ");
	utoa(UsedSatellites,tbuff,10);
	huart_puts(tbuff);
	huart_puts("\r\n");
	huart_puts("Londeg: ");
	utoa(long_deg,tbuff,10);
	huart_puts(tbuff);
	huart_puts("\r\n");
	huart_puts("Lonm: ");
	utoa(long_min,tbuff,10);
	huart_puts(tbuff);
	huart_puts("\r\n");
	huart_puts("Lons: ");
	utoa(long_sec,tbuff,10);
	huart_puts(tbuff);
	huart_puts("\r\n");
	huart_puts("Latdeg: ");
	utoa(lat_deg,tbuff,10);
	huart_puts(tbuff);
	huart_puts("\r\n");
	huart_puts("Latm: ");
	utoa(lat_min,tbuff,10);
	huart_puts(tbuff);
	huart_puts("\r\n");
	huart_puts("Lats: ");
	utoa(lat_sec,tbuff,10);
	huart_puts(tbuff);
	huart_puts("\r\n");
	huart_puts("SiV: ");
	utoa(SatsinView,tbuff,10);
	huart_puts(tbuff);
	huart_puts("\r\n");*/
}

void submit_countjob_status()
{
	huart_puts("\r\n");
	huart_puts("@CNT@");
	utoa(cj1_d1,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(cj1_d2,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(cj1_d3,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(cj2_d1,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(cj2_d2,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(cj2_d3,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(cj3_d1,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(cj3_d2,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(cj3_d3,tbuff,10);
	huart_puts(tbuff);
	huart_putc(',');
	utoa(cj_active,tbuff,10);
	huart_puts(tbuff);
	huart_puts("\r\n");
}

void vardelay(double ms)
{
	while(ms > 0)
	{
		_delay_ms(1);
		ms--;
	}
}

void pwm_init()
{
	TCCR0 |= (1 << COM01) | (1 << COM00) | (1 << WGM00) | (1 << CS02);
	OCR0 = pwm_g_startval;
	DDRB |= (1 << PB3);
}

void switch_gas_pwm(uint8_t onoff)
{
	if(onoff == 1)
	{
		TCCR0 |= (1 << COM01) | (1 << COM00) | (1 << WGM00) | (1 << CS02);
	}
	else
	{
		TCCR0 &= ~((1 << COM01) | (1 << COM00));
	}
}

void pwm2_init()
{
	if(motor_allowed == 0)
	{
		TCCR2 &= ~((1 << CS20) | (1 << CS21) | (1 << CS22) | (1 << COM21) | (1 << COM20));
		if(steeringmode == 1)
			PORTD |= (1<<PD7); //set high because otherwise motor would stay permanent on
		else
			PORTD &= ~(1<<PD7);
	}
	else
	{
		if(steeringmode == 1) //non inverting pwm if relais used, inverted if motor driver used (as pwm is inverted on driver board)
		{
			TCCR2 |= (1<<COM20);
		}
		else
		{
			TCCR2 &= ~(1<<COM20);
		}

		switch(pwm_l_prescaler)
		{
			case 0:
			{
				//Prescaler 256
				TCCR2 &= ~(1 << CS20);
				TCCR2 |= (1 << WGM20) | (1 << WGM21) | (1 << COM21) | (1 << CS22) | (1 << CS21);
				break;
			}
			case 2:
			{
				//Prescaler 64
				TCCR2 &= ~( (1 << CS21) | (1 << CS20) );
				TCCR2 |= (1 << WGM20) | (1 << WGM21) | (1 << COM21) | (1 << CS22);
				break;
			}
			case 3:
			{
				//Prescaler 32
				TCCR2 &= ~(1 << CS22);
				TCCR2 |= (1 << WGM20) | (1 << WGM21) | (1 << COM21) | (1 << CS20) | (1 << CS21);
				break;
			}
			case 4:
			{
				//Prescaler 8
				TCCR2 &= ~((1 << CS22) | (1 << CS20));
				TCCR2 |= (1 << WGM20) | (1 << WGM21) | (1 << COM21) | (1 << CS21);
				break;
			}
			case 5:
			{
				//Prescaler 1
				TCCR2 &= ~((1 << CS22) | (1 << CS21));
				TCCR2 |= (1 << WGM20) | (1 << WGM21) | (1 << COM21) | (1 << CS20);
				break;
			}
			default:
			{
				//Prescaler 128
				TCCR2 &= ~(1 << CS21);
				TCCR2 |= (1 << WGM20) | (1 << WGM21) | (1 << COM21) | (1 << CS22) | (1 << CS20);
			}
		}
	}
	OCR2 = pwm_l_startval;
	DDRD |=	(1 << PD7);
}

void USART_Flush( void )
{
	unsigned char dummy;
	while ( UCSRA & (1<<RXC) ) dummy = UDR;
}

void start_countjob1(char count, char reset)
{
	if(cj_active != 1 && cj_active != 3 && cj_active != 5 && cj_active != 7 )
	{
		if(reset == 1)
		{
			cj1_d3 = CJ_d3_DEFAULT;
			cj1_d2 = CJ_d2_DEFAULT;
		}
		cj1_d1 = count;
		cj_active += 1;
	}
}

void start_countjob2(uint16_t count, char reset)
{
	if(cj_active != 2 && cj_active != 3 && cj_active != 6 && cj_active != 7)
	{
		if(reset == 1)
		{
			cj2_d3 = CJ_d3_DEFAULT;
			cj2_d2 = CJ_d2_DEFAULT;
		}
		cj2_d1 = count;
		cj_active += 2;
	}
}
void start_countjob3(char count, char reset)
{
	if(cj_active != 4 && cj_active != 5 && cj_active != 6 && cj_active != 7)
	{
		if(reset == 1)
		{
			//cj3_d3 = CJ_d3_DEFAULT;
			cj3_d2 = CJ_d2_DEFAULT;
		}
		cj3_d1 = count;
		cj_active += 4;
	}
}

void stop_countjob1()
{
	cj_active -= 1;
}

void stop_countjob2()
{
	cj_active -= 2;
}

void stop_countjob3()
{
	cj_active -= 4;
}

void cmd_recognized(uint8_t reco)
{
	if(reco == 1)
	{
		huart_puts("\r\n");
		huart_putc('O');
		huart_putc('K');
		huart_puts("\r\n");
	}
	else if(reco == 2)
	{
		huart_puts("\r\n");
		huart_putc('N');
		huart_putc('A');
		huart_putc('N');
		huart_puts("\r\n");
		USART_Flush();
		lastchar = 0;
	}
	else if(reco == 3)
	{
		huart_puts("\r\n");
		huart_putc('O');
		huart_putc('O');
		huart_putc('R');
		huart_puts("\r\n");
		USART_Flush();
		lastchar = 0;
	}
	else
	{
		huart_puts("\r\n");
		huart_putc('?');
		huart_putc('?');
		huart_puts("\r\n");
		USART_Flush();
		lastchar = 0;
	}
}

/* ADC Einzelmessung */
uint8_t ADC_Read( uint8_t channel )
{
  //Falls ADC-Ergebnis nicht links adjustiert ADCW retourgeben und rückgabewert auf uint16_t ändern
  // Kanal waehlen, ohne andere Bits zu beeinflußen
  ADMUX = (ADMUX & ~(0x1F)) | (channel & 0x1F);
  ADCSRA |= (1<<ADSC);            // eine Wandlung "single conversion"
  while (ADCSRA & (1<<ADSC) ) {}  // auf Abschluss der Konvertierung warten
  return ADCH;                    // ADC auslesen und zurückgeben
}


char is_num(char c)
{
	if(c>47 && c<58)
	{
		return 1;
	}
	else
	{
		return 0;
	}
}

void set_manual_override(uint8_t state)
{
	if(state == 0 && manual_override == 1) //used to deactivate both relais and pwm when manual override is finished
	{
		motor_allowed = 0;
		pwm2_init();
		PORTD &= ~(1 << PD4);
		PORTB &= ~(1 << PB4);
	}
	manual_override = state;
}

void set_direction_pin(unsigned char direction)
{
	if(direction == 'l')
	{
		PORTC |= (1<<PC4);
	}
	else
	{
		PORTC &= ~(1<<PC4);
	}
}

void prepare_steer_motor(uint8_t onoff, unsigned char direction)
{
	if(steeringmode == 1)
	{
		if(onoff == 1)
		{
			set_direction_pin(direction);
			motor_allowed = 1;
		}
		else
		{
			motor_allowed = 0;
		}
		pwm2_init();
	}
	else
	{
		if(onoff == 1)
		{
			motor_allowed = 1;
		}
		else
		{
			motor_allowed = 0;
		}
		pwm2_init();
	}
}

void steer(uint8_t xon, unsigned char direction)
{
	if(direction == 'l')
	{
		if(xon == 1)
		{
			if(finalpos_reached != 1)
			{
				prepare_steer_motor(1,direction);
				PORTB |= (1 << PB4); //activate relais, deactivate other relais
				PORTD &= ~(1 << PD4);
			}
		}
		else
		{
			prepare_steer_motor(0,direction);
			//PORTB &= ~(1 << PB4);
		}
	}
	else if(direction == 'r')
	{
		if(xon == 1)
		{
			if(finalpos_reached != 2)
			{
				prepare_steer_motor(1,direction);
				PORTD |= (1 << PD4); //activate relais, deactivate other relais
				PORTB &= ~(1 << PB4);
			}
		}
		else
		{
			prepare_steer_motor(0,direction);
			//PORTD &= ~(1 << PD4);
		}
	}
	else
	{
		huart_puts("dir?");
		huart_puts("\r\n");
	}
}

void steer_pulse(unsigned char direction)
{
	unsigned char steps = l_stepdur;
	steer(1,direction);
	while(steps > 0)
	{
		_delay_ms(10);
		if(!(PIND & (1 << PIND3)) && direction == 'r')
		{
			//immediate stop, reached full travel right
			break;
		}
		if(!(PIND & (1 << PIND2)) && direction == 'l')
		{
			//immediate stop, reached full travel left
			break;
		}
		steps--;
	}
	steer(0,direction);
}

void reset()
{
	huart_puts("XXX");
	wdt_enable(WDTO_15MS);
	while(1) {};
}

void factory_reset_cmps10()
{
	/*uint8_t xstate = 0;
	xstate = i2c_start(CMPS10+I2C_WRITE);       // set device address and write mode
	if ( xstate )
	{
        // failed to issue start condition, possibly no device found
        i2c_stop();
		huart_puts("FRERR");
		huart_puts("\r\n");
		_delay_ms(1000);
    }
	else
	{
		i2c_write(22);
		i2c_write(0x20);
		i2c_stop();
		_delay_ms(100);
		xstate = i2c_start(CMPS10+I2C_WRITE);       // set device address and write mode
		if ( xstate )
		{
			// failed to issue start condition, possibly no device found
			i2c_stop();
			huart_puts("FRERR");
			huart_puts("\r\n");
			_delay_ms(1000);
		}
		else
		{
			i2c_write(22);
			i2c_write(0x2A);
			i2c_stop();
			_delay_ms(100);
			xstate = i2c_start(CMPS10+I2C_WRITE);       // set device address and write mode
			if ( xstate )
			{
				// failed to issue start condition, possibly no device found
				i2c_stop();
				huart_puts("FRERR");
				huart_puts("\r\n");
				_delay_ms(1000);
			}
			else
			{
				i2c_write(22);
				i2c_write(0x60);
				i2c_stop();
				huart_puts("FRDONE");
				huart_puts("\r\n");
			}
		}
	}*/
	_delay_ms(1000);
}

void parse_X_cmd()
{
	switch(cmda[1])
	{
		case 'X':
		{
			if(cmda[2] == 'r' && cmda[3] == 'e')
			{
				if(cmda[4] == 's') //Factory reset CMPS10
				{
					reset();
					cmd_recognized(1);
				}
				else
				{
					cmd_recognized(0);
				}
			}
			else
			{
				cmd_recognized(0);
			}
			break;
		}
		case 'C':
		{
			if(cmda[2] == 'f' && cmda[3] == 'a')
			{
				if(cmda[4] == 'c') //Factory reset CMPS10
				{
					factory_reset_cmps10();
					cmd_recognized(1);
				}
				else
				{
					cmd_recognized(0);
				}
			}
			else
			{
				cmd_recognized(0);
			}
			break;
		}
		case 'R':
		{
			if(cmda[2] == 'i' && cmda[3] == '2')
			{
				if(cmda[4] == 'c') //XRi2c used fr testing...
				{
					//test something
					submit_parsed_gps_data();
					cmd_recognized(1);
				}
				else
				{
					cmd_recognized(0);
				}
			}
			else if(cmda[2] == 'l' && cmda[3] == 'i')
			{
				if(cmda[4] == 'p')
				{
					steer_pulse('l');
					cmd_recognized(1);
				}
				else if(cmda[4] == 'e')
				{
					steer(1,'l');
					cmd_recognized(1);
				}
				else if (cmda[4] == 'a')
				{
					steer(0,'l');
					cmd_recognized(1);
				}
				else
				{
					cmd_recognized(0);
				}
			}
			else if(cmda[2] == 'r' && cmda[3] == 'e')
			{
				if(cmda[4] == 'p')
				{
					steer_pulse('r');
					cmd_recognized(1);
				}
				else if(cmda[4] == 'e')
				{
					steer(1,'r');
					cmd_recognized(1);
				}
				else if (cmda[4] == 'a')
				{
					steer(0,'r');
					cmd_recognized(1);
				}
				else
				{
					cmd_recognized(0);
				}
			}
			else
			{
				cmd_recognized(0);
			}
			break;
		}
		case 'P':
		{
			if(cmda[2] == 'e' && cmda[3] == 'i' && cmda[4] == 'n')
			{
				PORTD |= (1 << PD5);
				cmd_recognized(1);
			}
			else if(cmda[2] == 'a' && cmda[3] == 'u' && cmda[4] == 's')
			{
				PORTD &= ~(1 << PD5);
				cmd_recognized(1);
			}
			else
			{
				cmd_recognized(0);
			}
			break;
		}
		default:
		{
			cmd_recognized(0);
			break;
		}
	}
}

void parse_R_cmd()
{
	switch(cmda[1])
	{
		case 'G':
		{
			if(cmda[2] == 'e')
			{
				//GPS ein
				gps_active = 1;
				cmd_recognized(1);
			}
			else if(cmda[2] == 'a')
			{
				//GPS aus
				gps_active = 0;
				cmd_recognized(1);
			}
			else if(cmda[2] == 'E')
			{
				//GPS output ein
				gps_output_active = 1;
				cmd_recognized(1);
			}
			else if(cmda[2] == 'A')
			{
				//GPS output aus
				gps_output_active = 0;
				cmd_recognized(1);
			}
			else
			{
				cmd_recognized(0);
			}
			break;
		}
		case 'E':
		{
			if(cmda[2] == 'e')
			{
				//I2C errorausgabe ein
				i2c_errors_active = 1;
				cmd_recognized(1);
			}
			else if(cmda[2] == 'a')
			{
				//I2C errorausgabe aus
				i2c_errors_active = 0;
				cmd_recognized(1);
			}
			else
			{
				cmd_recognized(0);
			}
			break;
		}
		case 'I':
		{
			if(cmda[2] == 'e')
			{
				//I2C ein
				i2c_active = 1;
				cmd_recognized(1);
			}
			else if(cmda[2] == 'a')
			{
				//I2C aus
				i2c_active = 0;
				cmd_recognized(1);
			}
			else
			{
				cmd_recognized(0);
			}
			break;
		}
		case 'A':
		{
			if(cmda[2] == 'e' && cmda[3] == 'i' && cmda[4] == 'n')
			{
				//Status AdcValues
				huart_puts("\r\n");
				huart_puts("@AIN@");
				utoa(ADC_Read(0),tbuff,10);
				huart_puts(tbuff);
				huart_putc(',');
				utoa(ADC_Read(1),tbuff,10);
				huart_puts(tbuff);
				huart_putc(',');
				utoa(ADC_Read(2),tbuff,10);
				huart_puts(tbuff);
				huart_putc(',');
				utoa(ADC_Read(3),tbuff,10);
				huart_puts(tbuff);
				huart_putc(',');
				utoa(ADC_Read(4),tbuff,10);
				huart_puts(tbuff);
				huart_putc(',');
				utoa(ADC_Read(5),tbuff,10);
				huart_puts(tbuff);
				huart_putc(',');
				utoa(ADC_Read(6),tbuff,10);
				huart_puts(tbuff);
				huart_putc(',');
				utoa(ADC_Read(7),tbuff,10);
				huart_puts(tbuff);
				huart_puts("\r\n");
				cmd_recognized(1);
			}
			else
			{
				cmd_recognized(0);
			}
			break;
		}
		case 'S':
		{
			if(cmda[2] == 'e' && cmda[3] == 'p' && cmda[4] == 'r')
			{
				read_settings_from_eeprom();
				cmd_recognized(1);
			}
			else if(cmda[2] == 'r' && cmda[3] == 'a' && cmda[4] == 'm')
			{
				read_settings_from_ram();
				cmd_recognized(1);
			}
			else
			{
				cmd_recognized(0);
			}
			break;
		}
		case 'R':
		{
			if(cmda[2] == 'd' && cmda[3] == 'd' && cmda[4] == 'r')
			{
				//Status DataDirectionRegister
				huart_puts("\r\n");
				huart_puts("@DDR@");
				utoa(DDRA,tbuff,10);
				huart_puts(tbuff);
				huart_putc(',');
				utoa(DDRB,tbuff,10);
				huart_puts(tbuff);
				huart_putc(',');
				utoa(DDRC,tbuff,10);
				huart_puts(tbuff);
				huart_putc(',');
				utoa(DDRD,tbuff,10);
				huart_puts(tbuff);
				huart_puts("\r\n");
				cmd_recognized(1);
			}
			else
			{
				cmd_recognized(0);
			}
			break;
		}
		case 'D':
		{
			if(cmda[2] == 'e')
			{
				//Status Digitaleingaenge
				huart_puts("\r\n");
				huart_puts("@DIN@");
				utoa(PINA,tbuff,10);
				huart_puts(tbuff);
				huart_putc(',');
				utoa(PINB,tbuff,10);
				huart_puts(tbuff);
				huart_putc(',');
				utoa(PINC,tbuff,10);
				huart_puts(tbuff);
				huart_putc(',');
				utoa(PIND,tbuff,10);
				huart_puts(tbuff);
				huart_puts("\r\n");
				cmd_recognized(1);
			}
			else if(cmda[2] == 'a')
			{
				//Status Digitalausgaenge
				huart_puts("\r\n");
				huart_puts("@DOUT@");
				utoa(PORTA,tbuff,10);
				huart_puts(tbuff);
				huart_putc(',');
				utoa(PORTB,tbuff,10);
				huart_puts(tbuff);
				huart_putc(',');
				utoa(PORTC,tbuff,10);
				huart_puts(tbuff);
				huart_putc(',');
				utoa(PORTD,tbuff,10);
				huart_puts(tbuff);
				huart_puts("\r\n");
				cmd_recognized(1);

				/*utoa(cj1_d3,tbuff,10);
				huart_puts(tbuff);
				//huart_puts("\r\n");
				utoa(cj1_d2,tbuff,10);
				huart_puts(tbuff);
				//huart_puts("\r\n");
				utoa(cj2_d3,tbuff,10);
				huart_puts(tbuff);
				//huart_puts("\r\n");
				utoa(cj2_d2,tbuff,10);
				huart_puts(tbuff);
				//huart_puts("\r\n");*/
			}
			else
			{
				cmd_recognized(0);
			}
			break;
		}
		case 'V':
		{
			if(cmda[2] == 'v' && cmda[3] == 'a' && cmda[4] == 'r')
			{
				submit_runtime_vars();
				cmd_recognized(1);
			}
			else if(cmda[2] == 'c' && cmda[3] == 'n' && cmda[4] == 't')
			{
				submit_countjob_status();
				cmd_recognized(1);
			}
			else if(cmda[2] == 'u' && cmda[3] == 'e' && cmda[4] == 'b')
			{
				submit_ueberw_status();
				cmd_recognized(1);
			}
			else
			{
				cmd_recognized(0);
			}
			break;
		}
		default:
		{
			cmd_recognized(0);
			break;
		}
	}
}

void parse_S_cmd()
{
	unsigned char temp[5];
	uint8_t tempval = 0;
	switch(cmda[1])
	{
		case 'G':
		{
			if(is_num(cmda[2]) && is_num(cmda[3]) && is_num(cmda[4]) && is_num(cmda[5]))
			{
				temp[0] = cmda[2];
				temp[1] = cmda[3];
				temp[2] = cmda[4];
				temp[3] = cmda[5];
				temp[4] = '\0';
				tempval = atoi(temp);
				if(tempval > gas_trim_high)
				{
					OCR0 = gas_trim_high;
					cmd_recognized(3);
				}
				else if(tempval < gas_trim_low)
				{
					OCR0 = gas_trim_low;
					cmd_recognized(3);
				}
				else
				{
					OCR0 = tempval;
					pwm_g_startval = tempval;
					cmd_recognized(1);
				}
			}
			else
			{
				cmd_recognized(2);
			}
			break;
		}
		case 'L':
		{
			if(is_num(cmda[2]) && is_num(cmda[3]) && is_num(cmda[4]) && is_num(cmda[5]))
			{
			temp[0] = cmda[2];
			temp[1] = cmda[3];
			temp[2] = cmda[4];
			temp[3] = cmda[5];
			temp[4] = '\0';
			pwm_l_startval = atoi(temp);
			OCR2 = pwm_l_startval;
			cmd_recognized(1);
			}
			else
			{
				cmd_recognized(2);
			}
			break;
		}
		case 'S':
		{
			if(cmda[2] == 'p' && cmda[3] == 's' && cmda[4] == 'c')
			{
				if(cmda[5] > 47 && cmda[5] < 54)
				{
					pwm_l_prescaler = ((unsigned char)cmda[5])-48;
					pwm2_init();
					cmd_recognized(1);
				}
				else
				{
					cmd_recognized(0);
				}
			}
			else if(cmda[2] == 's' && cmda[3] == 'a' && cmda[4] == 'v' && cmda[5] == 'e' )
			{
				save_settings_to_eeprom();
				cmd_recognized(1);
			}
			else if(cmda[2] == 's' && is_num(cmda[3]) && is_num(cmda[4]) && is_num(cmda[5]))
			{
				temp[0] = '0';
				temp[1] = cmda[3];
				temp[2] = cmda[4];
				temp[3] = cmda[5];
				temp[4] = '\0';
				l_stepdur = atoi(temp);
				cmd_recognized(1);
			}
			else
			{
				cmd_recognized(0);
			}
			break;
		}
		case 'T':
		{
			if(cmda[2] == 'l' && cmda[3] == 'o' && cmda[4] == 'w')
			{
				gas_trim_low = OCR0;
				cmd_recognized(1);
			}
			else if(cmda[2] == 'h' && cmda[3] == 'i' && cmda[4] == 'g')
			{
				gas_trim_high = OCR0;
				cmd_recognized(1);
			}
			else if(cmda[2] == 'r' && cmda[3] == 'e' && cmda[4] == 's')
			{
				gas_trim_high = 255;
				gas_trim_low = 0;
				cmd_recognized(1);
			}
			else
			{
				cmd_recognized(0);
			}
			break;
		}
		case 'P':
		{
			if(cmda[2] == 'd' && cmda[3] == 'e' && cmda[4] == 'a')
			{
				autopump_active = 0;
				cmd_recognized(1);
			}
			else if(cmda[2] == 'a' && cmda[3] == 'c' && cmda[4] == 't')
			{
				autopump_active = 1;
				cmd_recognized(1);
			}
			else
			{
				cmd_recognized(0);
			}
			break;
		}
		case 'M':
		{
			if(cmda[2] == 'a' && cmda[3] == 'c' && cmda[4] == 't')
			{
				set_manual_override(1);
				manual_phone_override = 1;
				cmd_recognized(1);
			}
			else if(cmda[2] == 'd' && cmda[3] == 'e' && cmda[4] == 'a')
			{
				set_manual_override(0);
				manual_phone_override = 0;
				cmd_recognized(1);
			}
			else
			{
				cmd_recognized(0);
			}
			break;
		}
		case 'C':
		{
			if(cmda[2] == 'a' && is_num(cmda[3]) && is_num(cmda[4]) && is_num(cmda[5]))
			{
				temp[0] = '0';
				temp[1] = cmda[3];
				temp[2] = cmda[4];
				temp[3] = cmda[5];
				temp[4] = '\0';
				cj3_d3 = atoi(temp);
				start_countjob3(cj3_d3,1);
				cmd_recognized(1);
			}
			else if(cmda[2] == 'd' && cmda[3] == 'e' && cmda[4] == 'a')
			{
				stop_countjob3();
				cmd_recognized(1);
			}
			else
			{
				cmd_recognized(0);
			}
			break;
		}
		case 'R':
		{
			if(cmda[2] == 'r' && is_num(cmda[3]) && is_num(cmda[4]) && is_num(cmda[5]))
			{
				temp[0] = '0';
				temp[1] = cmda[3];
				temp[2] = cmda[4];
				temp[3] = cmda[5];
				temp[4] = '\0';
				rgb_red = atoi(temp);
				cmd_recognized(1);
			}
			else if(cmda[2] == 'g' && is_num(cmda[3]) && is_num(cmda[4]) && is_num(cmda[5]))
			{
				temp[0] = '0';
				temp[1] = cmda[3];
				temp[2] = cmda[4];
				temp[3] = cmda[5];
				temp[4] = '\0';
				rgb_green = atoi(temp);
				cmd_recognized(1);
			}
			else if(cmda[2] == 'b' && is_num(cmda[3]) && is_num(cmda[4]) && is_num(cmda[5]))
			{
				temp[0] = '0';
				temp[1] = cmda[3];
				temp[2] = cmda[4];
				temp[3] = cmda[5];
				temp[4] = '\0';
				rgb_blue = atoi(temp);
				cmd_recognized(1);
			}
			else if(cmda[2] == 'a' && is_num(cmda[3]) && is_num(cmda[4]) && is_num(cmda[5]))
			{
				temp[0] = '0';
				temp[1] = cmda[3];
				temp[2] = cmda[4];
				temp[3] = cmda[5];
				temp[4] = '\0';
				rgb_blue = atoi(temp);
				rgb_green = rgb_blue;
				rgb_red = rgb_blue;
				cmd_recognized(1);
			}
			else if(cmda[2] == 't' && is_num(cmda[3]) && is_num(cmda[4]) && is_num(cmda[5]))
			{
				temp[0] = cmda[3];
				temp[1] = cmda[4];
				temp[2] = cmda[5];
				temp[3] = '\0';
				tempval = atoi(temp);
				rgb_test = tempval;
				cmd_recognized(1);
			}
			else if(cmda[2] == 's' && is_num(cmda[3]) && is_num(cmda[4]) && is_num(cmda[5]))
			{
				temp[0] = cmda[3];
				temp[1] = cmda[4];
				temp[2] = cmda[5];
				temp[3] = '\0';
				tempval = atoi(temp);
				rgb_sound = tempval;
				cmd_recognized(1);
			}
			else
			{
				cmd_recognized(0);
			}
			break;
		}
		default:
		{
			cmd_recognized(0);
			break;
		}
	}
}

void build_cmd(unsigned char cmd)
{
	if(cmd == 6) //skip ack char from WP8
	{

	}
	else
	{
		huart_putc(cmd);
		if(parsing_in_progress == 1)
		{
			huart_puts("!!");
			lastchar = 0;
			return;
		}
		//utoa(lastchar,tbuff,10);
		//huart_puts(tbuff);
		if(lastchar >= 5)
		{
			cmda[lastchar] = cmd;
			/*huart_putc('#');
			huart_putc(cmda[0]);
			huart_putc(cmda[1]);
			huart_putc(cmda[2]);
			huart_putc(cmda[3]);
			huart_putc(cmda[4]);
			huart_putc(cmda[5]);
			huart_putc('#');*/
			switch(cmda[0])
			{
				case 'X':
				{
					parse_X_cmd();
					break;
				}
				case 'R':
				{
					parse_R_cmd();
					break;
				}
				case 'S':
				{
					parse_S_cmd();
					break;
				}
				default:
				{
					cmd_recognized(0);
					break;
				}
			}
			lastchar = 0;
		}
		else
		{
			cmda[lastchar] = cmd;
			lastchar++;
		}
	}
}




ISR( USART_RXC_vect,ISR_BLOCK)
{
	//char aktchar = UDR;
	build_cmd(UDR);
	//huart_puts((char*) *cmda);
	//huart_puts("\r\n");
	/*if(lastchar != 0)
	{
		huart_putc(lastchar);
		huart_putc(aktchar);
		doit2(lastchar,aktchar);
		lastchar = 0;
	}
	else
	{
		huart_putc(aktchar);
		huart_putc('.');
		lastchar = aktchar;
	}*/
}

void countjob1_finished()
{
	huart_puts("cj1");
	huart_puts("\r\n");
	pumping_forbidden = 1;

}

void countjob2_finished()
{
	huart_puts("cj2");
	huart_puts("\r\n");
	pumping_forbidden = 0;
}

void countjob3_finished()
{
	//send infos
	submit_countjob_status();
	submit_runtime_vars();
	start_countjob3(cj3_d3,1);
}

void do_count()
{
		//COUNTJOB 1
		if(cj_active == 1 || cj_active == 3 || cj_active == 5 || cj_active == 7)
		{
			if(cj1_d3 > 0)
			{
				cj1_d3--;
			}
			else
			{
				cj1_d3 = CJ_d3_DEFAULT;
				if(cj1_d2 > 0)
				{
					cj1_d2--;
				}
				else
				{
					cj1_d2 = CJ_d2_DEFAULT;
					if(cj1_d1 > 1)
					{
						cj1_d1--;
					}
					else
					{
						cj_active -= 1;
						countjob1_finished();
					}
				}
			}
		}

		//COUNTJOB 2
		if(cj_active == 2 || cj_active == 3 || cj_active == 6 || cj_active == 7)
		{
			if(cj2_d3 > 0)
			{
				cj2_d3--;
			}
			else
			{
				cj2_d3 = CJ_d3_DEFAULT;
				if(cj2_d2 > 0)
				{
					cj2_d2--;
				}
				else
				{
					cj2_d2 = CJ_d2_DEFAULT;
					if(cj2_d1 > 1)
					{
						cj2_d1--;
					}
					else
					{
						cj_active -= 2;
						countjob2_finished();
					}
				}
			}
		}

		//COUNTJOB 3
		if(cj_active == 4 || cj_active == 5 || cj_active == 6 || cj_active == 7)
		{
			/*if(cj3_d3 > 0)
			{
				cj3_d3--;
			}
			else
			{
				cj3_d3 = CJ_d3_DEFAULT;*/
				if(cj3_d2 > 0)
				{
					cj3_d2--;
				}
				else
				{
					cj3_d2 = CJ_d2_DEFAULT;
					if(cj3_d1 > 1)
					{
						cj3_d1--;
					}
					else
					{
						cj_active -= 4;
						countjob3_finished();
					}
				}
			//}
		}
}

ISR(TIMER0_OVF_vect)
{
	//CountJobs
	do_count();
	remote_iv++;
	do_gps++;
	do_ueb++;
	if(remote_iv == REMOTE_INTERVAL)
	{
		do_i2c = 1;
		remote_iv = 0;
	}
}

ISR(INT0_vect)
{
	if(!(PIND & (1 << PIND2)))
	{
		//debounce
		_delay_ms(20);
		if(!(PIND & (1 << PIND2)))
		{
			finalpos_reached = 1;
		}
	}
	else
	{
		finalpos_reached = 0;
	}
}

ISR(INT1_vect)
{
	if(!(PIND & (1 << PIND3)))
	{
		//debounce
		_delay_ms(20);
		if(!(PIND & (1 << PIND3)))
		{
			finalpos_reached = 2;
		}
	}
	else
	{
		finalpos_reached = 0;
	}
}

void interrupt_init()
{
	//set INT0, INT1 as input with pullup enabled
	DDRD &= ~( (1 << PD2) | (1 << PD3) );
	//PORTD &= ~( (1 << PD2) | (1 << PD3) );
	PORTD |= (1 << PD2) | (1 << PD3);
	//enable interrupt INT0 and INT1 on any logical change
	MCUCR |= (1 << ISC10) | (1 << ISC00);
	GICR |= (1 << INT0) | (1 << INT1);
	//Now check if one of the pins is low at starttime (cause no interrupt is fired if pin is low after reset or startup)
	if(!(PIND & (1 << PIND2)))
			finalpos_reached = 1;
	if(!(PIND & (1 << PIND3)))
			finalpos_reached = 2;
}

void adc_init()
{
	DDRA = 0x00;
	//set pullup on all adc_pins except 7,6 and 5 because they have an external pullup
	PORTA = 0b00011111;
	//REFS0, REFS1 auf 0 -> external  AREF
	//Result leftadjusted
	ADMUX |= (1 << ADLAR);
	//Enable ADC, Set Prescaler to 64 ( ~118KHZ )
	ADCSRA |= (1 << ADEN) | (1 << ADPS1) | (1 << ADPS2);

}

void merge_notify_flag(unsigned char newflag)
{
	uint8_t c = 0;
	while(c<8)
	{
		if((notify_immunity_flag & (1<<c)))
		{
			if((notify_flag & (1<<c)))
				newflag |= (1<<c);
			else
				newflag &= ~(1<<c);
		}
		c++;
	}
	notify_flag = newflag;
}

void communicate_with_remote(void)
{
	uint8_t state;
    state = i2c_start(REMOTE+I2C_WRITE);       // set device address and write mode
	if ( state ) {
        /* failed to issue start condition, possibly no device found */
        i2c_stop();
		if(i2c_errors_active)
		{
		huart_puts("REMERR");
		huart_puts("\r\n");
		}

    }
	else
	{
		//read values
        i2c_write(0x00);                      //write address
        i2c_rep_start(REMOTE+I2C_READ);       //set device address and read mode
		merge_notify_flag(i2c_readAck());
		//notify_flag = i2c_readAck();
		uint8_t xmo = i2c_readAck();
		if(manual_override == 1 && xmo == 0)
			set_manual_override(0);
		else
			manual_override = xmo;
		//manual_override = i2c_readAck();
		gas_pwm_from_i2c = i2c_readAck();
		manual_steer = i2c_readAck();
		ca_active =i2c_readAck();
		autopump_active = i2c_readAck();
		ca_corrlevel = i2c_readAck();
		ca_coursechange_level = i2c_readAck();
		ca_required_action = i2c_readAck();
			/*char xxxbuff[9];
			huart_puts("@NOTIFY,");
			xxxbuff[8] = '\0';
			utoa(notify_flag,xxxbuff,2);
			huart_puts(xxxbuff);
			huart_puts("\r\n");*/
		if((notify_flag & (1<<NOTIFY_NEW_SETTING))) //if bit 1 in notify_flag isset, stating that new settings are here...
		{
			huart_puts("NFNS\r\n");
			gas_trim_high = i2c_readAck();
			gas_trim_low = i2c_readAck();
			pwm_g_startval = i2c_readAck();
			l_stepdur = i2c_readAck();
			rgb_red = i2c_readAck();
			rgb_green = i2c_readAck();
			rgb_blue = i2c_readAck();
			rgb_test = i2c_readAck();
			rgb_sound = i2c_readNak();
			notify_flag &= ~(1<<NOTIFY_NEW_SETTING); //clear notify_flag new settings bit
			notify_immunity_flag |= (1<<NOTIFY_NEW_SETTING);
		}
		else
		{
			state = i2c_readNak(); //do dummy read with NAK
		}

		/*char xbuff[5];
		utoa(i2c_readAck(),xbuff,10);
		huart_puts(xbuff);
		huart_putc('*');
		utoa(i2c_readAck(),xbuff,10);
		huart_puts(xbuff);
		huart_putc('*');
		utoa(i2c_readAck(),xbuff,10);
		huart_puts(xbuff);
		huart_putc('*');
		utoa(i2c_readAck(),xbuff,10);
		huart_puts(xbuff);
		huart_putc('*');
		utoa(i2c_readAck(),xbuff,10);
		huart_puts(xbuff);
		huart_putc('*');
		utoa(i2c_readNak(),xbuff,10);
		huart_puts(xbuff);
		huart_puts("\r\n");*/
		i2c_stop();
		//write values
		state = i2c_start(REMOTE+I2C_WRITE);       // set device address and write mode
		if ( state )
		{
			/* failed to issue start condition, possibly no device found */
			i2c_stop();
			if(i2c_errors_active)
			{
				huart_puts("REMERW");
			huart_puts("\r\n");
			}

		}
		else
		{
			//SUBMIT DATA TO REMOTE
			i2c_write(0x00);
			i2c_write(course >> 8);
			i2c_write(course);
			i2c_write(roll);
			i2c_write(nick);
			i2c_write(OCR0);
			i2c_write(ca_active);
			i2c_write(autopump_active);
			i2c_write(OCR2);
			i2c_write(finalpos_reached);
			i2c_write(FixQuality);
			i2c_write(NS);
			i2c_write(EW);
			i2c_write(long_deg);
			i2c_write(long_min);
			i2c_write(long_sec >> 8);
			i2c_write(long_sec);
			i2c_write(lat_deg);
			i2c_write(lat_min);
			i2c_write(lat_sec >> 8);
			i2c_write(lat_sec);
			i2c_write(GPSThour);
			i2c_write(GPSTmin);
			i2c_write(GPSTsec);
			i2c_write(GPSTday);
			i2c_write(GPSTmon);
			i2c_write(GPSTyear);
			i2c_write(HDOP);
			i2c_write(GPSStatus);
			i2c_write(UsedSatellites);
			i2c_write(iSpeed);
			i2c_write(iHeading);
			i2c_write(SatsinView);
			i2c_write(manual_override);
			i2c_write(gas_trim_high);
			i2c_write(gas_trim_low);
			i2c_write(pwm_g_startval);
			i2c_write(notify_flag);
			//DATA FROM UEBERW
			i2c_write((ueb_voltage >> 8));
			i2c_write(ueb_voltage);
			i2c_write(ueb_batalarm);
			i2c_write(ueb_wsens_high);
			i2c_write(ueb_wsens_low);
			i2c_write(ueb_pumping);
			i2c_write(ueb_pumpstate);
			i2c_write(ueb_nosms);
			i2c_write(ueb_deny_reco);
			i2c_write(ueb_pumpstarts);
			i2c_write((ueb_pumprunned >> 8));
			i2c_write(ueb_pumprunned);
			i2c_write(ueb_phone_res1);
			i2c_write(ueb_phone_res2);
			i2c_write(ueb_sent_sms);
			i2c_write((ueb_all_sms >> 8));
			i2c_write(ueb_all_sms);
			i2c_write(ueb_phone_init);
			i2c_write(l_stepdur);
			i2c_write(rgb_red);
			i2c_write(rgb_green);
			i2c_write(rgb_blue);	//#58
			i2c_write(rgb_test);
			i2c_write(rgb_sound);

			/*char xxxbuff[9];
			huart_puts("@WOTIFY,");
			xxxbuff[8] = '\0';
			utoa(notify_flag,xxxbuff,2);
			huart_puts(xxxbuff);
			huart_puts("\r\n");*/
			//i2c_write();
			i2c_stop();
			notify_immunity_flag = 0;
		}
        return;
	}
}

void communicate_with_rgbctrl()
{
	uint8_t state;
	uint8_t trgb_red = 255;
	uint8_t trgb_green = 255;
	uint8_t trgb_blue = 255;
	uint8_t trgb_test = 0;
	uint8_t trgb_sound = 0;
    state = i2c_start(RGBCTRL+I2C_WRITE);       // set device address and write mode
	if ( state ) {
        /* failed to issue start condition, possibly no device found */
        i2c_stop();
		if(i2c_errors_active)
		{
			huart_puts("RGBERR");
		huart_puts("\r\n");
		}

    }
	else
	{
		uint8_t tchanged = 0;
		
		//read values
        i2c_write(0x00);                      //write address
        i2c_rep_start(RGBCTRL+I2C_READ);       //set device address and read mode
		trgb_red = i2c_readAck();
		trgb_green = i2c_readAck();
		trgb_blue = i2c_readAck();
		trgb_test = i2c_readAck();
		tchanged = i2c_readNak();
		i2c_stop();
		
		if(tchanged != 255)
			trgb_sound = tchanged;
		
		tchanged = 0;		

		
		if(rgb_test > 0)
		{
			tchanged = 1;
			trgb_test = rgb_test;
			rgb_test = 0;
		}
		/*huart_putc('S');
		utoa(rgb_sound,tbuff,10);
		huart_puts(tbuff);
		huart_putc('#');
		utoa(trgb_sound,tbuff,10);
		huart_puts(tbuff);
		huart_puts("\r\n");*/
		//check if changed values...
		if((rgb_sound != trgb_sound) || (tchanged != 0) || (trgb_green != rgb_green) || (trgb_blue != rgb_blue) || (trgb_red != rgb_red) || (trgb_red != rgb_red))
		{
			//write values
			state = i2c_start(RGBCTRL+I2C_WRITE);       // set device address and write mode
			if ( state )
			{
				/* failed to issue start condition, possibly no device found */
				i2c_stop();
				if(i2c_errors_active)
				{
					huart_puts("RGBERW");
				huart_puts("\r\n");
				}

			}
			else
			{
				//SUBMIT DATA
 				i2c_write(0x00);
				i2c_write(rgb_red);
 				i2c_write(rgb_green);
 				i2c_write(rgb_blue);
 				i2c_write(trgb_test);
				i2c_write(rgb_sound);
				i2c_stop();
			}
		}
        return;
	}
}

void communicate_with_ueberwachung()
{
	uint8_t state;
    state = i2c_start(BOOT_UEBERWACHUNG+I2C_WRITE);       // set device address and write mode
	if ( state ) {
        /* failed to issue start condition, possibly no device found */
        i2c_stop();
		if(i2c_errors_active)
		{
			huart_puts("UEBERR");
		huart_puts("\r\n");
		}

    }
	else
	{
		//read values
        i2c_write(0x00);                      //write address
        i2c_rep_start(BOOT_UEBERWACHUNG+I2C_READ);       //set device address and read mode
		ueb_voltage = i2c_readAck()*256;
		ueb_voltage = ueb_voltage+i2c_readAck();
		ueb_batalarm = i2c_readAck();
		ueb_wsens_high = i2c_readAck();
		ueb_wsens_low = i2c_readAck();
		ueb_pumping = i2c_readAck();
		ueb_pumpstate = i2c_readAck();
		ueb_autopump_active = i2c_readAck();
		ueb_nosms = i2c_readAck();
		ueb_deny_reco = i2c_readAck();
		ueb_pumpstarts = i2c_readAck();
		ueb_pumprunned = i2c_readAck()*256;
		ueb_pumprunned = ueb_pumprunned+i2c_readAck();
		ueb_phone_res1 = i2c_readAck();
		ueb_phone_res2 = i2c_readAck();
		ueb_sent_sms = i2c_readAck();
		ueb_all_sms = i2c_readAck()*256;
		ueb_all_sms = ueb_all_sms+i2c_readAck();
		ueb_phone_init = i2c_readNak();

		i2c_stop();
		//write values
		state = i2c_start(BOOT_UEBERWACHUNG+I2C_WRITE);       // set device address and write mode
		if ( state )
		{
			/* failed to issue start condition, possibly no device found */
			i2c_stop();
			if(i2c_errors_active)
			{
			huart_puts("UEBERW");
			huart_puts("\r\n");
			}

		}
		else
		{
			//SUBMIT DATA
			i2c_write(99); //dummy byte.. warum auch immer.. irgendwie verschluckt i2c das erste byte auf der gegenseite :(
 			i2c_write(lat_deg);
 			i2c_write(lat_min);
 			i2c_write(lat_sec >> 8);
 			i2c_write(lat_sec);
			i2c_write(long_deg);
			i2c_write(long_min);
			i2c_write(long_sec >> 8);
			i2c_write(long_sec);
			i2c_write(EW);
			i2c_write(NS);
			i2c_write(FixQuality);
			i2c_write(autopump_active);


			//i2c_write(notify_flag);
			//i2c_write();
			i2c_stop();
		}
        return;
	}
}


void read_cmps10(void)
{
	uint8_t bearing, bearingh, bearingl;
    bearing = i2c_start(CMPS10+I2C_WRITE);       // set device address and write mode
	if ( bearing ) {
        /* failed to issue start condition, possibly no device found */
        i2c_stop();
		if(i2c_errors_active)
		{
			huart_puts("CMPERR");
		huart_puts("\r\n");
		}

    }else {
        /* issuing start condition ok, device accessible */
		//i2c_write(0x01);                       // write address = 0
        //i2c_write(0x51);                       // ret=0 -> Ok, ret=1 -> no ACK
        //i2c_stop();								// set stop conditon = release bus

		//delay at least 66 ms for ranging operation to finish;
		//_delay_ms(66);
        //i2c_start_wait(SFR02+I2C_WRITE);     // set device address and write mode
        i2c_write(0x01);                       // write address
        i2c_rep_start(CMPS10+I2C_READ);       // set device address and read mode
 		bearing = i2c_readAck();
		bearingh = i2c_readAck();
		bearingl = i2c_readAck();
		nick = i2c_readAck();
		roll = i2c_readNak();
        i2c_stop();
		course = bearingh;
		course = course*256+bearingl;
		/*utoa(course,tbuff,10);
		huart_putc('*');
		huart_puts(tbuff);
		utoa(bearingh,tbuff,10);
		huart_putc('*');
		huart_puts(tbuff);
		utoa(bearingl,tbuff,10);
		huart_putc('*');
		huart_puts(tbuff);
		itoa(nick,tbuff,10);
		huart_putc('*');
		huart_puts(tbuff);
		itoa(roll,tbuff,10);
		huart_putc('*');
		huart_puts(tbuff);
		huart_puts("\r\n");*/
        return;
	}
}

void process_remote_commands()
{
	if(manual_override == 1)
	{
		huart_puts("MOR--!");
		huart_puts("\r\n");
		OCR0 = gas_pwm_from_i2c;
		/*uint8_t tempval = gas_pwm_from_i2c;
		if(tempval > gas_trim_high)
		{
			OCR0 = gas_trim_high;
		}
		else if(tempval < gas_trim_low)
		{
			OCR0 = gas_trim_low;
		}
		else
		{
			OCR0 = tempval;
			pwm_g_startval = tempval;
		}*/

		//TODO process manual_steer (manual steer command)
		if(manual_steer != 0)
		{
			steer_pulse(manual_steer);
			huart_puts("MS");
			huart_putc(manual_steer);
		}
	}
	if(ca_active == 1 && (notify_flag & (1<<NOTIFY_NEW_CA_ACTION))) //check if notify_flag bit 0 isset
	{
		huart_puts("REM--!");
		if(ca_required_action > 0)
		{
			huart_puts("\r\n");
			huart_puts("--TODOL ");
			itoa(ca_required_action,tbuff,10);
			huart_puts(tbuff);
			l_stepdur = ca_required_action*10;
			steer_pulse('r');
		}
		else if(ca_required_action < 0)
		{
			huart_puts("\r\n");
			huart_puts("--TODOR ");
			itoa(ca_required_action,tbuff,10);
			huart_puts(tbuff);
			l_stepdur = ca_required_action*-10;
			steer_pulse('l');
		}
		else
		{
			huart_puts("\r\n");
			huart_puts("--NXTD");
		}
		notify_immunity_flag |= (1<<NOTIFY_NEW_CA_ACTION);
		notify_flag &= ~(1<<NOTIFY_NEW_CA_ACTION); //clear notify flag for ca action
	}
	else if(ca_active == 0 && (notify_flag & (1<<NOTIFY_NEW_CA_ACTION))) //ca_active not set but notify_flag here? clear flag
	{
		notify_immunity_flag |= (1<<NOTIFY_NEW_CA_ACTION);
		notify_flag &= ~(1<<NOTIFY_NEW_CA_ACTION); //clear notify flag for ca action
		huart_puts("CLF");
		huart_puts("\r\n");
	}
	else
	{
		//huart_puts("--NOTACT");
	}
	//huart_puts("\r\n");
}

int main(void)
{
	//LOAD INITIAL SETTINGS FROM EEPROM
	load_settings_from_eeprom();
	//set to output for relais1
	DDRB |= (1 << PB4);
	//set to output for relais2, relais3 (onboard)
	DDRD |= (1 << PD4) | (1 << PD5);
	//set to input for manual_override, manual steering left and right and activate pullups
	DDRC &= ~( (1 << PC7) | (1 << PC6) | (1 << PC5) );
	PORTC |= (1 << PC7) | (1 << PC6) | (1 << PC5);
	DDRC |= (1 << PC4); //output for direction control of motor driver
	//Config Interrupts INT0, INT1
	interrupt_init();
	//Init ADC and set complete PORTA to Input
	adc_init();
	//Init Hardware UART
	huart_init();
	//Init Software UART
	uart_init();
	//Enable Overflow Interrupt and set Prescaler to 256 of Timer0 for CountJobs
	TCCR0 |= (1 << CS02);
	TIMSK |= (1 << TOIE0);
	//Init PWM Servo
	pwm_init();
	//Init PWM2 Motor
	pwm2_init();
	//Init I2C
	i2c_init();

	/**/
	huart_puts("BootSteuerung V 1.0");
	huart_puts("\r\n");
	wdt_enable( WDTO_2S ); //2 sek
	sei();

	while(1)
    {
		wdt_reset();
		if(do_i2c == 1 && i2c_active == 1)
		{
			//read_cmps10();
			communicate_with_remote();
			process_remote_commands();
			communicate_with_ueberwachung();
			communicate_with_rgbctrl();
			/*utoa(ueb_voltage,tbuff,10);
			huart_puts(tbuff);
			huart_puts("\r\n");*/
			do_i2c = 0;
		}
		if(do_gps >= GPS_OUTPUT_INTERVAL && gps_output_active == 1)
		{
			submit_essential_gps_data();
			do_gps = 0;
		}
		if(do_ueb >= UEB_OUTPUT_INTERVAL)
		{
			submit_ueberw_status();
			do_ueb = 0;
		}
		wdt_reset();
		//Check for new GPS-Sentence and send it
		if(newgpssentence == 1 && gps_active == 1)
		{
			nmea_Parse();
			//itoa(nmea_Parse(),tbuff,10);
			//huart_putc('x');
			//huart_puts(tbuff);
			//huart_puts("X\r\n");
			//submit_parsed_gps_data();
			//huart_puts((char *)*okbuffer);
			//DEACTIVATE output of raw gps and compass data - not used anymore since pocket pc replaced trough lumnia920
			//huart_puts(okbuffer);
			//send compass info
			/*huart_puts("@STEMC,");
			utoa(course,tbuff,10);
			huart_puts(tbuff);
			huart_putc(',');
			itoa(nick,tbuff,10);
			huart_puts(tbuff);
			huart_putc(',');
			itoa(roll,tbuff,10);
			huart_puts(tbuff);
			huart_puts("\r\n");
			huart_puts("@NOTIFY,");
			char xxxbuff[9];
			xxxbuff[8] = '\0';
			utoa(notify_flag,xxxbuff,2);
			huart_puts(xxxbuff);
			huart_puts(" GAS ");
			utoa(OCR0,xxxbuff,10);
			huart_puts(xxxbuff);
			huart_puts("\r\n");
			//*/
			newgpssentence = 0;
		}
		else
		{
			unsigned short memfree = get_mem_unused();
			/*utoa(memfree,tbuff,10);
			huart_putc('M');
			huart_puts(tbuff);
			huart_puts("\r\n");*/
			if(memfree < 25)
			{
				huart_puts("STOP");
				//while(1);
				reset();
			}
			vardelay(50);
		}
		wdt_reset();
		//switch gas pwm off if not used to protect gas servo
		if(manual_override == 1 || manual_phone_override == 1)
		{
			if(last_ocr_val == OCR0)
			{
				if(servo_protect_counter >= SERVO_PROTECT_COUNTER_VAL)
				{
					switch_gas_pwm(0);
					servo_protect_counter++;
				}
				else
				{
					switch_gas_pwm(1);
					servo_protect_counter++;
				}
			}
			else
			{
				switch_gas_pwm(1);
				last_ocr_val = OCR0;
				servo_protect_counter = 0;
			}
		}
		else
		{
			switch_gas_pwm(0);
		}
    }
	return 0;
}