// Robotmaaier SOFTSTART

// Verwijder de "_NO" om enkel het LCD te testen
#define LCD_DEBUG_NO

// Op het display rechtsonder verschijnt een letter die aangeeft waarmee hij bezig is.
// V = normaal vooruit rijden
// T = uit zichzelf een bocht maken
// P = een bocht maken omdat hij de perimeter aan de zijkant merkt.
// P_time = draaitijd na detectie perimeterlus
// B_time = draaitijd na botsing met bumper
// set_PWM_LINKS() , OCR1_LINKS = linkermotor
// Perimeterontvangers testen door in debug-mode te gaan 
// "voorwaarts" indrukken voor je de robot start
// en vervolgens de robot (automatisch) op de perimeter af te sturen
// Zodra hij stopt, gaat het LCD de opgepikte waarden tonen.
// Je kan deze debug-routine verlaten door op de start-knop te drukken,
// en --nadat er "gestopt" op het LCD verschijnt, op "achteruit" te drukken.

// Minimum en maximum turntime in (seconden * 10)
#define MAX_TURNTIME    678                                     // 66 seconden
#define MIN_TURNTIME    345                                     // 34 seconden
// Af en toe maakt de robotmaaier een willekeurige bocht naar links of rechts
// MAX_DIRCHANGE bepaalt de maximum-tijd die aan de bocht besteed wordt
#define MAX_DIRCHANGE   201                                     // 20 seconden
// Turntime bij het vermijden van de perimeter-lus  10 = ongeveer 1 seconde
#define P_time          20
// Hoe lang de robot ter plaatse draait nadat de bumper iets geraakt heeft
#define B_time          10
// De tijd die een draaiende motor nodig heeft om uit te bollen (in milliseconden),
// alvorens we de rij-richting omkeren
#define UITBOL_TIJD     800                                     // 0.8 seconden
// Maximum is 100%
#define MAXIMUM_SPEED   100
// Onder dit minimum wordt PWM_RECHTS (PWM_LINKS) laag gemaakt, en stopt de motor.
#define MINIMUM_SPEED   25
#define DRIEKWART_SPEED ((((MAXIMUM_SPEED - MINIMUM_SPEED) / 4) * 3) + MINIMUM_SPEED)
#define HALF_SPEED      (((MAXIMUM_SPEED - MINIMUM_SPEED) / 2) + MINIMUM_SPEED)
#define KWART_SPEED     (((MAXIMUM_SPEED - MINIMUM_SPEED) / 4) + MINIMUM_SPEED)
// De waarde van ADC, waaronder we een perimeter-ingang als "actief" beschouwen
#define BOVENGRENS      160
// PM_REF wordt gebruikt om hysteresis in te bouwen. Deze moet dus groter zijn dan BOVENGRENS
#define PM_REF          180
// PM_ZIJWAARTS bepaalt de gevoeligheid van de achterste ontvangers
// wanneer de robot parallel aan de perimeter-lus rijdt
#define PM_ZIJWAARTS    180
// De tijd gedurende welke de robot achteruit rijdt, nadat hij de perimeter opmerkte, in milliseconden
#define PM_ACHTERWAARTS 500



#ifndef P
#define P(s) ({static const char c[] __attribute__ ((progmem)) = s;c;})
#endif

#define F_CPU 16000000UL
#include <avr/io.h>
#include <util/delay.h>
#include <util/delay_basic.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>

void delay_ms(unsigned int ms)
{
    unsigned int            cnt = 0;

    for (cnt = 0cnt < mscnt++) {
        _delay_ms(0.99);
    }
}

inline void __attribute__ ((always_inline)) delay_us(unsigned int us)
{
    unsigned int            us_cnt = 0;

    for (us_cnt = 0us_cnt < usus_cnt++) {
        _delay_us(0.99);
    }
}


// Uitgangen op PORTB
#define UIT_PORT        PORTB
#define UIT_DDR         DDRB
#define RIGHT_DIR       _BV(0)                                  // Rechts vooruit of achteruit
#define RIGHT_SPEED     _BV(1)                                  // OC1A - PWM rechts
#define LEFT_SPEED      _BV(2)                                  // OC1B - PWM links
#define LEFT_DIR        _BV(3)                                  // Links vooruit of achteruit
#define RESERVE3        _BV(4)                                  // was: motor for the cutting blades
#define BEEPER          _BV(5)                                  // Beeper
#define UITPINNEN       LEFT_DIR | LEFT_SPEED | RIGHT_SPEED | RIGHT_DIR | BEEPER

// Bedieningstoetsen op PORTC
// Enkel K_MANUEEL wordt nog als digitale ingangspin gebruikt - de overige define's gebruiken we als bitmask

//#define KNOPPEN_PORT  PINC
#define K_VOORUIT       _BV(0)
#define K_ACHTERUIT     _BV(1)
#define K_LINKS         _BV(2)
#define K_RECHTS        _BV(3)
#define K_MESSEN        _BV(4)
//#define K_MANUEEL     _BV(5)
#define K_AAN_UIT       _BV(6)

// PORTD
#define SENSOR_PORT     PIND
#define FRONTBUMPER     _BV(0)                                  // Front bumper - aktief laag
#define REARBUMPER      _BV(1)                                  // Rear bumper - actief laag
#define K_MANUEEL       _BV(2)
#define RESERVE1        _BV(4)                                  //
#define RESERVE2        _BV(5)                                  // PWM-uitgang maaiermotors
#define NTC             _BV(6)                                  //
#define KANTELCONTACT   _BV(7)                                  // De kantel-schakelaars
#define PORTDPINNEN     FRONTBUMPER | REARBUMPER | K_MANUEEL | KANTELCONTACT | NTC

// Overige definities
#define START           1
#define VOORWAARTS      2
#define ACHTERWAARTS    3
#define TURNLEFT        4
#define TURNRIGHT       5
#define ERROR           6
#define LINKS           7
#define RECHTS          8
#define OFF             9
#define ALL             10
#define ALLEBEI         11
#define TURN            12
#define UIT             13
#define AAN             14
#define NOP             15
#define YES             16
#define NO              17

// Het PWM-gebeuren
#define OCR1_RECHTS     OCR1A
#define OCR1_LINKS      OCR1B
#define PWM_RECHTS      OC1A
#define PWM_LINKS       OC1B
#define COM_RECHTS      COM1A1
#define COM_LINKS       COM1B1

// ADC-waarden voor de toetsen - meer info bij manueel()
#define R12k    225
#define R5k6    169
#define R2k2    118
#define R0k4     50

#define KN_1            adc[0]
#define KN_2            adc[1]
#define P_RV            adc[2]
#define P_LV            adc[3]
#define P_RA            adc[4]
#define P_LA            adc[5]

// Het aantal EEPROM-adressen dat we benutten om de uptime bij te houden
#define EEPROM_NR       256

// Globale variabelen
volatile unsigned int   turntimerandom_inttimer2_ovf_cnt;
volatile unsigned char  uptime_secondenuptime_minutenvorige_uptime_minutenbumperturn = NO;
volatile unsigned char  aan_uit = UITstatus = STARTrm_debug = NOadc_cnt = 1adc[6];
char                    tekst[20];

// Subroutines

/*
  LCD-interface
  Software om de driedraads LCD-interface aan te sturen

  Pros  2007
*/


#define TXT 23
#define COM 45

// instruction register bit positions
#define LCD_CLR             0                                   // DB0: clear display
#define LCD_HOME            1                                   // DB1: return to home position
#define LCD_ENTRY_MODE      2                                   // DB2: set entry mode
#define LCD_ENTRY_INC       1                                   // DB1: 1=increment, 0=decrement
#define LCD_ENTRY_SHIFT     0                                   // DB2: 1=display shift on
#define LCD_ON              3                                   // DB3: turn lcd/cursor on
#define LCD_ON_DISPLAY      2                                   // DB2: turn display on
#define LCD_ON_CURSOR       1                                   // DB1: turn cursor on
#define LCD_ON_BLINK        0                                   // DB0: blinking cursor ?
#define LCD_MOVE            4                                   // DB4: move cursor/display
#define LCD_MOVE_DISP       3                                   // DB3: move display (0-> cursor) ?
#define LCD_MOVE_RIGHT      2                                   // DB2: move right (0-> left) ?
#define LCD_FUNCTION        5                                   // DB5: function set
#define LCD_FUNCTION_8BIT   4                                   // DB4: set 8BIT mode (0->4BIT mode)
#define LCD_FUNCTION_2LINES 3                                   // DB3: two lines (0->one line)
#define LCD_FUNCTION_10DOTS 2                                   // DB2: 5x10 font (0->5x7 font)
#define LCD_CGRAM           6                                   // DB6: set CG RAM address
#define LCD_DDRAM           7                                   // DB7: set DD RAM address
#define LCD_BUSY            7                                   // DB7: LCD is busy

// set entry mode: display shift on/off, dec/inc cursor move direction
#define LCD_ENTRY_DEC            0x04                           // display shift off, dec cursor move dir
#define LCD_ENTRY_DEC_SHIFT      0x05                           // display shift on,  dec cursor move dir
#define LCD_ENTRY_INC_           0x06                           // display shift off, inc cursor move dir
#define LCD_ENTRY_INC_SHIFT      0x07                           // display shift on,  inc cursor move dir

