Kinetic Sculpture  3.1
Software to Architecture for the Junior Kinetic Sculpture Project
 All Classes Files Functions Variables Macros Pages
Motor.h
Go to the documentation of this file.
1 
3 #pragma once
4 
11 class Motor{
12  public:
13  const byte FULL_OFF = 255;
14  const byte FULL_ON = 0;
15  double percentage = 0;
24  Motor (byte direction, byte pwm, byte tachPin) {
25  directionPin = direction;
26  pwmPin = pwm;
27  tachometerPin = tachPin;
28 
29  minUsablePercent = 40;
30  maxUsablePercent = 100;
31  /*
32  * Change the prescaler for timer 1 (used by the motor PWM) to increase the PWM frequency
33  * to 31250Hz so that it can not be heard (1=31250Hz, 2=3906Hz, 3=488Hz, 4=122Hz, 5=30.5Hz)
34  */
35  TCCR1B = (TCCR1B & B11111000) | 1;
36  setupMotor();
37  }
38 
44  void setupMotor() {
45  pinMode(directionPin, OUTPUT);
46  pinMode(pwmPin, OUTPUT);
47  analogWrite(pwmPin, FULL_OFF); //Write off to ensure motor is initialized to be off
48 
49  pinMode(tachometerPin, INPUT_PULLUP);
50  }
51 
60  void runMotor(double percent){
61  if(percent < 0){
62  digitalWrite(directionPin, LOW);
63  }
64  else{
65  digitalWrite(directionPin, HIGH);
66  }
67 
68  analogWrite(pwmPin, turnPercentIntoPwm(percent));
69  percentage = percent;
70  }
71 
80  double turnPercentIntoPwm(double percent){
81  // Maps the input percentage (0-100%) into a usable percentage for the motor based off minUsablePercent and maxUsablePercent
82  if (percent > 0) {
83  percent = map(percent, 0, 100, minUsablePercent, maxUsablePercent);
84  } else if (percent < 0) {
85  percent = map(percent, 0, -100, minUsablePercent, maxUsablePercent);
86  }
87 
88  return 255 - (255 * abs(percent) / 100);
89  }
90 
94  void turnOffMotor() {
95  analogWrite(pwmPin, FULL_OFF);
96  }
97 
101  void turnOnMotor() {
102  analogWrite(pwmPin, FULL_ON);
103  }
104 
112  void increasePercentage(double step){
113  if(percentage < 100){
114  percentage += step;
116  }
117  }
118 
127  void decreasePercentage(double step){
128  if(percentage > -100){
129  percentage -= step;
131  }
132  }
139  newTime = micros();
140  microsecondsBetweenLines = newTime - timeOfLastMeasurement;
141  timeOfLastMeasurement = newTime;
142  rotationsPerMinute = 24000000 / microsecondsBetweenLines;
143  }
144 
148  unsigned long getRotationsPerMinute(){
149  return rotationsPerMinute;
150  }
151 
156  return tachometerPin;
157  }
158 
164  double getPercentage(){
165  return percentage;
166  }
167 
173  double getDirection(){
174  return digitalRead(directionPin);
175  }
176 
184  bool setMinimumUsablePercent(byte percent){
185  if((percent < 0) || (percent > 100)){ //Ignore this request
186  return false;
187  }
188 
189  minUsablePercent = percent;
190  return true;
191  }
192 
199  return minUsablePercent;
200  }
201 
208  return maxUsablePercent;
209  }
210 
219  bool setMaxUsablePercent(byte percent){
220  if((percent < minUsablePercent)){ // If the percent is less than minUsablePercent return
221  return false;
222  }else if((percent < 0) || (percent > 100)){ // If the percent is negative or greater than 100
223  return false;
224  }
225 
226  maxUsablePercent = percent;
227  return true;
228  }
229 
230  private:
231  byte minUsablePercent;
232  byte maxUsablePercent;
233  byte pwmPin, directionPin, tachometerPin;
234  unsigned long rotationsPerMinute, newTime, timeOfLastMeasurement, microsecondsBetweenLines;
235 };
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
Definition: Motor.h:11
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