Project

General

Profile

Statistics
| Revision:

root / branches / encoders / code / projects / libdragonfly / spi.c @ 565

History | View | Annotate | Download (3.57 KB)

1
/* @file spi.c
2
 * @brief
3
 * SPI module
4
 * @bug broken
5
 */
6

    
7
#include <avr/interrupt.h>
8
#include "ring_buffer.h"
9
#include "spi.h"
10
#include <dragonfly_lib.h>
11

    
12

    
13
/*
14
SS = PB0
15
SCK = PB1
16
MOSI = PB2
17
MISO = PB3
18
*/
19
/* Controls clock freq. see Table 72 of specs*/
20

    
21
#define DOUBLE_SCK 1
22
#define SPR0_BIT 1
23
#define SPR1_BIT 0
24
#define LSB 1
25
#define MSB 0
26

    
27

    
28
RING_BUFFER_NEW(spi_buffer, 16, char, spi_send_buff, spi_rec_buff);
29
volatile char spi_status;
30
char spi_mode;
31
static spi_fun_recv_t  spi_recv_function;
32
//static spi_fun_send_t  spi_send_function;
33

    
34

    
35
void spi_init(char mode, spi_fun_recv_t recv_func) {
36
    usb_puts("spi_init: start\n");
37

    
38
        spi_mode = mode;
39

    
40
        RING_BUFFER_CLEAR(spi_send_buff);
41
        RING_BUFFER_CLEAR(spi_rec_buff);
42

    
43
        spi_recv_function = recv_func;
44
        //spi_send_function = send_func;
45

    
46
    /* Enables the SPI module
47
     * Enable Interrupt, Enable SPI Module, LSB First, Master Mode, Clock div = 64
48
     */
49
    SPCR = 0x00;
50
    if (spi_mode == MASTER) {
51
            SPCR = _BV(SPIE) | _BV(SPE) | _BV(DORD) | _BV(MSTR)| _BV(SPR1) | _BV(SPR0);
52
    } else {
53
            SPCR = _BV(SPIE) | _BV(SPE) | _BV(DORD) | ~_BV(MSTR)| _BV(SPR1) | _BV(SPR0);
54
    }
55
            
56
    SPSR = 0x00;
57
        SPSR = _BV(SPI2X); 
58
        
59
        spi_status = SPI_IDLE;
60

    
61
    /* Set SCLK, SS, MOSI as outputs. MISO as input */
62
        if(spi_mode == MASTER) {
63
            DDRB |= MOSI | SCLK | SS;
64
            DDRB &= ~MISO;
65
                PORTB |= SS;        //Keep SS High until transmit
66
        /* Set SCLK, SS, MOSI as inputs. MISO as output */
67
        } else {
68
            DDRB &= ~MOSI & ~SCLK & ~SS;
69
            DDRB |= MISO;
70
    }
71
        
72
        //sei();
73
        //usb_puts("spi_init: end\n");
74
}
75

    
76
int spi_send(char *data, int bytes) {
77

    
78
        int i;
79

    
80
    if(bytes == 0) 
81
        return -1; /* ...needed?*/
82
    
83
    //Prevent race condition on the buffer
84
    cli();
85
    for(i = 1; i < bytes; i++) {
86
        // Fail if the buffer is full
87
            if(RING_BUFFER_FULL(spi_send_buff)) {
88
                sei();
89
                return -1;
90
            }
91
        
92
            RING_BUFFER_ADD(spi_send_buff, data[i]);
93
    }
94
    
95
    sei();
96
    
97
    spi_status |= SPI_SEND;
98
        
99
        if (spi_mode == MASTER ){
100
                PORTB &= ~SS;        //Select slave
101
        }
102
        
103
    SPDR = *data;
104
    /*
105
        if(spi_mode)
106
                usb_puts("MASTER");
107
        else
108
                usb_puts("SLAVE");
109
                
110
        usb_puts(": sending [");usb_putc(*data);usb_puts("]\n\r");
111
        */
112
        //sei();
113
        
114
        return 1;
115
}
116

    
117
void spi_read(int bytes) {
118
    
119
    cli();
120
    for(int i = 1; i < bytes; i++) {
121
        // Fail if the buffer is full
122
            if(RING_BUFFER_FULL(spi_send_buff)) {
123
                sei();
124
                return;
125
            }
126
        
127
            RING_BUFFER_ADD(spi_send_buff, '0');
128
    }
129
    
130
    sei();
131

    
132
    spi_status |= SPI_RECV;
133
        
134
        if (spi_mode == MASTER ){
135
                PORTB &= ~SS;        //Select slave
136
        }
137
        
138
    SPDR = '0';
139

    
140
}
141

    
142
void spi_read_one(void)
143
{
144
        PORTB &= ~SS;
145
        SPDR = 'x';
146
}
147

    
148
ISR(SIG_SPI) {
149
        char c;
150

    
151
        //You always receive something. You need to handle it before you overwrite it.
152
    spi_recv_function(SPDR);        
153

    
154
    //The clock is running so dequeue another byte to send        
155
        if(!RING_BUFFER_EMPTY(spi_send_buff)) {//cheap way to test if SPI_SEND
156
                RING_BUFFER_REMOVE(spi_send_buff, c);
157
                SPDR = c;
158
        //If we're the master and we're done sending, end the transmission
159
        } else if (spi_mode == MASTER) {
160
            PORTB |= SS;
161
        } else if (spi_mode == SLAVE) {
162
            SPDR = '0';
163
        }
164
        
165

    
166
    
167
        /*
168
        if(spi_status & SPI_SEND) {
169
                spi_status ^= SPI_SEND;
170
                
171
        if (spi_mode == MASTER) {
172
                    PORTB |= SS;
173
        }
174
    } else if (spi_status & SPI_RECV) {
175
           
176
    }
177
    */
178
    //End the transmission if we are not sending or recieving anymore
179
        //} else if(spi_mode == MASTER) {
180
        //   PORTB |= SS;
181
        //}
182
        
183
        //Call the recv function whenver we recieve a byte
184
        //if(spi_status == SPI_RECV){
185
                //spi_recv_function(SPDR);
186
                //if(spi_mode == MASTER)
187
                        //PORTB |= SS;
188
        //}
189
}                
190