// display on/off, cursor on/off, blinking char at cursor position
#define LCD_DISP_OFF             0x08                           // display off
#define LCD_DISP_ON              0x0C                           // display on, cursor off
#define LCD_DISP_ON_BLINK        0x0D                           // display on, cursor off, blink char
#define LCD_DISP_ON_CURSOR       0x0E                           // display on, cursor on
#define LCD_DISP_ON_CURSOR_BLINK 0x0F                           // display on, cursor on, blink char

// move cursor/shift display
#define LCD_MOVE_CURSOR_LEFT     0x10                           // move cursor left  (decrement)
#define LCD_MOVE_CURSOR_RIGHT    0x14                           // move cursor right (increment)
#define LCD_MOVE_DISP_LEFT       0x18                           // shift display left
#define LCD_MOVE_DISP_RIGHT      0x1C                           // shift display right

// function set: set interface data length and number of display lines
#define LCD_FUNCTION_4BIT_1LINE  0x20                           // 4-bit interface, single line, 5x7 dots
#define LCD_FUNCTION_4BIT_2LINES 0x28                           // 4-bit interface, dual line,   5x7 dots
#define LCD_FUNCTION_8BIT_1LINE  0x30                           // 8-bit interface, single line, 5x7 dots
#define LCD_FUNCTION_8BIT_2LINES 0x38                           // 8-bit interface, dual line,   5x7 dots

#define LCD_MODE_DEFAULT     (_BV(LCD_ENTRY_MODE) | _BV(LCD_ENTRY_INC))

// normally you do not change the following
#define LCD_LINES           2                                   // visible lines
#define LCD_LINE_LENGTH  0x40                                   // internal line length
#define LCD_START_LINE1  0x00                                   // DDRAM address of first char of line 1
#define LCD_START_LINE2  0x40                                   // DDRAM address of first char of line 2
#define LCD_START_LINE3  0x14                                   // DDRAM address of first char of line 3
#define LCD_START_LINE4  0x54                                   // DDRAM address of first char of line 4


// Stuur een karakter of een instructie naar de LCD-interface
#define LCD_PORT        PORTC
#define LCD_DDR         DDRC
#define LCD_LATCH_PORT  PORTD
#define LCD_LATCH_DDR   DDRD
#define LCD_DATA_PIN    _BV(0)
#define LCD_CLK_PIN     _BV(1)
#define LCD_LATCH_PIN   _BV(3)

inline void __attribute__ ((always_inline)) LCD_ENABLE(void)
{
    LCD_LATCH_PORT &= ~(LCD_LATCH_PIN);
    LCD_LATCH_DDR |= LCD_LATCH_PIN;
    LCD_PORT = 0;
    LCD_DDR = LCD_DATA_PIN | LCD_CLK_PIN;
}

inline void __attribute__ ((always_inline)) LCD_DISABLE(void)
{
    LCD_DDR = 0;
    LCD_PORT = 0;
}


// Dit is de bediening v/d 3-draads seriele interface.
// LCD_DATA_PIN wordt verbonden met de Data-ingang van een 74HC595 en met RS v/d LCD-module.
// LCD_CLK_PIN wordt verbonden met de schuifregisterklok v/d 74HC595
// LCD_LATCH_PIN wordt verbonden met de Latch-ingang v/d 74HC595 en met de E-pin v/d LCD-module.

// Werking:
// LCD_LATCH_PIN laag
// LCD_CLK_PIN laag
// Bit 7 klaarzetten
// LCD_CLK_PIN hoog en terug laag
// Bit 6 klaarzetten
// LCD_CLK_PIN hoog en terug laag
// ...
// Bit 0 klaarzetten
// LCD_CLK_PIN hoog en terug laag
// RS klaarzetten
// LCD_LATCH_PIN hoog en terug laag

/*
 * Gebruik van de LCD-routines:
 * ============================
 * 
 * lcd_init();
 * Deze routine wordt typisch aangeroepen vanuit setup()
 * Ze initialiseert de LCD-module voor twee regels
 * 
 * lcd_gotoyx(y, x);
 * Duidt de plaats aan, waar het volgende karakter moet verschijnen
 * y = regel = 1 of 2
 * x = kolom = 0 ... 15 (of 0 ... 19 bij een 2 x 20 scherm)
 * 
 * lcd_clrscr();
 * Wis het ganse scherm. Tekst zal nu links bovenaan verschijnen
 * 
 * lcd_clearline(regel);
 * Wis regel 1 of regel 2
 * Tekst, die hierna volgt, zal aan het begin van de gewiste regel verschijnen
 * 
 * lcd_puts(*string);
 * Plaats een tekststring uit RAM op het LCD. De tekststring dient eerst met de nodige data gevuld te worden
 * Er is momenteel een string van 20 karakters voorzien: tekst[20] (zie hierboven).
 * Voorbeeld:
 * unsigned int abc;                    // Een variabele
 * abc = 1234;                          // We geven die een willekeurige waarde
 * char tekst[20];                      // De tekstbuffer
 * sprintf(tekst, "abc = %u", abc);     // Tekstbuffer vullen
 * lcd_puts(tekst);                     // Buffer naar het LCD sturen. Er verschijnt nu "abc = 1234" op het scherm
 * 
 * lcd_puts_P(*string in ROM);
 * lcd_puts() kan ook zo gebruikt worden: lcd_puts("HALLO");
 * Dat is sterk af te raden! avr-gcc gaat 4 bytes RAM benutten om de string "HALLO" te plaatsen.
 * De ATmega328 beschikt weliswaar over 2048 bytes RAM, maar het is onverstandig daar spilzuchtig mee om te gaan.
 * Hier komt lcd_puts_P() ter hulp. De rare constructie hieronder ( #define lcd_puts_P(__s)    lcd_puts_p(P(__s)) )
 * zorgt er voor, dat de karakters in ROM blijven staan. De routine wijkt af van lcd_puts(), doordat hij rechtstreeks
 * uit ROM kan lezen.
 * Let wel: het is lcd_puts_P() met hoofdletter P, en NIET lcd_puts_p()!!!
 * 
 * lcd_char(char);
 * Zonodig kan deze routine gebruikt worden om 1 enkel karakter naar het LCD te sturen.
 * Arduino-pinnen A2 en A3 moeten dan wel eerst als uitgang geschakeld worden, en op het eind terug als ingang.
 * Voorbeeld:
 * LCD_ENABLE();                                // Pinnen als uitgang schakelen
 * lcd_char('A');                       // Geen "A"! "A" is een string, 'A' is een enkel karakter.
 * LCD_DISABLE();
 */



#define lcd_puts_P(__s)    lcd_puts_p(P(__s))
#define lcd_command(x)     char2LCD3(x, COM)
#define lcd_char(x)        char2LCD3(x, TXT)

void char2LCD3(unsigned char karakterunsigned char RS)
{
    volatile unsigned char  cnt = 0;

    for (cnt = 0cnt < 8cnt++) {
        if ((karakter & 0x80) == 0x00) {                        // een '0'
            LCD_PORT &= ~(LCD_DATA_PIN);                        // LCD_DATA_PIN laag
        } else {                                                // een '1'
            LCD_PORT |= LCD_DATA_PIN;                           // LCD_DATA_PIN hoog
        }
        _delay_us(100);
        LCD_PORT |= LCD_CLK_PIN;                                // Seriele klok hoog
        _delay_us(100);
        LCD_PORT &= ~(LCD_CLK_PIN);                             // Serieele klok terug laag
        karakter = karakter << 1;                               // Bits een plaatsje naar rechts schuiven
    }
    _delay_us(100);
    if (RS == TXT) {
        LCD_PORT |= LCD_DATA_PIN;                               // Tekst, RS moet hoog
    } else {
        LCD_PORT &= ~(LCD_DATA_PIN);                            // Instructie, RS moet laag
    }
    _delay_us(100);
    LCD_LATCH_PORT |= LCD_LATCH_PIN;                            // schuifregister -> par. uitgang
    _delay_us(160);
    LCD_LATCH_PORT &= ~(LCD_LATCH_PIN);                         // par. uitgang -> LCD-module
    _delay_us(84);
}


void lcd_init(void)
{
    LCD_ENABLE();                                               // Pinnen als uitgang schakelen
    delay_ms(10);                                               // Minstens 16 mSec wachten na power-on
    LCD_ENABLE();
    delay_ms(10);
    lcd_command(LCD_FUNCTION_8BIT_2LINES);                      // RESET-procedure
    delay_ms(10);                                               //   |
    lcd_command(LCD_FUNCTION_8BIT_2LINES);                      //   |
    _delay_us(150);                                             //   V
    lcd_command(LCD_FUNCTION_8BIT_2LINES);
    _delay_us(50);
    lcd_command(LCD_FUNCTION_8BIT_2LINES);
    _delay_us(50);
    lcd_command(LCD_DISP_OFF);
    _delay_us(50);
    lcd_command(LCD_DISP_ON);
    _delay_us(50);
    lcd_command(LCD_MODE_DEFAULT);
    _delay_us(50);
    lcd_command(_BV(LCD_CLR));
    delay_ms(2);
    lcd_command(LCD_DISP_ON);
    delay_ms(2);
    LCD_DISABLE();                                              // PC2 en PC3 terug als INGANG schakelen!!!
}


