wpi-32u4-library
Rangefinder.cpp
Go to the documentation of this file.
1#include <Rangefinder.h>
2#include <pcint.h>
3
4#define ECHO_RECD 0x02
5
11Rangefinder::Rangefinder(uint8_t echo, uint8_t trig)
12{
13 echoPin = echo;
14 trigPin = trig;
15}
16
17// sets up the interface
19{
20 // assert ECHO pin is an input
21 pinMode(echoPin, INPUT);
22
23 // register the interrupt for the echo
24 if(digitalPinToInterrupt(echoPin) != NOT_AN_INTERRUPT)
25 {
26 Serial.println("Attaching rangefinder ISR");
27 attachInterrupt(digitalPinToInterrupt(echoPin), ::ISR_Rangefinder, CHANGE);
28 }
29 else if(digitalPinToPCInterrupt(echoPin) != NOT_AN_INTERRUPT)
30 {
31 Serial.println("Attaching rangefinder PC_ISR");
33 }
34 else
35 {
36 Serial.println("Not a rangefinder interrupt pin!");
37 }
38
39 //control pin for commanding pings must be an output
40 pinMode(trigPin, OUTPUT);
41}
42
52{
53 // if the echo pin is still high, just update the last ping time
54 if(digitalRead(echoPin)) lastPing = millis();
55
56 // check if we're ready to ping
57 if(millis() - lastPing >= pingInterval)
58 {
59 //disable interrupts while we adjust the ISR variables
60 cli();
61 pulseEnd = pulseStart = 0;
62
63 //clear out any leftover states
64 state = 0;
65 sei();
66
67 // keep track of when we sent the last ping
68 lastPing = millis();
69
70 // toggle the trigger pin to send a chirp
71 digitalWrite(trigPin, HIGH); //commands a ping; leave high for the duration
72 delayMicroseconds(30); //datasheet says hold HIGH for >20us; we'll use 30 to be 'safe'
73 digitalWrite(trigPin, LOW); //unclear if pin has to stay HIGH
74 }
75
76 return state;
77}
78
80{
81 uint16_t echoLength = 0;
82 if(state & ECHO_RECD)
83 {
84 cli();
85 echoLength = pulseEnd - pulseStart;
86 state &= ~ECHO_RECD;
87 sei();
88 }
89
90 return echoLength;
91}
92
94{
95 uint16_t pulseDur = checkEcho();
96 if(pulseDur) distance = pulseDur / 58.0;
97
98 // After we've checked for an echo, check to send the next ping
100
101 return distance;
102}
103
110{
111 if(digitalRead(echoPin)) //transitioned to HIGH
112 {
113 pulseStart = micros();
114 }
115
116 else //transitioned to LOW
117 {
118 pulseEnd = micros();
119 state |= ECHO_RECD;
120 }
121}
122
126{
128}
#define ECHO_RECD
Definition: Rangefinder.cpp:4
void ISR_Rangefinder(void)
Rangefinder rangefinder
volatile uint8_t state
Definition: Rangefinder.h:18
uint8_t checkPingTimer(void)
checkPingTimer() checks to see if it's time to send a new ping.
Definition: Rangefinder.cpp:51
Rangefinder(uint8_t echo, uint8_t trig)
Constructor.
Definition: Rangefinder.cpp:11
uint8_t echoPin
Definition: Rangefinder.h:20
float getDistance(void)
Returns the last recorded distance in cm. The first call to getDistance() will return 99.
Definition: Rangefinder.cpp:93
uint16_t checkEcho(void)
Definition: Rangefinder.cpp:79
uint8_t trigPin
Definition: Rangefinder.h:21
void ISR_echo(void)
ISR for the echo pin.
uint32_t lastPing
Definition: Rangefinder.h:24
volatile uint32_t pulseEnd
Definition: Rangefinder.h:33
void init(void)
Definition: Rangefinder.cpp:18
uint32_t pingInterval
Definition: Rangefinder.h:29
volatile uint32_t pulseStart
Definition: Rangefinder.h:32
float distance
Definition: Rangefinder.h:36
uint8_t digitalPinToPCInterrupt(uint8_t pin)
Definition: pcint.cpp:53
void attachPCInt(uint8_t pcInt, void(*pcisr)(void))
Attaches a function to a pin change interrupt.
Definition: pcint.cpp:12