farmbot-arduino-firmware/src/PinGuardPin.cpp

40 lines
857 B
C++
Raw Normal View History

2016-04-08 16:19:45 -06:00
#include "PinGuardPin.h"
2016-08-28 08:48:26 -06:00
#include "ParameterList.h"
2016-04-08 16:19:45 -06:00
PinGuardPin::PinGuardPin() {
pinNr = 0;
}
// Set the initial settings for what pin to check
2016-05-02 15:14:01 -06:00
void PinGuardPin::loadPinConfig(int pinNrParamNr, int activeStateParamNr, int timeOutParamNr) {
pinNr = ParameterList::getInstance()->getValue(pinNrParamNr);
activeState = (ParameterList::getInstance()->getValue(activeStateParamNr)== 1);
timeOut = ParameterList::getInstance()->getValue(timeOutParamNr);
2016-04-08 16:19:45 -06:00
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);
}
}