1
0

FullArmControl.ino 5.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244
  1. #include <AccelStepper.h>
  2. // Define the pins:
  3. // Stepper 0
  4. #define STEP_PIN0 2
  5. #define DIR_PIN0 30
  6. #define ENABLE_PIN0 31
  7. #define SENSOR_PIN0 32
  8. // Stepper 1
  9. #define STEP_PIN1 3
  10. #define DIR_PIN1 33
  11. #define ENABLE_PIN1 34
  12. #define SENSOR_PIN1 35
  13. // Stepper 2
  14. #define STEP_PIN2 4
  15. #define DIR_PIN2 36
  16. #define ENABLE_PIN2 37
  17. #define SENSOR_PIN2 38
  18. // Stepper 3
  19. #define STEP_PIN3 5
  20. #define DIR_PIN3 39
  21. #define ENABLE_PIN3 40
  22. #define SENSOR_PIN3 41
  23. // Define the steps per revolution of thr stepper motor
  24. const float STEPS_PER_REVOLUTION = 200.0;
  25. float i = 12; //Gear Transmission
  26. // Create myStepper Class and inherit AccelStepper
  27. class myStepper : public AccelStepper {
  28. public:
  29. myStepper(uint8_t interface = AccelStepper::FULL4WIRE, uint8_t pin1 = 2, uint8_t pin2 = 3, uint8_t sensorPin = 6, uint8_t enablePin = 7)
  30. : AccelStepper(interface, pin1, pin2, 9, 10, true), sensorPin(sensorPin), enablePin(enablePin) {}
  31. void rotateStepper(float degrees) {
  32. // Calculate the number of steps based on the desired angle
  33. float steps = degrees * (STEPS_PER_REVOLUTION / 360.0);
  34. // Move the stepper to the specified number of steps
  35. move(steps);
  36. // Disable the motor
  37. digitalWrite(enablePin, LOW);
  38. // Run the stepper until it reaches the target position
  39. while (distanceToGo() != 0) {
  40. run();
  41. }
  42. Serial.println(distanceToGo());
  43. // Enable the motor
  44. digitalWrite(enablePin, LOW);
  45. }
  46. void calibrateStepper() {
  47. while (digitalRead(sensorPin) == HIGH) {
  48. rotateStepper(1);
  49. delay(1);
  50. }
  51. }
  52. private:
  53. int sensorPin;
  54. int enablePin;
  55. };
  56. myStepper stepper0(AccelStepper::DRIVER, STEP_PIN0, DIR_PIN0, SENSOR_PIN0, ENABLE_PIN0);
  57. myStepper stepper1(AccelStepper::DRIVER, STEP_PIN1, DIR_PIN1, SENSOR_PIN1, ENABLE_PIN1);
  58. myStepper stepper2(AccelStepper::DRIVER, STEP_PIN2, DIR_PIN2, SENSOR_PIN2, ENABLE_PIN2);
  59. myStepper stepper3(AccelStepper::DRIVER, STEP_PIN3, DIR_PIN3, SENSOR_PIN3, ENABLE_PIN3);
  60. const byte numChars = 32;
  61. char receivedChars[numChars];
  62. char tempChars[numChars]; // temporary array for use when parsing
  63. // variables to hold the parsed data
  64. float moveToAngels[4] = { 0, 0, 0, 0 };
  65. int calibrateArm = 0;
  66. boolean newData = false;
  67. //============
  68. void setup() {
  69. Serial.begin(9600);
  70. // Set the maximum speed and acceleration (you can adjust these values)
  71. stepper0.setMaxSpeed(400);
  72. stepper0.setAcceleration(400.0);
  73. stepper1.setMaxSpeed(400);
  74. stepper1.setAcceleration(400.0);
  75. stepper2.setMaxSpeed(400);
  76. stepper2.setAcceleration(400.0);
  77. stepper3.setMaxSpeed(400);
  78. stepper3.setAcceleration(400.0);
  79. // Set the enable pin as an output and disable the motor by default
  80. pinMode(ENABLE_PIN0, OUTPUT);
  81. digitalWrite(ENABLE_PIN0, LOW);
  82. pinMode(SENSOR_PIN0, INPUT);
  83. pinMode(ENABLE_PIN1, OUTPUT);
  84. digitalWrite(ENABLE_PIN1, LOW);
  85. pinMode(SENSOR_PIN1, INPUT);
  86. pinMode(ENABLE_PIN2, OUTPUT);
  87. digitalWrite(ENABLE_PIN2, LOW);
  88. pinMode(SENSOR_PIN2, INPUT);
  89. pinMode(ENABLE_PIN3, OUTPUT);
  90. digitalWrite(ENABLE_PIN3, LOW);
  91. pinMode(SENSOR_PIN3, INPUT);
  92. // Set the motor direction (0 for clockwise, 1 for counter-clockwise)
  93. stepper0.setPinsInverted(false, false, true);
  94. stepper1.setPinsInverted(false, false, true);
  95. stepper2.setPinsInverted(false, false, true);
  96. stepper3.setPinsInverted(false, false, true);
  97. }
  98. //============
  99. void loop() {
  100. recvWithStartEndMarkers();
  101. if (newData == true) {
  102. strcpy(tempChars, receivedChars);
  103. // this temporary copy is necessary to protect the original data
  104. // because strtok() used in parseData() replaces the commas with \0
  105. parseData();
  106. showParsedData();
  107. newData = false;
  108. //check received values
  109. Serial.println(moveToAngels[3]);
  110. if (calibrateArm == 1) {
  111. stepper0.calibrateStepper();
  112. stepper1.calibrateStepper();
  113. stepper2.calibrateStepper();
  114. stepper3.calibrateStepper();
  115. } else {
  116. stepper0.rotateStepper(moveToAngels[0] * i);
  117. stepper1.rotateStepper(moveToAngels[1] * i);
  118. stepper2.rotateStepper(moveToAngels[2] * i);
  119. stepper3.rotateStepper(moveToAngels[3] * i);
  120. }
  121. //reset recieved values
  122. moveToAngels[0] = 0;
  123. moveToAngels[1] = 0;
  124. moveToAngels[2] = 0;
  125. moveToAngels[3] = 0;
  126. calibrateArm = 0;
  127. }
  128. }
  129. //============
  130. void recvWithStartEndMarkers() {
  131. static boolean recvInProgress = false;
  132. static byte ndx = 0;
  133. char startMarker = '<';
  134. char endMarker = '>';
  135. char rc;
  136. while (Serial.available() > 0 && newData == false) {
  137. rc = Serial.read();
  138. Serial.print(rc);
  139. if (recvInProgress == true) {
  140. if (rc != endMarker) {
  141. receivedChars[ndx] = rc;
  142. ndx++;
  143. if (ndx >= numChars) {
  144. ndx = numChars - 1;
  145. }
  146. } else {
  147. receivedChars[ndx] = '\0'; // terminate the string
  148. recvInProgress = false;
  149. ndx = 0;
  150. newData = true;
  151. }
  152. }
  153. else if (rc == startMarker) {
  154. recvInProgress = true;
  155. }
  156. }
  157. }
  158. //============
  159. void parseData() { // split the data into its parts
  160. char* strtokIndx; // this is used by strtok() as an index
  161. strtokIndx = strtok(tempChars, ","); // get the first part
  162. calibrateArm = atoi(strtokIndx); // convert this part to an integer
  163. strtokIndx = strtok(NULL, ","); // this continues where the previous call left off
  164. moveToAngels[0] = atoi(strtokIndx);
  165. strtokIndx = strtok(NULL, ",");
  166. moveToAngels[1] = atoi(strtokIndx); // convert this part to a float
  167. strtokIndx = strtok(NULL, ",");
  168. moveToAngels[2] = atof(strtokIndx); // convert this part to a float
  169. strtokIndx = strtok(NULL, ",");
  170. moveToAngels[3] = atof(strtokIndx); // convert this part to a float
  171. }
  172. //============
  173. // For debugging purposes
  174. void showParsedData() {
  175. Serial.print("Calibration: ");
  176. Serial.println(calibrateArm);
  177. Serial.print("Stepper1 ");
  178. Serial.println(moveToAngels[0]);
  179. Serial.print("Stepper2 ");
  180. Serial.println(moveToAngels[1]);
  181. Serial.print("Stepper3 ");
  182. Serial.println(moveToAngels[2]);
  183. Serial.print("Stepper4 ");
  184. Serial.println(moveToAngels[3]);
  185. }