Kinetic Sculpture  3.1
Software to Architecture for the Junior Kinetic Sculpture Project
 All Classes Files Functions Variables Macros Pages
Disc.h
Go to the documentation of this file.
1 
3 #pragma once
4 #include "Motor.h"
5 
6 #define MAX_RPM 30
14 class Disc{
15  public:
25  Disc(Motor* attachedMotor) {
26  motor = attachedMotor;
27  motor->setupMotor();
28  }
29 
39  void updateSpeed(float desiredRpm) {
40  if(desiredRpm > 30){ //If the desired RPM is greater than max run at max
41  desiredRpm = MAX_RPM;
42  }else if(desiredRpm < -30){
43  desiredRpm = -1 * MAX_RPM;
44  }
45 
46  delay(100);
47  float tachRpm = motor->getRotationsPerMinute();
48  double motorPercentage = motor->getPercentage();
49  float desiredDiscRpm = desiredRpm;
50  long desiredTachRpm = desiredDiscRpm * 1250; //converts DiscRpm to Tach rpm
51  long desireMin = desiredTachRpm - 1000; //Creates a lower bound on rpm
52  long desireMax = desiredTachRpm + 1000; //Creates an upper bound on rpm
53 
54  while (tachRpm > desireMax or tachRpm < desireMin){ //Runs until Rpm is within 10% of desired value
55  delay(100);
56  tachRpm = motor->getRotationsPerMinute();
57  motorPercentage = motor->getPercentage();
58  byte dir = motor->getDirection();
59  if (dir == 0){
60  tachRpm = -tachRpm;
61  }
62  if (desiredTachRpm > tachRpm){
63  motor->increasePercentage(double((desiredTachRpm-tachRpm)/10000));
64  }
65  else if(desiredTachRpm < tachRpm){
66  motor->decreasePercentage(double((tachRpm-desiredTachRpm)/10000));
67  }
68  }
69  }
75  unsigned long getRotationsPerMinute(){
76  return motor->getRotationsPerMinute();
77  }
78 
82  void setISR(){
83  motor->interruptServiceRoutine();
84  }
85 
91  void turnOnMotor(){
92  motor->turnOnMotor();
93  }
94 
100  void turnOffMotor(){
101  motor->turnOffMotor();
102  }
103 
110  void runDisc(double percent){
111  motor->runMotor(percent);
112  }
113 
120  int randRpm = rand() % MAX_RPM;
121  int randDir = pow(-1, rand() % 2); //Randomly generate -1 or 1 to determine the direction of rotation
122 
123  updateSpeed(randRpm * randDir);
124  }
125 
134  bool setMinMotorPercentage(byte percent){
135  return motor->setMinimumUsablePercent(percent);
136  }
137 
146  bool setMaxMotorPercentage(byte percent){
147  return motor->setMaxUsablePercent(percent);
148  }
149 
150  private:
151 };
Motor * motor
Definition: Disc.h:16
#define MAX_RPM
Definition: Disc.h:6
unsigned long getRotationsPerMinute()
Definition: Disc.h:75
void runMotor(double percent)
Definition: Motor.h:60
bool setMinMotorPercentage(byte percent)
Definition: Disc.h:134
void setISR()
Definition: Disc.h:82
bool setMaxUsablePercent(byte percent)
Definition: Motor.h:219
void turnOnMotor()
Definition: Disc.h:91
void turnOffMotor()
Definition: Disc.h:100
Definition: Motor.h:11
void turnOnMotor()
Definition: Motor.h:101
Disc(Motor *attachedMotor)
Definition: Disc.h:25
void turnOffMotor()
Definition: Motor.h:94
void decreasePercentage(double step)
Definition: Motor.h:127
void updateSpeed(float desiredRpm)
Definition: Disc.h:39
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
bool setMinimumUsablePercent(byte percent)
Definition: Motor.h:184
void runDisc(double percent)
Definition: Disc.h:110
bool setMaxMotorPercentage(byte percent)
Definition: Disc.h:146
void interruptServiceRoutine()
Definition: Motor.h:138
unsigned long getRotationsPerMinute()
Definition: Motor.h:148
void runDiscRandomly()
Definition: Disc.h:119