Project

General

Profile

Statistics
| Branch: | Revision:

scoutos / scout_avr / src / Atmega128rfa1.cpp @ 812788aa

History | View | Annotate | Download (2.27 KB)

1
#include "Atmega128rfa1.h"
2
#include "bom.h"
3

    
4
extern "C"
5
{
6
#include <avr/io.h>
7
#include <avr/interrupt.h>
8
  void __cxa_pure_virtual(void) {}
9
}
10

    
11
#define T0_KHZ 76
12
#define T0_OCR (F_CPU / 1000 / T0_KHZ) // 210 ticks
13
#define T0_ERROR (F_CPU / 1000 - T0_OCR*T0_KHZ) // 40 ticks/ms
14

    
15
unsigned char t0_count, t0_error;
16
unsigned long millis;
17

    
18
int rx_start = 0, rx_end = 0;
19
char rx_buffer[RX_BUFFER_SIZE];
20

    
21
Atmega128rfa1::Atmega128rfa1()
22
{
23
}
24

    
25
ISR(TIMER0_COMPA_vect)
26
{
27
  bom_isr();
28

    
29
  // F_CPU = T0_OCR * T0_KHZ + T0_ERROR
30
  // every millisecond, accumulate T0_ERROR, and when it reaches T0_OCR skip
31
  // one iteration
32
  t0_count++;
33
  if (t0_count >= T0_KHZ) {
34
    t0_error += T0_ERROR;
35
    if (t0_error < T0_OCR) {
36
      t0_count = 0;
37
    } else {
38
      t0_count = -1;
39
      t0_error -= T0_OCR;
40
    }
41
    millis++;
42
  }
43
}
44

    
45
ISR(USART0_RX_vect)
46
{
47
  char data = UDR0;
48
  if (rx_end == rx_start-1 || (rx_start == 0 && rx_end == RX_BUFFER_SIZE-1))
49
  {
50
    // TODO warn of buffer overflow?
51
  }
52
  else
53
  {
54
    rx_buffer[rx_end] = data;
55
    rx_end++;
56
    if (rx_end == RX_BUFFER_SIZE)
57
      rx_end = 0;
58
  }
59
}
60

    
61
void Atmega128rfa1::init()
62
{
63
  // === init serial ===
64
  // baud = F_CPU / (16 (UBRR + 1))
65
  uint16_t ubrr = F_CPU / 16 / BAUD_RATE - 1;
66
  UBRR0H = ubrr >> 8;
67
  UBRR0L = ubrr;
68
  // UMSEL0 = 0, asynchronous usart
69
  // UPM0 = 0, parity check disabled
70
  // USBS0 = 0, 1 stop bit
71
  // UCSZ0 = 3, 8-bit
72
  UCSR0B = _BV(RXCIE0) | _BV(RXEN0) | _BV(TXEN0);
73
  UCSR0C = _BV(UCSZ01) | _BV(UCSZ00);
74

    
75
  // === init time ===
76
  // COM0x = 0, pin OC0x not used
77
  // WGM0 = 2, clear timer on compare match, TOP = OCRA
78
  // CS0 = 1, no prescaler
79
  TCCR0A = _BV(WGM01);
80
  TCCR0B = _BV(CS00);
81
  // enable interrupt on compare match A
82
  TIMSK0 = _BV(OCIE0A);
83
  OCR0A = T0_OCR;
84
  millis = 0;
85

    
86
  sei();
87
}
88

    
89
int Atmega128rfa1::read()
90
{
91
  cli();
92
  if (rx_start == rx_end)
93
    return -1;
94
  else
95
  {
96
    int ret = rx_buffer[rx_start];
97
    rx_start++;
98
    if (rx_start == RX_BUFFER_SIZE)
99
      rx_start = 0;
100
    return ret;
101
  }
102
  sei();
103
}
104

    
105
void Atmega128rfa1::write(uint8_t* data, int length)
106
{
107
  // TODO make this non-blocking with a tx buffer
108
  int i;
109
  for (i = 0; i < length; i++)
110
  {
111
    while (!(UCSR0A & _BV(UDRE0)));
112
    UDR0 = data[i];
113
  }
114
}
115

    
116
unsigned long Atmega128rfa1::time()
117
{
118
  unsigned long ret;
119
  cli();
120
  ret = millis;
121
  sei();
122
  return ret;
123
}