3 #include "freertos/FreeRTOS.h" 4 #include "freertos/task.h" 5 #include "freertos/semphr.h" 6 #define MAX_POSSIBLE_INTERRUPT_RANGEFINDER 4 31 void attach(
int trigger,
int echo);
51 portMUX_TYPE
synch = portMUX_INITIALIZER_UNLOCKED;
float getDistanceCM()
get the distance of an object from the sensor in centimeters
static int getTimeoutState()
Function used by the timeout check thread to determine if this object has timed out.
static Rangefinder * list[MAX_POSSIBLE_INTERRUPT_RANGEFINDER]
list of attached rangefinders
void sensorISR()
The method called from the ISR indicating the echo pin changed state.
static bool timoutThreadStarted
long getRoundTripTimeMicroSeconds()
get the time of latest round trip in microseconds
Rangefinder objects wrap a FreeRTOS thread with pin change interrupts to read trigger/echo style ultr...
#define MAX_POSSIBLE_INTERRUPT_RANGEFINDER
volatile unsigned long startTime
static void checkTimeout()
check the current state of timeout and fire if its time to do so
static int numberOfFinders
void attach(int trigger, int echo)
Attach 2 pins to be used as triger and echo.
static void fire()
fire a strobe of the trig pin
volatile unsigned long roundTripTime