// goto position (regel y, kolom x)
void lcd_gotoyx(unsigned char yunsigned char x)
{
    LCD_ENABLE();
    if (y > 1) {                                                // Tweede regel
        x += LCD_START_LINE2;
    }
    lcd_command(_BV(LCD_DDRAM) + x);                            // goto position (x,y)
    LCD_DISABLE();
}


// clear lcd and set cursor to home position
void lcd_clrscr(void)
{
    LCD_ENABLE();
    _delay_us(2);
    lcd_command(1 << LCD_CLR);
    delay_ms(2);
    LCD_DISABLE();
}


// Wis regel 1 of 2
void lcd_clearline(unsigned char regel)
{
    char                    cnt = 0;

    LCD_ENABLE();
    if (regel < 2) {                                            // Bovenste regel?
        lcd_command(_BV(LCD_DDRAM));                            // Ga naar begin eerste regel
        for (cnt = 0cnt < 20cnt++) {                        // 20 plaatsen
            lcd_char(' ');                                      // vullen met spaties
        }
        lcd_command(_BV(LCD_DDRAM));                            // Terug naar begin eerste regel
    } else {                                                    // Onderste regel
        lcd_command(_BV(LCD_DDRAM) + LCD_START_LINE2);          // Ga naar begin tweede regel
        for (cnt = 0cnt < 20cnt++) {                        // 20 plaatsen
            lcd_char(' ');                                      // vullen met spaties
        }
        lcd_command(_BV(LCD_DDRAM) + LCD_START_LINE2);          // Terug naar begin tweede regel
    }
    LCD_DISABLE();
}



// Stuur string naar LCD
void lcd_puts(const char *s)
{
    LCD_ENABLE();
    while (*s) {
        lcd_char(*s);
        s++;
    }
    LCD_DISABLE();
}


// print string from program memory on lcd
void lcd_puts_p(const prog_char * progmem_s)
{
    register char           c = 0;

    LCD_ENABLE();
    _delay_us(2);
    while ((c = pgm_read_byte(progmem_s++))) {
        lcd_char(c);
    }
    LCD_DISABLE();
}


// Toon een unsigned int (0 ... 999) op het LCD
void smallint2lcd(unsigned int getal)
{
    unsigned char           cnt = 0;

    LCD_ENABLE();
    _delay_us(2);
    cnt = 0;
    while (getal > 99) {
        getal -= 100;
        cnt++;
    }
    lcd_char(cnt + '0');                                        // Honderdtallen
    cnt = 0;
    while (getal > 9) {
        getal -= 10;
        cnt++;
    }
    lcd_char(cnt + '0');                                        // Tientallen
    lcd_char(getal + '0');                                      // Eenheden
    LCD_DISABLE();
}


// Toon een unsigned char (0 ... 99) op het LCD
void smallchar2lcd(unsigned char getal)
{
    unsigned char           cnt = 0;

    LCD_ENABLE();
    _delay_us(2);
    cnt = 0;
    while (getal > 9) {
        getal -= 10;
        cnt++;
    }
    lcd_char(cnt + '0');                                        // Tientallen
    lcd_char(getal + '0');                                      // Eenheden
    LCD_DISABLE();
}


// EEPROM-routines
// Schrijf byte 'val' naar EEPROM-adres 'adres'  ATmega328: 1024 bytes EEPROM
static void char2eeprom(unsigned int adresunsigned char val)
{
    unsigned char           sreg = 0;

    while (EECR & _BV(EEPE));                                   // Wacht tot het EEPE-bit laag is
    while (SPMCSR & _BV(SELFPRGEN));                            // Wacht tot het SELFPRGEN-bit laag is
    EEAR = adres;                                               // Vul het adres in
    EEDR = val;                                                 // Vul data in
    sreg = SREG;                                                // Noteer SREG
    cli();                                                      // Onderbreek alle interrupts
    EECR = _BV(EEMPE);                                          // Eerst het EEMPE-bit hoog maken
    EECR |= _BV(EEPE);                                          // En onmiddelijk daarop het EEPE-bit
    SREG = sreg;                                                // SREG herstellen = interrupts toestaan
}


// Lees een byte van EEPROM-adres adres
static unsigned char eeprom2char(unsigned int adres)
{
    while (EECR & _BV(EEPE));
    EEAR = adres;
    EECR |= _BV(EERE);
    return EEDR;
}


// Om de uptime (in minuten) te bewaren gebruiken we de EEPROM
// We schrijven telkens naar een volgend adres
// Tijdens het opstarten zoeken we naar het adres met de hoogste stand. Die wijst naar de vorige uptime.

