farmbot-arduino-firmware/src/PinGuardPin.cpp

37 lines
648 B
C++
Raw Normal View History

2016-04-08 16:19:45 -06:00
#include "PinGuardPin.h"
PinGuardPin::PinGuardPin() {
pinNr = 0;
}
// Set the initial settings for what pin to check
void PinGuardPin::loadPinConfig(int newPinNr, bool newActiveState, int newTimeOut) {
pinNr = newPinNr;
activeState = newActiveState;
timeOut = newTimeOut;
timeOutCount = 0;
}
// Check each second if the time out is lapsed or the value has changed
void PinGuardPin::processTick() {
if (pinNr==0) {
return;
}
currentStatePin = digitalRead(pinNr);
if (currentStatePin != activeState) {
timeOutCount = 0;
} else {
timeOutCount++;
}
if (timeOutCount >= timeOut) {
digitalWrite(pinNr, !activeState);
}
}