Revision f115416e
ID | f115416e5ddb587db82174a69a40955b31973a99 |
Added initial BOM code
Only the sending code has been tested; receiving will soon be tested as
well.
scout_avr/src/main.cpp | ||
---|---|---|
42 | 42 |
|
43 | 43 |
#include "Atmega128rfa1.h" |
44 | 44 |
#include "range.h" |
45 |
#include "bom.h" |
|
45 | 46 |
|
46 | 47 |
int main() |
47 | 48 |
{ |
48 | 49 |
char buf[20]; |
50 |
int i; |
|
49 | 51 |
unsigned long now, next = 0; |
50 | 52 |
Atmega128rfa1 avr; |
51 | 53 |
avr.init(); |
52 | 54 |
range_init(); |
55 |
bom_init(); |
|
56 |
set_robot_id(0x2a); |
|
53 | 57 |
while (1) |
54 | 58 |
{ |
55 | 59 |
now = avr.time(); |
56 | 60 |
if (now > next) { |
57 | 61 |
next = now + 100; |
58 |
utoa(range_get(0), buf, 10); |
|
59 |
avr.write((uint8_t*) buf, strlen(buf)); |
|
60 |
avr.write((uint8_t*) ", ", 2); |
|
62 |
/*utoa(range_get(0), buf, 10); |
|
63 |
avr.puts("Range: "); |
|
64 |
avr.puts(buf); |
|
65 |
avr.puts(", "); |
|
61 | 66 |
utoa(range_get(1), buf, 10); |
62 |
avr.write((uint8_t*) buf, strlen(buf)); |
|
63 |
/*int data = avr.read(); |
|
64 |
if (data >= 0) |
|
65 |
{ |
|
66 |
uint8_t data8 = data; |
|
67 |
avr.write((uint8_t*) "Received ", 9); |
|
68 |
avr.write(&data8, 1); |
|
67 |
avr.puts(buf);*/ |
|
68 |
for (i = 0; i < 4; i++) { |
|
69 |
bom_send(i); |
|
70 |
int msg = bom_get(i); |
|
71 |
if (msg != BOM_NO_DATA) { |
|
72 |
avr.puts("BOM "); |
|
73 |
itoa(i, buf, 10); |
|
74 |
avr.puts(buf); |
|
75 |
avr.puts(": "); |
|
76 |
itoa(msg, buf, 10); |
|
77 |
avr.puts(buf); |
|
78 |
} |
|
69 | 79 |
} |
70 |
else |
|
71 |
avr.write((uint8_t*) ".", 1);*/ |
|
72 |
avr.write((uint8_t*) "\r\n", 2); |
|
80 |
avr.puts("\r\n"); |
|
73 | 81 |
} |
74 | 82 |
} |
75 | 83 |
return 0; |
Also available in: Unified diff