unsigned char eeprom_init(void)
{
    unsigned char           minuten = 0xFEval = 0;
    unsigned int            cnt_adres = 0;

    if (eeprom2char(0) == 0xFF) {                               // Was de EEPROM gewist?
        vorige_uptime_minuten = 0;
        minuten = 0xFF;                                         // Terugkeren met error-code 0xFF
    } else {                                                    // We zoeken de hoogste tellerstand
        for (cnt_adres = 1cnt_adres < EEPROM_NRcnt_adres++) {
            val = eeprom2char(cnt_adres);
            if (val == (unsigned charcnt_adres) {             // Data geldig?
                minuten = val;                                  // Dan overnemen in "minuten"
            } else {                                            // Zoniet,
                break;                                          // stoppen we er mee
            }
        }
        vorige_uptime_minuten = minuten;
    }

    for (cnt_adres = 0cnt_adres < EEPROM_NRcnt_adres++) {
        char2eeprom(cnt_adres0);                              // Zet alles op nul
    }

    uptime_seconden = 0;
    uptime_minuten = 0;
    timer2_ovf_cnt = 0;

    return minuten;
}


// Een passieve (piezo) beeper en een LED op dezelfde pin.
// Piezo-beepers maken flink lawaai bij hoge frequenties.
// Bij lage frequenties (1Hz bijvoorbeeld) is het geluid miniem.
// Van die eigenschap kunnen we misbruik maken om een LED en zo'n beeper met dezelfde pin te sturen.
// De LED brand gedurende die tijd op halve kracht;
// Gebruik: beep(frequentie in Hz, beeptijd in mSec);
void beep(unsigned int frequentieunsigned int beeptijd)
{
    unsigned int            wachttijd = 0times = 0count = 0;

    // return;

    // Voorbeeld: frequentie = 4000Hz, beeptijd = 300mSec
    // wachttijd in microseconden: ((1000000/2)/4000) = 125uS
    wachttijd = (unsigned int) ((1000000UL / 2) / (unsigned long) (frequentie));
    // times: (beeptijd * 500) / wachttijd = (300*500)/125 = 1200
    times = (unsigned int) (((unsigned long) (beeptijd) * 500UL) / (unsigned longwachttijd);
    for (count = 0count < timescount++) {
        PINB |= BEEPER;                                         // Toggle de beeper-uitgang
        delay_us(wachttijd);
    }
}


// Een softstart voor de maaier-motors
// Softstart ingeschakeld:  #define SOFT
// Softstart uitgeschakeld: #define HARD
#define SOFT
void maaier(unsigned char percent)
{
#ifdef HARD
    if (percent < 25) {
        OCR0B = 0;
    } else {
        OCR0B = 255;
    }
#else
    unsigned int            tmp;
    unsigned char           ocr0b = OCR0B;

    if (percent < 20) {
        OCR0B = 0;
        return;
    }
    if (percent > 100) {
        percent = 100;
    }
    tmp = (unsigned int) (percent) * 255;                       // 100% -> 25500
    percent = (unsigned char) (tmp / 100);                      // 25500 / 100 = 255
    if (ocr0b < 25) {                                           // Was de maaier uitgeschakeld?
        ocr0b = 25;                                             // dan starten we op 10%
    }
    if (ocr0b < percent) {                                      // Versnellen?
        while (ocr0b < percent) {
            ocr0b++;
            OCR0B = ocr0b;
            delay_ms(5);                                        // 2 -> 5
        }
    } else if (ocr0b > percent) {                               // Vertragen
        while (ocr0b > percent) {
            ocr0b--;
            OCR0B = ocr0b;
            delay_ms(5);                                        // 2 -> 5
        }
    }
#endif
}



// Een interrupt op PD7 (Arduino-pin 7, PCINT23)
// Dit gebeurt, wanneer de tilt-sensor actief wordt: iemand kantelt de robotmaaier of tilt hem op.
// We stoppen in dat geval alle motors ogenblikkelijk!
// Ook de bumpers kunnen deze ISR activeren. In beide gevallen leggen we eerst alle motors stil,
// om vervolgens na te gaan wat de oorzaak van de ISR was.
ISR(PCINT2_vect)
{
    unsigned char           pind = 0ocr0btmp_ocr0b;
    unsigned int            ocr1_rechts = 0ocr1_links = 0oc1a = 0oc1b = 0;

    pind = PIND;
    ocr1_rechts = OCR1_RECHTS;                                  // Snelheid noteren
    ocr1_links = OCR1_LINKS;
    ocr0b = OCR0B;

    // Nu nagaan, wat de oorzaak was
    if ((pind & KANTELCONTACT) != 0) {                          // Het kantelcontact?
      KANTEL:
        OCR1_RECHTS = 0;
        OCR1_LINKS = 0;
        OCR0B = 0;
        lcd_clearline(2);
        lcd_puts_P(" KANTEL ACTIEF");
        delay_ms(500);                                          // Contactdender vermijden
      REPEAT:
        while ((PIND & KANTELCONTACT) != 0) {                   // Zolang er een kantelcontact gesloten is,
            delay_ms(100);                                      // houden we ons stil
        }
        delay_ms(1000);                                         // Nog even wachten - veiligheid eerst!
        if ((PIND & KANTELCONTACT) != 0) {                      // Opnieuw controleren
            goto REPEAT;                                        // Contact nog gesloten? Terug naar de wachtlus!
        }

        lcd_clearline(2);
        lcd_puts_P(" OK");
        beep(400200);
        delay_ms(1000);
        beep(400200);
        delay_ms(1000);
        beep(400200);
        delay_ms(1000);
        if ((PIND & KANTELCONTACT) != 0) {                      // Opnieuw controleren
            goto KANTEL;                                        // Contact nog gesloten? Terug naar de wachtlus!
        }

        if (ocr0b > 64) {                                       // Draaide de maaier?
            tmp_ocr0b = 64;                                     // 25%
            while (tmp_ocr0b < ocr0b) {
                ocr0b++;                                        // Dan laten we die op gang komen
                OCR0B = ocr0b;
                if ((PIND & KANTELCONTACT) != 0) {
                    goto KANTEL;
                }
                delay_ms(5);
            }
        }

        oc1a = MINIMUM_SPEED;
        oc1b = MINIMUM_SPEED;


        while ((ADCSRA & _BV(ADSC)) != 0) {                     // Wachten op eind vorige ADC-conversie
        }
        ADMUX = 3 | _BV(REFS0) | _BV(ADLAR);                    // Kanaal instellen: PV_L, Ref = 5V, 8 bits
        ADCSRA |= _BV(ADSC);                                    // ADC starten
        while ((oc1a < ocr1_rechts) || (oc1b < ocr1_links)) {   // Motors langzaam op gang laten komen
            if ((PIND & KANTELCONTACT) != 0) {                  // Opnieuw controleren
                goto KANTEL;                                    // Contact nog gesloten? Terug naar de wachtlus!
            }
            // Het is niet uitgesloten, dat iemand het kantelcontact activeert, net voor we binnen het signaal
            // van de perimeter-lus waren. Zulke pestkoppen bestaan!!! :-)
            // We kunnen P_RV en/of P_RL niet zomaar uitlezen, want zolang deze ISR draait, wordt de ISR die
            // de analoge ingangen uitleest niet uitgevoerd.
            // Kortom: we moeten alles zelf doen...
            while ((ADCSRA & _BV(ADSC)) != 0) {                 // Wachten op eind vorige ADC-conversie
            }
            if (ADC < BOVENGRENS) {                             // Dicht bij de perimeter?
                PCIFR = 0x07;
                return;                                         // Dan stoppen we ermee
            }
            ADMUX = 2 | _BV(REFS0) | _BV(ADLAR);                // Kanaal instellen: P_RV, Ref = 5V, 8 bits
            ADCSRA |= _BV(ADSC);                                // ADC starten
            if (oc1a < ocr1_rechts) {
                oc1a++;
                OCR1_RECHTS = oc1a;
            }
            while ((ADCSRA & _BV(ADSC)) != 0) {
            }
            if (ADC < BOVENGRENS) {
                PCIFR = 0x07;
                return;
            }
            ADMUX = 3 | _BV(REFS0) | _BV(ADLAR);                // Kanaal instellen: PV_L, Ref = 5V, 8 bits
            ADCSRA |= _BV(ADSC);                                // ADC starten
            if (oc1b < ocr1_links) {
                oc1b++;
                OCR1_LINKS = oc1b;
            }
            delay_ms(4);
        }
    } else {                                                    // Een bumper heeft wat geraakt
        OCR1_RECHTS = 0;                                        // Aandrijfmotors stilleggen
        OCR1_LINKS = 0;
        //maaier(50);                                           // Maaier vertragen
        if ((pind & FRONTBUMPER) == 0) {                        // De voorste bumper?
            bumper = VOORWAARTS;
        } else if ((pind & REARBUMPER) == 0) {                  // De achterste bumper?
            bumper = ACHTERWAARTS;
        }
        // Voor alle zekerheid controleren we de kantelsensor
        if ((PIND & KANTELCONTACT) != 0) {
            goto KANTEL;
        }
    }
    PCIFR = 0x07;                                               // PCINT-vlaggen wissen
}


// Timer2-overflow
// Hier komen we 7812.5 maal per seconde voorbij
ISR(TIMER2_OVF_vect)
{
    unsigned char           channel = 0tmp = 0;

    random_int += TCNT1;

    if ((ADCSRA & _BV(ADSC)) == 0) {                            // Vorige ADC-conversie afgerond?
        if ((adc_cnt & 0x01) != 0) {                            // Was dit de 2e conversie?
            channel = adc_cnt / 2;                              // adc_cnt 1 -> channel 0, adc_cnt 3 -> channel 2, enz...
            if (channel < 2) {                                  // De toetsen
                adc[channel] = ADCH;                            // Resultaat van vorige conversie noteren
            } else {                                            // De perimeter-ontvangers
                tmp = adc[channel];
                tmp -= tmp / 8;
                tmp += ADCH / 8;                                // Gemiddelde berekenen
                adc[channel] = tmp;
            }
        }
        adc_cnt++;                                              // Volgende cnt
        if (adc_cnt > 11) {                                     // Range = 0 ... 11
            adc_cnt = 0;                                        // 12 -> 0
        }
        if (adc_cnt < 4) {                                      // ADC0 of ADC1?
            if ((LCD_DDR & LCD_DATA_PIN) != 0) {                // LCD wordt aangestuurd
                adc_cnt = 4;                                    // ADC0 en ADC1 slaan we dan maar over
            }
        }
        ADMUX = (adc_cnt / 2) | _BV(REFS0) | _BV(ADLAR);        // Kanaal instellen: Kanaal, Ref = 5V, 8 bits
        ADCSRA |= _BV(ADSC);                                    // start conversion
    }

    timer2_ovf_cnt++;                                           // Overflow-teller verhogen
    if (timer2_ovf_cnt > 7812) {                                // Er is een seconde voorbij
        timer2_ovf_cnt = 0;                                     // timer2_ovf_cnt terug op 0 zetten
        if (OCR0B > 0) {                                        // Enkel als de maaier draait
            uptime_seconden++;                                  // Uptime met een seconde verhogen
            if (uptime_seconden > 59) {                         // Om de 60 seconden
                uptime_minuten++;                               // Uptime-minuten verhogen
                uptime_seconden = 0;                            // En seconden terug op 0 zetten
                // Op adres 1 schrijven we 1 minuut, op adres 2 schrijven we 2 minuten, enz...
                // Op die manier kunnen we na een herstart nagaan of de data geldig is
                char2eeprom((unsigned intuptime_minutenuptime_minuten);     // Schrijf de huidige uptime weg
            }
        }
    }
}


unsigned int convertanalog(unsigned char channel)
{
    ADMUX = (channel & 0x07) | _BV(REFS0) | _BV(ADLAR);         // Kanaal instellen; Ref = 5V
    delay_ms(1);
    ADCSRA |= _BV(ADSC);                                        // start dummy conversion
    while ((ADCSRA & _BV(ADSC)) != 0) {
    }
    ADCSRA |= _BV(ADSC);                                        // start real conversion
    while ((ADCSRA & _BV(ADSC)) != 0) {                         // Effe wachten tot ADSC laag is
    }
    return (ADCH);                                              // ADCH uitlezen volstaat
}


void set_PWM_RECHTS(unsigned char percent)
{                                                               // Stel de puls/pause-verhouding van PWM_RECHTS in
    unsigned int            old_ocr1_rechts = 0new_ocr1_rechts = 0;

    old_ocr1_rechts = OCR1_RECHTS;                              // Huidige stand van OCR1_RECHTS noteren
    if (percent < MINIMUM_SPEED) {                              // Opgegeven percent lager dan minimum?
        while (old_ocr1_rechts > MINIMUM_SPEED) {               // Eerst vertragen
            old_ocr1_rechts--;
            OCR1_RECHTS = old_ocr1_rechts;
            delay_ms(2);
        }
        OCR1_RECHTS = 0;
        return;
    } else if (percent > 99) {                                  // Meer dan 99% = maximum
        new_ocr1_rechts = ICR1;
    } else {                                                    // Percent is hoger dan minimum en lager dan 100
        new_ocr1_rechts = ((unsigned long) (ICR1) * (unsigned longpercent) / 100UL;
    }
    if (old_ocr1_rechts < MINIMUM_SPEED) {
        old_ocr1_rechts = MINIMUM_SPEED;
    }
    if (new_ocr1_rechts < old_ocr1_rechts) {                    // Vertragen?
        while (new_ocr1_rechts < old_ocr1_rechts) {
            old_ocr1_rechts--;
            OCR1_RECHTS = old_ocr1_rechts;
            delay_ms(2);
        }
    } else if (new_ocr1_rechts > old_ocr1_rechts) {             // Versnellen?
        while (new_ocr1_rechts > old_ocr1_rechts) {
            old_ocr1_rechts++;
            OCR1_RECHTS = old_ocr1_rechts;
            delay_ms(2);
        }
    } else {                                                    // Gelijk. Niet uitgesloten
        OCR1_RECHTS = new_ocr1_rechts;
    }
}


void set_PWM_LINKS(unsigned char percent)
{                                                               // Stel de puls/pause-verhouding van PWM_LINKS in
    unsigned int            old_ocr1_links = 0new_ocr1_links = 0;

    old_ocr1_links = OCR1_LINKS;                                // Huidige stand van OCR1_LINKS noteren
    if (percent < MINIMUM_SPEED) {                              // Opgegeven percent lager dan minimum?
        while (old_ocr1_links > MINIMUM_SPEED) {                // Eerst vertragen
            old_ocr1_links--;
            OCR1_LINKS = old_ocr1_links;
            delay_ms(2);
        }
        OCR1_LINKS = 0;
        return;
    } else if (percent > 99) {                                  // Meer dan 99% = maximum
        new_ocr1_links = ICR1;
    } else {
        new_ocr1_links = ((unsigned long) (ICR1) * (unsigned longpercent) / 100UL;
    }
    if (old_ocr1_links < MINIMUM_SPEED) {
        old_ocr1_links = MINIMUM_SPEED;
    }
    if (new_ocr1_links < old_ocr1_links) {                      // Vertragen?
        while (new_ocr1_links < old_ocr1_links) {
            old_ocr1_links--;
            OCR1_LINKS = old_ocr1_links;
            delay_ms(2);
        }
    } else if (new_ocr1_links > old_ocr1_links) {               // Versnellen
        while (new_ocr1_links > old_ocr1_links) {
            old_ocr1_links++;
            OCR1_LINKS = old_ocr1_links;
            delay_ms(2);
        }
    } else {
        OCR1_LINKS = new_ocr1_links;
    }
}


void set_PWM_LR(unsigned char percent)
{                                                               // Stel de puls/pause-verhouding van PWM_RECHTS en PWM_LINKS gelijktijdig in
    unsigned int            old_ocr1_links = 0new_ocr1_links = 0old_ocr1_rechts = 0new_ocr1_rechts = 0;

    old_ocr1_links = OCR1_LINKS;                                // Huidige stand van OCR1_LINKS noteren
    old_ocr1_rechts = OCR1_RECHTS;                              // En van OCR1_RECHTS
    if (percent < MINIMUM_SPEED) {                              // Opgegeven percent lager dan minimum?
        while ((old_ocr1_rechts > MINIMUM_SPEED) || (old_ocr1_links > MINIMUM_SPEED)) {
            if (old_ocr1_rechts > MINIMUM_SPEED) {
                old_ocr1_rechts--;                              // Motors vertragen
                OCR1_RECHTS = old_ocr1_rechts;
            }
            if (old_ocr1_links > MINIMUM_SPEED) {
                old_ocr1_links--;
                OCR1_LINKS = old_ocr1_links;
            }
            delay_ms(2);
        }
        OCR1_RECHTS = 0;                                        // Motors stilleggen
        OCR1_LINKS = 0;
        return;
    } else if (percent > 99) {                                  // Meer dan 99% = maximum
        new_ocr1_rechts = ICR1;
        new_ocr1_links = ICR1;
    } else {                                                    // Tussen minimum en maximum
        new_ocr1_rechts = ((unsigned long) (ICR1) * (unsigned longpercent) / 100UL;
        new_ocr1_links = new_ocr1_rechts;                       // We gaan dat niet opnieuw berekenen
    }

    if (old_ocr1_rechts < MINIMUM_SPEED) {
        old_ocr1_rechts = MINIMUM_SPEED;
    }
    if (old_ocr1_links < MINIMUM_SPEED) {
        old_ocr1_links = MINIMUM_SPEED;
    }
    // We hebben nu 4 waarden: de oude en de nieuwe OCR1_RECHTS, en de oude en de nieuwe OCR1_LINKS
    // Die willen we op een vloeiende manier aanpassen.
    while ((new_ocr1_rechts != old_ocr1_rechts) || (new_ocr1_links != old_ocr1_links)) {
        if (new_ocr1_rechts < old_ocr1_rechts) {
            old_ocr1_rechts--;
        } else if (new_ocr1_rechts > old_ocr1_rechts) {
            old_ocr1_rechts++;
        }
        if (new_ocr1_links < old_ocr1_links) {
            old_ocr1_links--;
        } else if (new_ocr1_links > old_ocr1_links) {
            old_ocr1_links++;
        }
        OCR1_RECHTS = old_ocr1_rechts;
        OCR1_LINKS = old_ocr1_links;
        delay_ms(2);
    }
    OCR1_RECHTS = new_ocr1_rechts;
    OCR1_LINKS = new_ocr1_links;
}



// Stuur een motor: links, rechts, of allebei samen.
// Gebruik: motor(LINKS(RECHTS, ALLEBEI), VOORWAARTS(ACHTERWAARTS), snelheid(25% ... 100%));
// Een snelheid van minder dan MINIMUM_SPEED (zie hierboven) schakelt de motor uit.
void motor(unsigned char linksrechtsunsigned char richtingunsigned char snelheid)
{
    if (linksrechts == LINKS) {                                 // De linker motor
        if (richting == VOORWAARTS) {                           // moet voorwaarts draaien
            if ((UIT_PORT & LEFT_DIR) != 0) {                   // Draaide hij achterwaarts?
                set_PWM_LINKS(5);                               // Dan eerst de motor stoppen
                delay_ms(UITBOL_TIJD);                          // Laten uitbollen
                UIT_PORT &= ~(LEFT_DIR);                        // DIR laag maken
                delay_ms(500);
            }
        } else {                                                // Motor moet achterwaarts
            if ((UIT_PORT & LEFT_DIR) == 0) {                   // Draaide hij voorwaarts?
                set_PWM_LINKS(5);                               // Dan eerst de motor stoppen
                delay_ms(UITBOL_TIJD);                          // Laten uitbollen
                UIT_PORT |= LEFT_DIR;                           // DIR hoog maken
                delay_ms(500);
            }
        }
        set_PWM_LINKS(snelheid);                                // Snelheid aanpassen
    } else if (linksrechts == RECHTS) {                         // De rechter motor
        if (richting == VOORWAARTS) {                           // moet voorwaarts draaien
            if ((UIT_PORT & RIGHT_DIR) != 0) {                  // Draaide hij achterwaarts?
                set_PWM_RECHTS(5);                              // Dan eerst de motor stoppen
                delay_ms(UITBOL_TIJD);                          // Laten uitbollen
                UIT_PORT &= ~(RIGHT_DIR);                       // DIR laag maken
                delay_ms(500);
            }
        } else {                                                // Motor moet achterwaarts
            if ((UIT_PORT & RIGHT_DIR) == 0) {                  // Draaide hij voorwaarts?
                set_PWM_RECHTS(5);                              // Dan eerst de motor stoppen
                delay_ms(UITBOL_TIJD);                          // Laten uitbollen
                UIT_PORT |= RIGHT_DIR;                          // DIR hoog maken
                delay_ms(500);
            }
        }
        set_PWM_RECHTS(snelheid);                               // Snelheid aanpassen
    } else if (linksrechts == ALLEBEI) {                        // Allebei vooruit of achteruit
        if (richting == VOORWAARTS) {                           // Vooruit
            if ((UIT_PORT & (LEFT_DIR | RIGHT_DIR)) != 0) {     // Er draait minstens 1 motor achterwaarts
                set_PWM_LR(5);                                  // Beide motoren stoppen
                delay_ms(UITBOL_TIJD);                          // Laten uitbollen
                UIT_PORT &= ~(LEFT_DIR | RIGHT_DIR);            // DIR-pinnen laag maken
                delay_ms(200);
            }
        } else {                                                // Achteruit
            if ((UIT_PORT & (LEFT_DIR | RIGHT_DIR)) != (LEFT_DIR | RIGHT_DIR)) {        // Er draait minstens 1 motor voorwaarts
                set_PWM_LR(5);                                  // Beide motoren stoppen
                delay_ms(UITBOL_TIJD);
                UIT_PORT |= (LEFT_DIR | RIGHT_DIR);
                delay_ms(200);
            }
        }
        set_PWM_LR(snelheid);                                   // Snelheid aanpassen
    } else if (linksrechts == TURN) {                           // Ter plaatse draaien
        OCR1_RECHTS = 0;                                        // Onmiddelijk stoppen
        OCR1_LINKS = 0;
        delay_ms(UITBOL_TIJD);                                  // Laten uitbollen
        if (richting == LINKS) {                                // Willen we naar links,
            UIT_PORT &= ~(RIGHT_DIR);                           // dan moet de rechter-motor vooruit
            UIT_PORT |= LEFT_DIR;                               // en de linker achteruit
        } else {                                                // Naar rechts
            UIT_PORT |= RIGHT_DIR;                              // dan moet de rechter-motor achteruit
            UIT_PORT &= ~(LEFT_DIR);                            // en de linker vooruit
        }
        set_PWM_LR(HALF_SPEED);                                 // Niet te snel
        // 360 komt ongeveer overeen met 90 graden
        delay_ms(snelheid * 10);                                // ter plaatse draaien
        OCR1_RECHTS = 0;                                        // Motors stoppen
        OCR1_LINKS = 0;
        delay_ms(UITBOL_TIJD);                                  // Laten uitbollen...
        UIT_PORT &= ~(LEFT_DIR | RIGHT_DIR);                    // DIR-relais uitschakelen
    }
}


void forceer_uit(void)
{
    aan_uit = UIT;
    motor(ALLEBEIVOORWAARTS5);                              // Motors stoppen
    maaier(0);                                                  // Maaier stoppen
    lcd_clearline(1);
    lcd_puts_P(" Gestopt in");
    lcd_clearline(2);
    lcd_puts_P("  perimeter-lus");
    delay_ms(200);
    beep(1000200);
    PORTB &= ~(BEEPER);                                         // Knipper-LED doven
}


// Omdat we vanuit verschillende routines moeten controleren of de Start/Stop knop is ingedrukt,
// plaatsen we dat controleren in een afzonderlijke routine.
unsigned char check_aan_uit(void)
{
    if ((KN_2 > R5k6) && (KN_2 < R12k)) {                       // AAN/UIT-knop ingedrukt?
        if (aan_uit == AAN) {
            beep(2000200);                                    // Beepen en meteen contactdender onderdrukken
            aan_uit = UIT;
            motor(ALLEBEIVOORWAARTS5);                      // Motors stoppen
            maaier(0);                                          // Maaier stoppen
            lcd_clearline(2);
            lcd_puts_P(" Gestopt.");
            delay_ms(200);
            beep(1000200);
            PORTB &= ~(BEEPER);                                 // Knipper-LED doven
            return UIT;                                         // Terugkeren naar loop()
        } else {                                                // aan_uit was UIT
            aan_uit = AAN;
            beep(2000200);                                    // Beepen en meteen contactdender onderdrukken
            delay_ms(200);
            beep(1000200);
            PORTB |= BEEPER;                                    // Knipper-LED ontsteken
            return AAN;
        }
    } else {
        return NOP;
    }
}


void setup(void)
{
    unsigned char           tmp = 0;

    cli();
    CLKPR = _BV(CLKPCE);
    CLKPR = 0;                                                  // We willen op max. snelheid draaien
    delay_ms(100);
    CLKPR = _BV(CLKPCE);
    CLKPR = 0;                                                  // Een tweede maal, omzeker te zijn...
    UCSR0B = 0;
    UCSR0C = 0;
    delay_ms(100);
    lcd_init();
    lcd_clrscr();
    lcd_puts_P(" Initialising...");
    PORTD = PORTDPINNEN;                                        // Interne pull-up weerstanden activeren

    // Timer1 stuurt de aandrijfmotoren
    ICR1 = 555;                                                 // 18kHz
    TCCR1B = _BV(WGM13) | _BV(CS10);                            // Phase-correct PWM
    TCCR1A = _BV(COM1A1) | _BV(COM1B1);
    TCNT1 = 0x00;
    OCR1_RECHTS = 0;                                            // Minimum-waarde
    OCR1_LINKS = 0;
    PORTB &= ~(RIGHT_SPEED | LEFT_SPEED);                       // Laag maken voor alle zekerheid
    TIMSK1 = 0;

    delay_ms(1000);

    // Timer0 stuurt de maaier-motoren
    TCCR0A = _BV(COM0B1) | _BV(WGM00);                          // Phase-correct PWM
    TCCR0B = _BV(CS01);                                         // PWM-CLK = F_CPU / 8;
    OCR0B = 0;
    delay_ms(200);
    TIMSK0 = 0;

    // Timer 2 gebruiken we voor het genereren van random-waarden, voor het ADC-bedrijf
    // en voor het bijhouden van de uptime.

    tmp = eeprom_init();
    lcd_gotoyx(20);                                           // Ga naar 2e regel
    if (tmp == 0xFF) {                                          // Is de EEPROM gewist?
        lcd_puts_P("EEPROM = empty");
    } else if (tmp == 0xFE) {                                   // EEPROM was corrupt
        lcd_puts_P("EEPROM = ERR");
    } else {
        sprintf(tekst"UP was %uminuten", (unsigned inttmp); // Vorige uptime tonen
        lcd_puts(tekst);
    }
    TCCR2A = 0;                                                 // Enkel tellen van 0 tot 255
    TCCR2B = _BV(CS21);                                         // CLK = F_CPU / 8
    TIMSK2 = _BV(TOIE2);                                        // Interrupt bij overflow

    ADCSRA = _BV(ADEN) | _BV(ADPS2) | _BV(ADPS1) | _BV(ADPS2);  // Initialiseer de ADC
    ADMUX = _BV(REFS0) | _BV(ADLAR);                            // 8 bits volstaan
    ADCSRA |= _BV(ADSC);                                        // Start eerste conversie

    PCICR = _BV(PCIE2);                                         // Enable PinChange-Interrupt 2
    PCMSK2 = _BV(PCINT16) | _BV(PCINT17) | _BV(PCINT23);        // PD0, PD1, PD7 = interrupt-pin

#ifdef LCD_DEBUG
    while (1) {
        delay_ms(500);
        lcd_init();
        lcd_puts_P("LCD-debug");
        lcd_gotoyx(20);
        lcd_puts_P("  Regel 2");
    }
#else
    delay_ms(5000);
    lcd_init();
    lcd_puts_P("Motormaaier");
    lcd_gotoyx(20);
    lcd_puts_P("  tot uw dienst!");
    // Nu pas geven we de uitgangen vrij
    UIT_DDR = LEFT_DIR | LEFT_SPEED | RIGHT_SPEED | RIGHT_DIR | BEEPER// PORTB = motorsturing
    DDRD |= _BV(5);                                             // PD5 = maaier-sturing
    sei();                                                      // Enable global interrupts
#endif
}


// Afzonderlijke routines, om met de perimeter om te gaan


void show_pm(void)
{
    unsigned char           rvlvrala;

    rv = P_RV;
    lv = P_LV;
    ra = P_RA;
    la = P_LA;

    lcd_gotoyx(112);
    smallint2lcd(rv);
    lcd_gotoyx(10);
    smallint2lcd(lv);
    lcd_gotoyx(212);
    smallint2lcd(ra);
    lcd_gotoyx(20);
    smallint2lcd(la);
}


void perimeter_DEBUG(void)
{
    motor(ALLEBEIVOORWAARTS5);                              // Motors stoppen
    lcd_clrscr();
    lcd_gotoyx(16);
    lcd_puts_P("DE");
    lcd_gotoyx(26);
    lcd_puts_P("BUG");

    while (1) {
        delay_ms(100);
        check_aan_uit();                                        // AAN/UIT-knop ingedrukt?
        if (aan_uit == UIT) {
            return;                                             // Terugkeren naar automatisch()
        }
        show_pm();
        delay_ms(100);
        check_aan_uit();                                        // AAN/UIT-knop ingedrukt?
        if (aan_uit == UIT) {
            return;                                             // Terugkeren naar automatisch()
        }
    }
}


// Bereken een random-getal tussen de opgegeven minimum en maximum
unsigned int get_rand(unsigned int minunsigned int max)
{
    unsigned int            result = 0;

    result = random_int + TCNT2;                                // result = 0 ... 65535

    if (result > max) {                                         // Te groot
        while (result > max) {                                  // "min" aftrekken
            result -= min;                                      // tot het goed is
        }
    } else if (result < min) {                                  // Te klein
        result += min;                                          // Eenmalig "min" bijtellen
    }
    return (result);
}


// Bereken een random-turntime
unsigned int get_turntime(void)
{                                                               // Bereken een willekeurige turntime
    unsigned int            t = get_rand(MIN_TURNTIMEMAX_TURNTIME);

    sprintf(tekst" t = %02u"t / 10);
    lcd_clearline(2);
    lcd_puts(tekst);
    return t;
}


void perimeter(void)
{
    unsigned char           afteller = 0rvlv;
    unsigned int            ocr1_rechts = OCR1_RECHTSocr1_links = OCR1_LINKScnt;

    while ((ocr1_rechts > MINIMUM_SPEED) || (ocr1_links > MINIMUM_SPEED)) {     // Eerste stap:
        if (ocr1_rechts > MINIMUM_SPEED) {
            ocr1_rechts--;                                      // Beide motors vertragen
            OCR1_RECHTS = ocr1_rechts;
        }
        if (ocr1_links > MINIMUM_SPEED) {
            ocr1_links--;
            OCR1_LINKS = ocr1_links;
        }
        delay_us(20);
    }

    OCR1_RECHTS = 0;                                            // Linker-motor stoppen
    OCR1_LINKS = 0;                                             // Rechter-motor stoppen
    delay_ms(200);                                              // Even uitblazen...
    lcd_clrscr();
    lcd_gotoyx(16);
    lcd_puts_P("PM");
    afteller = 100;                                             // 100 = 20 seconden
    delay_ms(300);                                              // Alles tot rust laten komen
    show_pm();
    delay_ms(200);
    // Nu gaan we pas kijken, langs welke kant het signaal het sterkst is.
    rv = P_RV;
    lv = P_LV;
       if (rv < lv) {                                           // Signaal rechts = groter
       motor(LINKSACHTERWAARTSHALF_SPEED);                  // We gaan achterwaarts naar links draaien
       motor(RECHTSVOORWAARTSHALF_SPEED);
       } else {                                                 // Draai naar rechts
       motor(RECHTSACHTERWAARTSHALF_SPEED);
       motor(LINKSVOORWAARTSHALF_SPEED);
       }
    while ((P_RV < PM_REF) || (P_LV < PM_REF)) {
        // Draaien tot de voorste ontvangers uit de buurt van de perimeter zijn
        show_pm();
        delay_ms(200);
        afteller--;
        if (afteller < 1) {                                     // We gaan niet eeuwig blijven draaien...
            forceer_uit();
            return;
        } else if ((200 % 10) == 0) {                           // Elke seconde
            if (rv < lv) {                                      // Signaal rechts = groter
                motor(LINKSACHTERWAARTSHALF_SPEED);
            } else {                                            // Draai naar rechts
                motor(RECHTSACHTERWAARTSHALF_SPEED);
            }
        }
    }

    // We zijn er uit!
    motor(ALLEBEIVOORWAARTS5);
    delay_ms(200);
    motor(ALLEBEIVOORWAARTSMAXIMUM_SPEED);                  // Volle kracht vooruit
    lcd_clrscr();
    lcd_puts_P("AUTO-mode");
    turn = NO;
    turntime = get_turntime();
    maaier(100);
    if (((PIND & FRONTBUMPER) == 0) || (bumper == VOORWAARTS)) {
        OCR1_RECHTS = 0;
        OCR1_LINKS = 0;
        delay_ms(200);                                          // nog even laten uitbollen
        motor(ALLEBEIACHTERWAARTSHALF_SPEED);               // Achteruit rijden
        for (cnt = HALF_SPEEDcnt < MAXIMUM_SPEEDcnt++) {    // gedurende 2 seconden
            if ((SENSOR_PORT & REARBUMPER) == 0) {              // En tussendoor de achterste bumper testen
                OCR1_RECHTS = 0;                                // Paniek! We zitten klem!
                OCR1_LINKS = 0;
                maaier(0);                                      // Maaier stoppen
                status = ERROR;                                 // Status aanpassen
                return;                                         // Lus verlaten
            } else {
                motor(ALLEBEIACHTERWAARTScnt);              // Versnellen
            }
            delay_ms(10);
        }
        // Nu gaan we draaien
        motor(RECHTSVOORWAARTSHALF_SPEED);                  // Rechtermotor vooruit
        motor(LINKSACHTERWAARTSHALF_SPEED);                 // Linkermotor achteruit
        for (cnt = 0cnt < B_timecnt++) {                    // 20 = 2 seconden draaien
            if ((SENSOR_PORT & REARBUMPER) == 0) {              // Achterste bumper testen
                motor(ALLEBEIVOORWAARTS5);                  // Beide motors stoppen
                break;                                          // De for()-lus verlaten
            } else if ((SENSOR_PORT & FRONTBUMPER) == 0) {      // Voorste bumper testen
                motor(ALLEBEIACHTERWAARTSHALF_SPEED);       // Achteruit rijden
                delay_ms(500);
                motor(RECHTSVOORWAARTSHALF_SPEED);
                motor(LINKSACHTERWAARTSHALF_SPEED);
            }
            delay_ms(80);
        }
        maaier(100);
        // Nu kunnen we (hopelijk) terug vooruit rijden
        motor(ALLEBEIVOORWAARTSMAXIMUM_SPEED);
        bumper = 0;
    }
}


void automatisch(void)
{
    unsigned int            cnt = 0;
    unsigned char           afteller = 0mode = ' ';

  HERSTART:

    for (cnt = 1000cnt > 200cnt--) {
        PINB |= BEEPER;                                         // Een andere manier om te beeper
        delay_us(cnt);
    }

    lcd_init();
    lcd_puts_P("AUTO-mode");

    status = START;

    while ((PIND & K_MANUEEL) == 0) {                           // Zolang de manueel-knop laag is
      AUTO_LOOP:

        check_aan_uit();                                        // AAN/UIT-knop ingedrukt?
        if (aan_uit == UIT) {                                   // De perimeter-routines kunnen "aan_uit" ook op UIT zetten!
            return;                                             // Terugkeren naar loop()
        }

        if ((PIND & NTC) == 0) {                                // Temperatuurvoelers testen
            motor(ALLEBEIVOORWAARTS5);
            maaier(0);
            lcd_clearline(1);
            lcd_puts_P("Temp to high!");
            for (cnt = 0cnt < 4cnt++) {
                beep(1000500);
                beep(500500);
            }
            cnt = 10;
            while ((PIND & K_MANUEEL) == 0) {
                check_aan_uit();                                // AAN/UIT-knop ingedrukt?
                if (aan_uit == UIT) {                           // De perimeter-routines kunnen "aan_uit" ook op UIT zetten!
                    return;                                     // Terugkeren naar loop()
                }
                if ((PIND & NTC) == 0) {                        // Nog te warm?
                    cnt = 100;
                }
                delay_ms(5000);
                cnt--;
                if (cnt == 0) {
                    goto HERSTART;
                }
            }                                                   // Handbediening is uit zijn houder,
            return;                                             // dus keren we terug naar loop()
        }

        afteller++;
        if (afteller > 9) {
            PINB |= BEEPER;                                     // Toggle de beeper-uitgang
            afteller = 0;                                       // zodat de LED knippert
            sprintf(tekst" t = %02u    %c"turntime / 10mode);
            lcd_clearline(2);
            lcd_puts(tekst);
            maaier(100);
        }

        switch (status) {                                       // Wat zijn we aan het doen?

        case START:                                             // We zijn pas opgestart
            lcd_clearline(2);                                   // Wis regel 2
            lcd_puts_P(" Start in 5 sec.");                     // Initieele tekst
            LCD_ENABLE();                                       // Pinnen als LCD-uitgang schakelen
            for (cnt = '4'cnt > '0'cnt--) {
                delay_ms(1000);
                beep(400200);
                lcd_command(_BV(LCD_DDRAM) | 0x4A);             // Waar de '5' staat
                delay_ms(1);
                lcd_char(cnt);                                  // Vervang '5' door '4', '3', ...
            }
            maaier(100);                                        // Start de maaier
            delay_ms(1000);                                     // Was eerst een beep !!!!!!!!!!!!
            lcd_clearline(2);
            lcd_puts_P(" Gestart");
            delay_ms(1000);
            motor(ALLEBEIVOORWAARTSMAXIMUM_SPEED);          // Volle kracht vooruit
            status = VOORWAARTS;                                // Status aanpassen
            turntime = get_turntime();                          // Na x seconden gaan we andersom
            mode = 'V';
            break;

        case VOORWAARTS:                                        // We rijden voorwaarts 
            turntime--;                                         // turntime met 1 verminderen
            if (((PIND & FRONTBUMPER) == 0) || (bumper == VOORWAARTS)) {
                OCR1_RECHTS = 0;
                OCR1_LINKS = 0;
                //if (bumper == VOORWAARTS) {                               // De voorste bumper raakt iets!
                delay_ms(200);                                  // nog even laten uitbollen
                motor(ALLEBEIACHTERWAARTSHALF_SPEED);       // Achteruit rijden
                for (cnt = HALF_SPEEDcnt < MAXIMUM_SPEEDcnt++) {    // gedurende 2 seconden
                    if ((SENSOR_PORT & REARBUMPER) == 0) {      // En tussendoor de achterste bumper testen
                        OCR1_RECHTS = 0;                        // Paniek! We zitten klem!
                        OCR1_LINKS = 0;
                        maaier(0);                              // Maaier stoppen
                        status = ERROR;                         // Status aanpassen
                        goto AUTO_LOOP;                         // Lus verlaten
                    } else {
                        motor(ALLEBEIACHTERWAARTScnt);      // Versnellen
                    }
                    delay_ms(10);
                }
                // Nu gaan we draaien
                motor(RECHTSVOORWAARTSHALF_SPEED);          // Rechtermotor vooruit
                motor(LINKSACHTERWAARTSHALF_SPEED);         // Linkermotor achteruit
                for (cnt = 0cnt < B_timecnt++) {            // 20 = 2 seconden draaien
                    if ((SENSOR_PORT & REARBUMPER) == 0) {      // Achterste bumper testen
                        motor(ALLEBEIVOORWAARTS5);          // Beide motors stoppen
                        break;                                  // De for()-lus verlaten
                    } else if ((SENSOR_PORT & FRONTBUMPER) == 0) {      // Voorste bumper testen
                        motor(ALLEBEIACHTERWAARTSHALF_SPEED);       // Achteruit rijden
                        delay_ms(500);
                        motor(RECHTSVOORWAARTSHALF_SPEED);
                        motor(LINKSACHTERWAARTSHALF_SPEED);
                    }
                    delay_ms(80);
                }
                maaier(100);
                // Nu kunnen we (hopelijk) terug vooruit rijden
                motor(ALLEBEIVOORWAARTSMAXIMUM_SPEED);
                bumper = 0;
            } else if ((P_RV < BOVENGRENS) || (P_LV < BOVENGRENS)) {    // V nadert de perimeter-draad
                delay_ms(20);                                   // Even wachten
                if ((P_RV < BOVENGRENS) || (P_LV < BOVENGRENS)) {       // Nogmaals testen
                    if (rm_debug == YES) {                      // Debug-mode aan?
                        perimeter_DEBUG();
                    } else {
                        perimeter();
                    }
                }
            } else if (P_LA < PM_ZIJWAARTS) {                   // LA nadert de perimeter-draad
                motor(RECHTSVOORWAARTSHALF_SPEED);          // Bocht naar rechts
                turn = YES;                                     // Noteren
                turntime = P_time;                              // 2 seconden
                mode = 'P';
            } else if (P_RA < PM_ZIJWAARTS) {                   // RA nadert de perimeter-draad
                motor(LINKSVOORWAARTSHALF_SPEED);           // Bocht naar links
                turn = YES;                                     // Noteren
                turntime = P_time;
                mode = 'P';
            }
            // Als de turntime om is, gaan we na wat we aan het doen waren.
            // Indien turn == YES, waren we aan het draaien. We gaan nu rechtdoor
            // Indien turn == NO, reden we rechtdoor. We gaan dan draaien
            if (turntime == 0) {                                // turntime is afgelopen
                if (turn == NO) {                               // We reden rechtdoor
                    if ((TCNT2 & 0x01) == 0) {
                        motor(LINKSVOORWAARTSKWART_SPEED);  // Bocht naar links
                        motor(RECHTSVOORWAARTSMAXIMUM_SPEED);
                    } else {
                        motor(RECHTSVOORWAARTSKWART_SPEED); // Bocht naar rechts
                        motor(LINKSVOORWAARTSMAXIMUM_SPEED);
                    }
                    turn = YES;                                 // Noteren
                    turntime = get_rand((MAX_DIRCHANGE / 2), MAX_DIRCHANGE);
                    mode = 'T';
                } else {                                        // turn = YES
                    motor(ALLEBEIVOORWAARTSMAXIMUM_SPEED);
                    turn = NO;
                    turntime = get_turntime();
                    motor(ALLEBEIVOORWAARTSMAXIMUM_SPEED);
                    mode = 'V';
                }
                maaier(100);
            }
            break;                                              // Einde case VOORWAARTS:

        case ERROR:                                             // Zaten we klem?
            if ((SENSOR_PORT & FRONTBUMPER) != 0) {             // Voorste bumper vrij?
                motor(ALLEBEIVOORWAARTSMAXIMUM_SPEED);      // We proberen vooruit te rijden
                maaier(100);                                    // En we starten de maaier terug
                status = VOORWAARTS;                            // Status aanpassen
                turntime = get_turntime();
            } else if ((SENSOR_PORT & REARBUMPER) != 0) {       // Achterste bumper vrij?
                motor(ALLEBEIACHTERWAARTSKWART_SPEED);      // We proberen achteruit te rijden
                delay_ms(400);
                motor(TURNLINKS30);                         // Ter plaatse draaien
                motor(ALLEBEIVOORWAARTSMAXIMUM_SPEED);      // We proberen vooruit te rijden
                maaier(100);                                    // En we starten de maaier terug
                status = VOORWAARTS;                            // Status aanpassen
                turntime = get_turntime();
            } else {
                beep(4000100);                                // Maak wat kabaal
            }
            break;

        default:                                                // Hier horen we niet te belanden
            status = START;
            break;
        }
        delay_ms(100);                                          // Zodat turntime = 200 ongeveer overeenkomt met 20 seconden
    }
    beep(2000200);
    motor(ALLEBEIVOORWAARTS5);                              // Manueel-knop gesloten; motors stilleggen
    delay_ms(200);                                              // Even wachten om contactdender te onderdukken
    beep(1000200);
}


// Handbediening, zolang het "manueel"-contact gesloten is
void manueel(void)
{
    unsigned char           toetsen = 0vorige_toetsen = 0set = NO;
    unsigned int            kn1 = 0kn2 = 0;

    lcd_init();
    lcd_puts_P("HAND-mode");

    while ((PIND & K_MANUEEL) != 0) {                           // Zolang K_MANUEEL hoog is...
        if (check_aan_uit() == UIT) {                           // AAN/UIT-knop ingedrukt?
            return;                                             // Terugkeren naar loop()
        }

        kn1 = KN_1;
        kn2 = KN_2;
        toetsen = 0;
        if (kn1 < R0k4) {                                       // 100R-toets ingedrukt
            // Reserve
        } else if (kn1 < R2k2) {                                // 2k2-toets ingedrukt
            toetsen = K_ACHTERUIT;
        } else if (kn1 < R5k6) {                                // 5k6-toets ingedrukt
            toetsen = K_VOORUIT;
        } else if (kn1 < R12k) {                                // 12k-toets ingedrukt
            toetsen = K_MESSEN;
        }

        if (kn2 < R0k4) {                                       // 100R-toets ingedrukt
            // Reserve
        } else if (kn2 < R2k2) {
            toetsen |= K_RECHTS;
        } else if (kn2 < R5k6) {
            toetsen |= K_LINKS;
        }

        if (toetsen != vorige_toetsen) {                        // Gewijzigde toestand!
            vorige_toetsen = toetsen;                           // Noteren
            set = NO;
            delay_ms(100);                                      // Even wachten ivm contactdender
            lcd_clearline(2);
            sprintf(tekst" %u    %u"kn1kn2);
            lcd_puts(tekst);
        } else if (set == NO) {                                 // Toestand = stabiel
            set = YES;
            switch (toetsen) {                                  // Welke is er ingedrukt?
            case K_VOORUIT:                                     // Enkel de vooruit-knop
                motor(ALLEBEIVOORWAARTSMAXIMUM_SPEED);
                break;
            case K_ACHTERUIT:                                   // Enkel de achteruit-knop
                motor(ALLEBEIACHTERWAARTSMAXIMUM_SPEED);
                break;
            case K_VOORUIT | K_LINKS:                           // Vooruit en links samen
                motor(LINKSVOORWAARTSHALF_SPEED);
                motor(RECHTSVOORWAARTSMAXIMUM_SPEED);
                break;
            case K_LINKS:                                       // Enkel de links-knop
                motor(LINKSVOORWAARTS5);
                motor(RECHTSVOORWAARTSMAXIMUM_SPEED);
                break;
            case K_VOORUIT | K_RECHTS:                          // Vooruit en rechts samen
                motor(RECHTSVOORWAARTSHALF_SPEED);
                motor(LINKSVOORWAARTSMAXIMUM_SPEED);
                break;
            case K_RECHTS:                                      // Enkel de rechts-knop
                motor(RECHTSVOORWAARTS5);
                motor(LINKSVOORWAARTSMAXIMUM_SPEED);
                break;
            case K_ACHTERUIT | K_LINKS:                 // Achteruit en links samen
                motor(LINKSACHTERWAARTSHALF_SPEED);
                motor(RECHTSACHTERWAARTSMAXIMUM_SPEED);
                break;
            case K_ACHTERUIT | K_RECHTS:                        // Achteruit en rechts samen
                motor(RECHTSACHTERWAARTSHALF_SPEED);
                motor(LINKSACHTERWAARTSMAXIMUM_SPEED);
                break;
            case K_MESSEN:
                if (OCR0B == 0) {                               // Als de maaier stilstaat
                    maaier(100);                                // starten we hem
                } else {                                        // In het andere geval
                    maaier(0);                                  // stoppen we de maaier
                }
                delay_ms(500);                                  // Contactdender vermijden
                break;
            case 0:
            default:                                            // Niets ingedrukt, of een verboden combinatie ingedrukt
                motor(ALLEBEIVOORWAARTS5);
                break;
            }
        }
    }
    motor(ALLEBEIVOORWAARTS5);                              // Manueel = laag; we stoppen er mee
}



int main(void)
{
    setup();
    delay_ms(1000);
    while (1) {
        check_aan_uit();
        if (aan_uit == AAN) {                                   // AAN/UIT-knop ingedrukt?
            if ((PIND & K_MANUEEL) == 0) {                      // Manueel-knop gesloten
                automatisch();
            } else {
                manueel();
            }
        } else if (KN_1 < 250) {                                // Andere toets ingedrukt?
            delay_ms(100);                                      // Even wachten...
            if (KN_1 < R2k2) {                                  // 2k2-toets ingedrukt (achteruit)
                rm_debug = NO;
                beep(3000200);
                lcd_clearline(2);
                lcd_puts_P("DEBUG = OFF");
                delay_ms(600);
            } else if (KN_1 < R5k6) {                           // 5k6-toets ingedrukt (vooruit)
                rm_debug = YES;
                beep(3000200);
                lcd_clearline(2);
                lcd_puts_P("DEBUG = ON");
                delay_ms(600);
            } else if (KN_1 < R12k) {                           // 12k-toets ingedrukt (messen)
                lcd_clrscr();
                sprintf(tekst" Nu: %2uminuten", (unsigned intuptime_minuten);       // Uptime tonen
                lcd_puts(tekst);
                lcd_gotoyx(20);
                sprintf(tekst"Was: %2uminuten", (unsigned intvorige_uptime_minuten);        // Vorige uptime tonen
                lcd_puts(tekst);
            }
        }
    }
}