wpi-32u4-library
Public Member Functions | Protected Attributes
Rangefinder Class Reference

A class to manage the HC-SR04 ultrasonic rangefinder. More...

#include <Rangefinder.h>

Public Member Functions

 Rangefinder (uint8_t echo, uint8_t trig)
 Constructor. More...
 
void init (void)
 
uint8_t checkPingTimer (void)
 checkPingTimer() checks to see if it's time to send a new ping. More...
 
uint16_t checkEcho (void)
 
float getDistance (void)
 Returns the last recorded distance in cm. The first call to getDistance() will return 99. More...
 
void ISR_echo (void)
 ISR for the echo pin. More...
 

Protected Attributes

volatile uint8_t state = 0
 
uint8_t echoPin = -1
 
uint8_t trigPin = -1
 
uint32_t lastPing = 0
 
uint32_t pingInterval = 10
 
volatile uint32_t pulseStart = 0
 
volatile uint32_t pulseEnd = 0
 
float distance = 99
 

Detailed Description

A class to manage the HC-SR04 ultrasonic rangefinder.

Uses a TRIG and ECHO pin to send chirps and detect round trip time.

The object rangefinder is declared extern to work with the ISRs, which means you must define your object with the same name:

Rangefinder rangefinder(<echo>, <trigger>);

Definition at line 15 of file Rangefinder.h.

Constructor & Destructor Documentation

◆ Rangefinder()

Rangefinder::Rangefinder ( uint8_t  echo,
uint8_t  trig 
)

Constructor.

Parameters
echoThe echo pin. Must be interrupt enabled. PCInts OK.
trigThe trigger pin.

Definition at line 11 of file Rangefinder.cpp.

References echoPin, and trigPin.

Member Function Documentation

◆ checkEcho()

uint16_t Rangefinder::checkEcho ( void  )

Definition at line 79 of file Rangefinder.cpp.

References ECHO_RECD, pulseEnd, pulseStart, and state.

Referenced by getDistance().

◆ checkPingTimer()

uint8_t Rangefinder::checkPingTimer ( void  )

checkPingTimer() checks to see if it's time to send a new ping.

You can make the pingInterval arbitrarily small, since it won't send a ping if the ECHO pin is HIGH.

getDistance() calls this function, so you don't need to call this function manually.

Definition at line 51 of file Rangefinder.cpp.

References echoPin, lastPing, pingInterval, pulseEnd, pulseStart, state, and trigPin.

Referenced by getDistance().

◆ getDistance()

float Rangefinder::getDistance ( void  )

Returns the last recorded distance in cm. The first call to getDistance() will return 99.

Definition at line 93 of file Rangefinder.cpp.

References checkEcho(), checkPingTimer(), and distance.

◆ init()

void Rangefinder::init ( void  )

◆ ISR_echo()

void Rangefinder::ISR_echo ( void  )

ISR for the echo pin.

Records both the start and stop (rise and fall) of the echo pin. When the pin goes low, it sets a flag.

Definition at line 109 of file Rangefinder.cpp.

References ECHO_RECD, echoPin, pulseEnd, pulseStart, and state.

Referenced by ISR_Rangefinder().

Field Documentation

◆ distance

float Rangefinder::distance = 99
protected

Definition at line 36 of file Rangefinder.h.

Referenced by getDistance().

◆ echoPin

uint8_t Rangefinder::echoPin = -1
protected

Definition at line 20 of file Rangefinder.h.

Referenced by checkPingTimer(), init(), ISR_echo(), and Rangefinder().

◆ lastPing

uint32_t Rangefinder::lastPing = 0
protected

Definition at line 24 of file Rangefinder.h.

Referenced by checkPingTimer().

◆ pingInterval

uint32_t Rangefinder::pingInterval = 10
protected

Definition at line 29 of file Rangefinder.h.

Referenced by checkPingTimer().

◆ pulseEnd

volatile uint32_t Rangefinder::pulseEnd = 0
protected

Definition at line 33 of file Rangefinder.h.

Referenced by checkEcho(), checkPingTimer(), and ISR_echo().

◆ pulseStart

volatile uint32_t Rangefinder::pulseStart = 0
protected

Definition at line 32 of file Rangefinder.h.

Referenced by checkEcho(), checkPingTimer(), and ISR_echo().

◆ state

volatile uint8_t Rangefinder::state = 0
protected

Definition at line 18 of file Rangefinder.h.

Referenced by checkEcho(), checkPingTimer(), and ISR_echo().

◆ trigPin

uint8_t Rangefinder::trigPin = -1
protected

Definition at line 21 of file Rangefinder.h.

Referenced by checkPingTimer(), init(), and Rangefinder().


The documentation for this class was generated from the following files: