24 Motor (byte direction, byte pwm, byte tachPin) {
25 directionPin = direction;
27 tachometerPin = tachPin;
29 minUsablePercent = 40;
30 maxUsablePercent = 100;
35 TCCR1B = (TCCR1B & B11111000) | 1;
45 pinMode(directionPin, OUTPUT);
46 pinMode(pwmPin, OUTPUT);
49 pinMode(tachometerPin, INPUT_PULLUP);
62 digitalWrite(directionPin, LOW);
65 digitalWrite(directionPin, HIGH);
83 percent = map(percent, 0, 100, minUsablePercent, maxUsablePercent);
84 }
else if (percent < 0) {
85 percent = map(percent, 0, -100, minUsablePercent, maxUsablePercent);
88 return 255 - (255 * abs(percent) / 100);
140 microsecondsBetweenLines = newTime - timeOfLastMeasurement;
141 timeOfLastMeasurement = newTime;
142 rotationsPerMinute = 24000000 / microsecondsBetweenLines;
149 return rotationsPerMinute;
156 return tachometerPin;
174 return digitalRead(directionPin);
185 if((percent < 0) || (percent > 100)){
189 minUsablePercent = percent;
199 return minUsablePercent;
208 return maxUsablePercent;
220 if((percent < minUsablePercent)){
222 }
else if((percent < 0) || (percent > 100)){
226 maxUsablePercent = percent;
231 byte minUsablePercent;
232 byte maxUsablePercent;
233 byte pwmPin, directionPin, tachometerPin;
234 unsigned long rotationsPerMinute, newTime, timeOfLastMeasurement, microsecondsBetweenLines;
void runMotor(double percent)
Definition: Motor.h:60
double percentage
Definition: Motor.h:15
bool setMaxUsablePercent(byte percent)
Definition: Motor.h:219
double turnPercentIntoPwm(double percent)
Definition: Motor.h:80
const byte FULL_OFF
Definition: Motor.h:13
byte getMaxUsablePercent()
Definition: Motor.h:207
void turnOnMotor()
Definition: Motor.h:101
void turnOffMotor()
Definition: Motor.h:94
void decreasePercentage(double step)
Definition: Motor.h:127
void increasePercentage(double step)
Definition: Motor.h:112
double getDirection()
Definition: Motor.h:173
double getPercentage()
Definition: Motor.h:164
void setupMotor()
Definition: Motor.h:44
Motor(byte direction, byte pwm, byte tachPin)
Definition: Motor.h:24
bool setMinimumUsablePercent(byte percent)
Definition: Motor.h:184
byte getTachAttachedPin()
Definition: Motor.h:155
void interruptServiceRoutine()
Definition: Motor.h:138
const byte FULL_ON
Definition: Motor.h:14
byte getMinUsablePercent()
Definition: Motor.h:198
unsigned long getRotationsPerMinute()
Definition: Motor.h:148