RBE1001Lib
|
Rangefinder objects wrap a FreeRTOS thread with pin change interrupts to read trigger/echo style ultrasonic sensors. More...
#include <Rangefinder.h>
Public Member Functions | |
Rangefinder () | |
void | attach (int trigger, int echo) |
Attach 2 pins to be used as triger and echo. More... | |
long | getRoundTripTimeMicroSeconds () |
get the time of latest round trip in microseconds More... | |
float | getDistanceCM () |
get the distance of an object from the sensor in centimeters More... | |
void | sensorISR () |
The method called from the ISR indicating the echo pin changed state. More... | |
Static Public Member Functions | |
static void | checkTimeout () |
check the current state of timeout and fire if its time to do so More... | |
static void | fire () |
fire a strobe of the trig pin More... | |
static int | getTimeoutState () |
Function used by the timeout check thread to determine if this object has timed out. More... | |
Data Fields | |
portMUX_TYPE | synch = portMUX_INITIALIZER_UNLOCKED |
int | echoPin |
int | triggerPin |
volatile unsigned long | startTime |
volatile unsigned long | roundTripTime |
Static Public Attributes | |
static int | numberOfFinders = 0 |
static bool | timoutThreadStarted = false |
static int | pingIndex = 0 |
static bool | forceFire = false |
static Rangefinder * | list [MAX_POSSIBLE_INTERRUPT_RANGEFINDER] = { NULL, } |
list of attached rangefinders More... | |
Rangefinder objects wrap a FreeRTOS thread with pin change interrupts to read trigger/echo style ultrasonic sensors.
Rangefinder objects can be declared statically
Range is calculated continuously and the current measurement is retrieved with getDistanceCM()
Many objects can be declared, and they are pinged one at a time in a round-robbin configuration to prevent echo and cross-talk.
When pins are attached, the thread is started. The thread checks for timeouts and re sets the round-robbin.
This library supports up to 4 range finders
Definition at line 21 of file Rangefinder.h.
Rangefinder::Rangefinder | ( | ) |
Definition at line 136 of file Rangefinder.cpp.
void Rangefinder::attach | ( | int | trigger, |
int | echo | ||
) |
Attach 2 pins to be used as triger and echo.
The trigger pin needs to be an output, and the echo pin needs to have CHANGE interrupts.
Interrupts are managed through Arduio attachInterrupt()
Definition at line 92 of file Rangefinder.cpp.
References complexHandlerTaskUS, echoPin, MAX_POSSIBLE_INTERRUPT_RANGEFINDER, numberOfFinders, onTimer(), sensorISR0(), sensorISR1(), sensorISR2(), sensorISR3(), timoutThreadStarted, and triggerPin.
Referenced by setup().
|
static |
check the current state of timeout and fire if its time to do so
Definition at line 44 of file Rangefinder.cpp.
References fire(), and getTimeoutState().
Referenced by onTimer().
|
static |
fire a strobe of the trig pin
this will initiate a chirp and wait for the echo to come back
Definition at line 66 of file Rangefinder.cpp.
References forceFire, numberOfFinders, pingIndex, threadTimeout, and triggerPin.
Referenced by checkTimeout(), and onTimer().
float Rangefinder::getDistanceCM | ( | ) |
get the distance of an object from the sensor in centimeters
Definition at line 153 of file Rangefinder.cpp.
References getRoundTripTimeMicroSeconds().
Referenced by loop(), and updateDashboard().
long Rangefinder::getRoundTripTimeMicroSeconds | ( | ) |
get the time of latest round trip in microseconds
Definition at line 143 of file Rangefinder.cpp.
References roundTripTime, and synch.
Referenced by getDistanceCM().
|
static |
Function used by the timeout check thread to determine if this object has timed out.
Definition at line 40 of file Rangefinder.cpp.
References threadTimeout.
Referenced by checkTimeout().
void Rangefinder::sensorISR | ( | ) |
The method called from the ISR indicating the echo pin changed state.
This method is called by the static method for the associated interrupt.
Definition at line 82 of file Rangefinder.cpp.
References echoPin, forceFire, roundTripTime, startTime, and synch.
Referenced by sensorISR0(), sensorISR1(), sensorISR2(), and sensorISR3().
int Rangefinder::echoPin |
GPIO pin number for the echo
Definition at line 55 of file Rangefinder.h.
Referenced by attach(), and sensorISR().
|
static |
flag to force a fire from the timeout thread
Definition at line 47 of file Rangefinder.h.
Referenced by fire(), onTimer(), and sensorISR().
|
static |
list of attached rangefinders
when attach completes, a pointer to the object being attahced is added to this list. THis list is read from the timeout thread and Fire in order to run the round-robbin of all sensors.
Definition at line 80 of file Rangefinder.h.
|
static |
running count of attached range finders
Definition at line 35 of file Rangefinder.h.
|
static |
which index in the round robbin to ping
Definition at line 43 of file Rangefinder.h.
Referenced by fire().
volatile unsigned long Rangefinder::roundTripTime |
the cached time of the latest sensor read.
Definition at line 67 of file Rangefinder.h.
Referenced by getRoundTripTimeMicroSeconds(), and sensorISR().
volatile unsigned long Rangefinder::startTime |
portMUX_TYPE Rangefinder::synch = portMUX_INITIALIZER_UNLOCKED |
synchronization object to lock out access to volitile memory
Definition at line 51 of file Rangefinder.h.
Referenced by getRoundTripTimeMicroSeconds(), and sensorISR().
|
static |
flag to keep track of the state of the thread, started or not
Definition at line 39 of file Rangefinder.h.
Referenced by attach().
int Rangefinder::triggerPin |
GPIO pin for the trigger
Definition at line 59 of file Rangefinder.h.