farmbot-arduino-firmware/src/PinControl.cpp

72 lines
1.2 KiB
C++
Raw Normal View History

2014-09-04 15:42:34 -06:00
#include "PinControl.h"
static PinControl* instance;
PinControl * PinControl::getInstance() {
if (!instance) {
instance = new PinControl();
};
return instance;
}
;
PinControl::PinControl() {
}
2014-09-09 14:28:54 -06:00
int PinControl::setMode(int pinNr, int mode) {
2014-09-10 09:21:17 -06:00
pinMode(pinNr , mode );
2014-09-04 15:42:34 -06:00
return 0;
}
2014-09-13 16:53:55 -06:00
int PinControl::writeValue(int pinNr, int value, int mode) {
if (mode == 0) {
digitalWrite(pinNr, value);
return 0;
}
if (mode == 1) {
analogWrite(pinNr, value);
return 0;
}
return 1;
2014-09-04 15:42:34 -06:00
}
2014-09-13 16:53:55 -06:00
int PinControl::readValue(int pinNr, int mode) {
int value = 0;
if (mode == 0) {
if (digitalRead(pinNr) == 1){
2014-09-13 16:53:55 -06:00
value = 1;
}
}
if (mode == 1) {
value = analogRead(pinNr);
}
2014-10-18 13:55:30 -06:00
if (mode == 0 || mode == 1) {
2014-09-13 16:53:55 -06:00
2014-10-18 13:55:30 -06:00
Serial.print("R41");
Serial.print(" ");
Serial.print("P");
Serial.print(pinNr);
Serial.print(" ");
Serial.print("V");
Serial.print(value);
2016-10-02 15:43:39 -06:00
//Serial.print("\r\n");
CurrentState::getInstance()->printQAndNewLine();
2014-10-18 13:55:30 -06:00
return 0;
}
else {
return 1;
}
2014-09-04 15:42:34 -06:00
}
2014-09-13 16:53:55 -06:00
int PinControl::writePulse(int pinNr, int valueOne, int valueTwo, long time, int mode) {
writeValue( pinNr, valueOne, mode);
delay(time);
2014-09-13 16:53:55 -06:00
writeValue( pinNr, valueTwo, mode);
return 0;
}