Details | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
66 | jan-hendri | 1 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
2 | // + Regler für Brushless-Motoren |
||
3 | // + ATMEGA8 mit 8MHz |
||
4 | // + (c) 01.2007 Holger Buss |
||
5 | // + Nur für den privaten Gebrauch |
||
6 | // + Keine Garantie auf Fehlerfreiheit |
||
7 | // + Kommerzielle Nutzung nur mit meiner Zustimmung |
||
8 | // + Der Code ist für die Hardware BL_Ctrl V1.0 entwickelt worden |
||
9 | // + www.mikrocontroller.com |
||
10 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
||
11 | |||
12 | #include "main.h" |
||
13 | #include "uart.h" |
||
14 | |||
15 | #define MAX_SENDE_BUFF 100 |
||
16 | #define MAX_EMPFANGS_BUFF 100 |
||
17 | |||
18 | unsigned volatile char SIO_Sollwert = 0; |
||
19 | unsigned volatile char SioTmp = 0; |
||
20 | unsigned volatile char SendeBuffer[MAX_SENDE_BUFF]; |
||
21 | unsigned volatile char RxdBuffer[MAX_EMPFANGS_BUFF]; |
||
22 | unsigned volatile char NeuerDatensatzEmpfangen = 0; |
||
23 | unsigned volatile char UebertragungAbgeschlossen = 1; |
||
24 | unsigned char MeineSlaveAdresse; |
||
25 | unsigned char MotorTest[4] = {0,0,0,0}; |
||
26 | unsigned volatile char AnzahlEmpfangsBytes = 0; |
||
27 | |||
28 | struct str_DebugOut DebugOut; |
||
29 | |||
30 | |||
31 | int Debug_Timer; |
||
32 | |||
33 | |||
34 | SIGNAL(INT_VEC_TX) |
||
35 | { |
||
36 | } |
||
37 | |||
38 | void SendUart(void) |
||
39 | { |
||
40 | static unsigned int ptr = 0; |
||
41 | unsigned char tmp_tx; |
||
42 | if(!(UCSRA & 0x40)) return; |
||
43 | if(!UebertragungAbgeschlossen) |
||
44 | { |
||
45 | ptr++; // die [0] wurde schon gesendet |
||
46 | tmp_tx = SendeBuffer[ptr]; |
||
47 | if((tmp_tx == '\r') || (ptr == MAX_SENDE_BUFF)) |
||
48 | { |
||
49 | ptr = 0; |
||
50 | UebertragungAbgeschlossen = 1; |
||
51 | } |
||
52 | USR |= (1<TXC); |
||
53 | UDR = tmp_tx; |
||
54 | } |
||
55 | else ptr = 0; |
||
56 | } |
||
57 | |||
58 | // -------------------------------------------------------------------------- |
||
59 | void Decode64(unsigned char *ptrOut, unsigned char len, unsigned char ptrIn,unsigned char max) // Wohin mit den Daten; Wie lang; Wo im RxdBuffer |
||
60 | { |
||
61 | unsigned char a,b,c,d; |
||
62 | unsigned char ptr = 0; |
||
63 | unsigned char x,y,z; |
||
64 | while(len) |
||
65 | { |
||
66 | a = RxdBuffer[ptrIn++] - '='; |
||
67 | b = RxdBuffer[ptrIn++] - '='; |
||
68 | c = RxdBuffer[ptrIn++] - '='; |
||
69 | d = RxdBuffer[ptrIn++] - '='; |
||
70 | if(ptrIn > max - 2) break; // nicht mehr Daten verarbeiten, als empfangen wurden |
||
71 | |||
72 | x = (a << 2) | (b >> 4); |
||
73 | y = ((b & 0x0f) << 4) | (c >> 2); |
||
74 | z = ((c & 0x03) << 6) | d; |
||
75 | |||
76 | if(len--) ptrOut[ptr++] = x; else break; |
||
77 | if(len--) ptrOut[ptr++] = y; else break; |
||
78 | if(len--) ptrOut[ptr++] = z; else break; |
||
79 | } |
||
80 | |||
81 | } |
||
82 | |||
83 | |||
84 | //+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
||
85 | //++ Empfangs-Part der Datenübertragung |
||
86 | //+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
||
87 | SIGNAL(INT_VEC_RX) |
||
88 | { |
||
89 | |||
90 | #if X3D_SIO == 1 |
||
91 | static unsigned char serPacketCounter = 100; |
||
92 | SioTmp = UDR; |
||
93 | if(SioTmp == 0xF5) // Startzeichen |
||
94 | { |
||
95 | serPacketCounter = 0; |
||
96 | } |
||
97 | else |
||
98 | { |
||
99 | if(++serPacketCounter == MotorAdresse) // (1-4) |
||
100 | { |
||
101 | SIO_Sollwert = SioTmp; |
||
102 | SIO_Timeout = 200; // werte für 200ms gültig |
||
103 | } |
||
104 | else |
||
105 | { |
||
106 | if(serPacketCounter > 100) serPacketCounter = 100; |
||
107 | } |
||
108 | } |
||
109 | #else |
||
110 | static unsigned int crc; |
||
111 | static unsigned char crc1,crc2,buf_ptr; |
||
112 | static unsigned char UartState = 0; |
||
113 | unsigned char CrcOkay = 0; |
||
114 | |||
115 | SioTmp = UDR; |
||
116 | if(buf_ptr >= MAX_EMPFANGS_BUFF) UartState = 0; |
||
117 | if(SioTmp == '\r' && UartState == 2) |
||
118 | { |
||
119 | UartState = 0; |
||
120 | crc -= RxdBuffer[buf_ptr-2]; |
||
121 | crc -= RxdBuffer[buf_ptr-1]; |
||
122 | crc %= 4096; |
||
123 | crc1 = '=' + crc / 64; |
||
124 | crc2 = '=' + crc % 64; |
||
125 | CrcOkay = 0; |
||
126 | if((crc1 == RxdBuffer[buf_ptr-2]) && (crc2 == RxdBuffer[buf_ptr-1])) CrcOkay = 1; else { CrcOkay = 0; }; |
||
127 | if(CrcOkay) // Datensatz schon verarbeitet |
||
128 | { |
||
129 | //NeuerDatensatzEmpfangen = 1; |
||
130 | AnzahlEmpfangsBytes = buf_ptr; |
||
131 | |||
132 | RxdBuffer[buf_ptr] = '\r'; |
||
133 | if(/*(RxdBuffer[1] == MeineSlaveAdresse || (RxdBuffer[1] == 'a')) && */(RxdBuffer[2] == 'R')) wdt_enable(WDTO_250MS); // Reset-Commando |
||
134 | uart_putchar(RxdBuffer[2]); |
||
135 | if (RxdBuffer[2] == 't') // Motortest |
||
136 | { Decode64((unsigned char *) &MotorTest[0],sizeof(MotorTest),3,AnzahlEmpfangsBytes); |
||
137 | SIO_Sollwert = MotorTest[MotorAdresse - 1]; |
||
138 | SIO_Timeout = 500; // werte für 500ms gültig |
||
139 | |||
140 | } |
||
141 | } |
||
142 | } |
||
143 | else |
||
144 | switch(UartState) |
||
145 | { |
||
146 | case 0: |
||
147 | if(SioTmp == '#' && !NeuerDatensatzEmpfangen) UartState = 1; // Startzeichen und Daten schon verarbeitet |
||
148 | buf_ptr = 0; |
||
149 | RxdBuffer[buf_ptr++] = SioTmp; |
||
150 | crc = SioTmp; |
||
151 | break; |
||
152 | case 1: // Adresse auswerten |
||
153 | UartState++; |
||
154 | RxdBuffer[buf_ptr++] = SioTmp; |
||
155 | crc += SioTmp; |
||
156 | break; |
||
157 | case 2: // Eingangsdaten sammeln |
||
158 | RxdBuffer[buf_ptr] = SioTmp; |
||
159 | if(buf_ptr < MAX_EMPFANGS_BUFF) buf_ptr++; |
||
160 | else UartState = 0; |
||
161 | crc += SioTmp; |
||
162 | break; |
||
163 | default: |
||
164 | UartState = 0; |
||
165 | break; |
||
166 | } |
||
167 | |||
168 | |||
169 | #endif |
||
170 | }; |
||
171 | |||
172 | |||
173 | // -------------------------------------------------------------------------- |
||
174 | void AddCRC(unsigned int wieviele) |
||
175 | { |
||
176 | unsigned int tmpCRC = 0,i; |
||
177 | for(i = 0; i < wieviele;i++) |
||
178 | { |
||
179 | tmpCRC += SendeBuffer[i]; |
||
180 | } |
||
181 | tmpCRC %= 4096; |
||
182 | SendeBuffer[i++] = '=' + tmpCRC / 64; |
||
183 | SendeBuffer[i++] = '=' + tmpCRC % 64; |
||
184 | SendeBuffer[i++] = '\r'; |
||
185 | UebertragungAbgeschlossen = 0; |
||
186 | UDR = SendeBuffer[0]; |
||
187 | } |
||
188 | |||
189 | |||
190 | // -------------------------------------------------------------------------- |
||
191 | void SendOutData(unsigned char cmd,unsigned char modul, unsigned char *snd, unsigned char len) |
||
192 | { |
||
193 | unsigned int pt = 0; |
||
194 | unsigned char a,b,c; |
||
195 | unsigned char ptr = 0; |
||
196 | |||
197 | |||
198 | SendeBuffer[pt++] = '#'; // Startzeichen |
||
199 | SendeBuffer[pt++] = modul; // Adresse (a=0; b=1,...) |
||
200 | SendeBuffer[pt++] = cmd; // Commando |
||
201 | |||
202 | while(len) |
||
203 | { |
||
204 | if(len) { a = snd[ptr++]; len--;} else a = 0; |
||
205 | if(len) { b = snd[ptr++]; len--;} else b = 0; |
||
206 | if(len) { c = snd[ptr++]; len--;} else c = 0; |
||
207 | SendeBuffer[pt++] = '=' + (a >> 2); |
||
208 | SendeBuffer[pt++] = '=' + (((a & 0x03) << 4) | ((b & 0xf0) >> 4)); |
||
209 | SendeBuffer[pt++] = '=' + (((b & 0x0f) << 2) | ((c & 0xc0) >> 6)); |
||
210 | SendeBuffer[pt++] = '=' + ( c & 0x3f); |
||
211 | } |
||
212 | AddCRC(pt); |
||
213 | } |
||
214 | |||
215 | |||
216 | |||
217 | //############################################################################ |
||
218 | //Routine für die Serielle Ausgabe |
||
219 | int uart_putchar (char c) |
||
220 | //############################################################################ |
||
221 | { |
||
222 | if (c == '\n') |
||
223 | uart_putchar('\r'); |
||
224 | //Warten solange bis Zeichen gesendet wurde |
||
225 | loop_until_bit_is_set(USR, UDRE); |
||
226 | //Ausgabe des Zeichens |
||
227 | UDR = c; |
||
228 | |||
229 | return (0); |
||
230 | } |
||
231 | |||
232 | // -------------------------------------------------------------------------- |
||
233 | void WriteProgramData(unsigned int pos, unsigned char wert) |
||
234 | { |
||
235 | } |
||
236 | |||
237 | //############################################################################ |
||
238 | //INstallation der Seriellen Schnittstelle |
||
239 | void UART_Init (void) |
||
240 | //############################################################################ |
||
241 | { |
||
242 | //Enable TXEN im Register UCR TX-Data Enable & RX Enable |
||
243 | |||
244 | UCR=(1 << TXEN) | (1 << RXEN); |
||
245 | // UART Double Speed (U2X) |
||
246 | USR |= (1<<U2X); |
||
247 | // RX-Interrupt Freigabe |
||
248 | |||
249 | UCSRB |= (1<<RXCIE); // serieller Empfangsinterrupt |
||
250 | |||
251 | // TX-Interrupt Freigabe |
||
252 | // UCSRB |= (1<<TXCIE); |
||
253 | |||
254 | //Teiler wird gesetzt |
||
255 | UBRR= (SYSCLK / (BAUD_RATE * 8L) -1 ); |
||
256 | //öffnet einen Kanal für printf (STDOUT) |
||
257 | fdevopen (uart_putchar, NULL); |
||
258 | Debug_Timer = SetDelay(200); |
||
259 | // Version beim Start ausgeben (nicht schön, aber geht... ) |
||
260 | uart_putchar ('\n');uart_putchar ('B');uart_putchar ('L');uart_putchar (':'); |
||
261 | uart_putchar ('V');uart_putchar (0x30 + VERSION_HAUPTVERSION);uart_putchar ('.');uart_putchar (0x30 + VERSION_NEBENVERSION/10); uart_putchar (0x30 + VERSION_NEBENVERSION%10); |
||
262 | uart_putchar ('\n');uart_putchar ('A');uart_putchar ('D');uart_putchar ('R'); uart_putchar (':'); uart_putchar (0x30 + MotorAdresse); |
||
263 | |||
264 | } |
||
265 | |||
266 | |||
267 | |||
268 | |||
269 | //--------------------------------------------------------------------------------------------- |
||
270 | void DatenUebertragung(void) |
||
271 | { |
||
272 | if((CheckDelay(Debug_Timer) && UebertragungAbgeschlossen)) // im Singlestep-Betrieb in jedem Schtitt senden |
||
273 | { |
||
274 | SendOutData('D',MeineSlaveAdresse,(unsigned char *) &DebugOut,sizeof(DebugOut)); |
||
275 | Debug_Timer = SetDelay(50); // Sendeintervall |
||
276 | } |
||
277 | } |