wpi-32u4-library
Rangefinder.h
Go to the documentation of this file.
1#pragma once
2
3#include <Arduino.h>
4
16{
17protected:
18 volatile uint8_t state = 0;
19
20 uint8_t echoPin = -1;
21 uint8_t trigPin = -1;
22
23 // for keeping track of ping intervals
24 uint32_t lastPing = 0;
25
26 // we set the pingInterval to 10 ms, but it won't actually ping that fast
27 // since it _only_ pings if the ECHO pin is low -- that is, it will ping
28 // in 10 ms or when the last echo is done, whichever is _longer_
29 uint32_t pingInterval = 10;
30
31 // for keeping track of echo duration
32 volatile uint32_t pulseStart = 0;
33 volatile uint32_t pulseEnd = 0;
34
35 // holds the last recorded distance
36 float distance = 99;
37
38public:
39 Rangefinder(uint8_t echo, uint8_t trig);
40
41 // must call init() to set up pins and interrupts
42 void init(void);
43
44 // checks to see if it's time to emit a ping
45 uint8_t checkPingTimer(void);
46
47 // checks to see if an echo is complete
48 uint16_t checkEcho(void);
49
53 float getDistance(void);
54
55 // ISR for the echo pin
56 void ISR_echo(void);
57};
58
59// ISR for the echo
60void ISR_Rangefinder(void);
61
62// we declare as extern so we can refer to it in the ISR
Rangefinder rangefinder
void ISR_Rangefinder(void)
A class to manage the HC-SR04 ultrasonic rangefinder.
Definition: Rangefinder.h:16
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