scoutos / scout_avr / src / range.cpp @ 399f7d1b
History | View | Annotate | Download (1.8 KB)
1 |
extern "C" |
---|---|
2 |
{ |
3 |
#include <avr/io.h> |
4 |
#include <avr/interrupt.h> |
5 |
} |
6 |
#include "range.h" |
7 |
|
8 |
/* Ultrasonic Sensor:
|
9 |
* -if RX pin is left open, it will continuously take readings
|
10 |
* -PW output is 147us/in.
|
11 |
* -PW will be high for a maximum of 37.5ms if no target is detected
|
12 |
*
|
13 |
* 37.5ms * 8 MHz / 8 prescaler = 37500 max wait
|
14 |
* 37.5ms * 16 MHz / 8 prescaler = problem
|
15 |
* 37.5ms * 16 MHz / 64 prescaler = 9375 max wait
|
16 |
*/
|
17 |
|
18 |
struct range_t {
|
19 |
unsigned int start; // timer value on rising edge |
20 |
unsigned int value; // last measured range |
21 |
char done;
|
22 |
} volatile range[2]; |
23 |
|
24 |
static void on_edge(int which) |
25 |
{ |
26 |
unsigned char int_high; |
27 |
unsigned int time = TCNT5; |
28 |
|
29 |
if (which)
|
30 |
{ |
31 |
int_high = PIN_SONAR_PWM & _BV(P_SONAR_PWM1); |
32 |
} |
33 |
else
|
34 |
{ |
35 |
int_high = PIN_SONAR_PWM & _BV(P_SONAR_PWM0); |
36 |
} |
37 |
|
38 |
if (int_high)
|
39 |
{ |
40 |
range[which].start = time; |
41 |
} |
42 |
else
|
43 |
{ |
44 |
PORT_SONAR_TX &= ~ _BV(P_SONAR_TX); |
45 |
// if timer overflowed since start, this arithmetic should still work out
|
46 |
range[which].value = time - range[which].start; |
47 |
range[which].done = 1;
|
48 |
} |
49 |
} |
50 |
|
51 |
ISR(INT3_vect) |
52 |
{ |
53 |
on_edge(0);
|
54 |
} |
55 |
|
56 |
ISR(INT2_vect) |
57 |
{ |
58 |
on_edge(1);
|
59 |
} |
60 |
|
61 |
void range_init()
|
62 |
{ |
63 |
// ISCx = 1, edge triggered
|
64 |
EICRA |= _BV(ISC20) | _BV(ISC30); |
65 |
// enable INT2 and INT3
|
66 |
EIMSK |= _BV(INT2) | _BV(INT3); |
67 |
|
68 |
// CS1 = 3, 1/64 prescaler
|
69 |
// if this is changed, remember to change recv_edge in bom.cpp!
|
70 |
TCCR5B = _BV(CS50) | _BV(CS51); |
71 |
|
72 |
// set tx as output
|
73 |
DDRG |= _BV(DDG1); |
74 |
PORT_SONAR_TX &= ~ _BV(P_SONAR_TX); |
75 |
} |
76 |
|
77 |
void range_measure(unsigned int *values) |
78 |
{ |
79 |
int i;
|
80 |
|
81 |
for (i = 0; i < 2; i++) |
82 |
{ |
83 |
range[i].value = RANGE_ERR; |
84 |
range[i].done = 0;
|
85 |
} |
86 |
|
87 |
// TODO ensure that one interrupt won't be delayed because of the other
|
88 |
PORT_SONAR_TX |= _BV(P_SONAR_TX); |
89 |
|
90 |
for (i = 0; i < 2; i++) |
91 |
{ |
92 |
while (!range[i].done) {}
|
93 |
values[i] = range[i].value; |
94 |
} |
95 |
} |