1
0

Greifer2.0.ino 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480
  1. #include <AS5600.h>
  2. #include "AX12A.h"
  3. #define DirectionPin (14u)
  4. #define BaudRate (1000000ul)
  5. #define ID1 (4u)
  6. #define ID2 (5u)
  7. #include <SoftwareSerial.h>
  8. #include <XYZrobotServo.h>
  9. //AS5600 Sensor
  10. #include <Wire.h>
  11. SoftwareSerial servoSerial(2, 4); //(18,19)
  12. int input = 0;
  13. XYZrobotServo servo1(servoSerial, 2);
  14. const uint8_t playtime = 100;
  15. const int max_angle = 712,min_angle = 312;
  16. const byte numChars = 32;
  17. int dir = 25; //16
  18. //int brake = 5;
  19. int pwma = 27;
  20. int speed = 0;
  21. int i;
  22. //int Turns = 7;
  23. //bool State = 0;
  24. volatile bool Startup = 0;
  25. volatile bool richtung;
  26. const byte Test_button = 14;
  27. const byte button_oben = 13; //25
  28. const byte button_unten = 26;
  29. int magnetStatus = 0; //value of the status register (MD, ML, MH)
  30. int lowbyte; //raw angle 7:0
  31. word highbyte; //raw angle 7:0 and 11:8
  32. int rawAngle; //final raw angle
  33. float degAngle; //raw angle in degrees (360/4096 * [value between 0-4095])
  34. int quadrantNumber, previousquadrantNumber; //quadrant IDs
  35. int numberofTurns = 0; //number of turns
  36. int lastnumberofTurns = 0;
  37. float correctedAngle = 0; //tared angle - based on the startup value
  38. float startAngle = 0; //starting angle
  39. float totalAngle = 0; //total absolute angular displacement
  40. float previoustotalAngle = 0; //for the display printing
  41. int sollposition; //von 0 bis 1 * totalTurns
  42. // initialize prozent to an invalid value
  43. int previousProzent = -1; // variable to store the previous valid value
  44. int prozent;
  45. int totalTurns; // number of Turns after Kalibration sollte ungefähr 33 entsprechen (23/0.7)
  46. int x ,position;
  47. int val[10] = {0,0,0,0,0};
  48. int choice;
  49. void IRAM_ATTR nachUnten(){
  50. richtung = HIGH;
  51. speed = 255;
  52. //sollposition = sollposition - 3;
  53. }
  54. void IRAM_ATTR nachOben(){
  55. richtung = LOW;
  56. speed = 255;
  57. //sollposition = sollposition + 3;
  58. }
  59. void IRAM_ATTR Start(){
  60. Startup = 1;
  61. }
  62. void setup() {
  63. Serial.begin(115200); //start serial - tip: don't use serial if you don't need it (speed considerations)
  64. Wire.begin();
  65. ax12a.begin(BaudRate, DirectionPin, &Serial2);
  66. ax12a.setEndless(ID1, OFF);
  67. ax12a.setEndless(ID2, OFF);
  68. ax12a.setMaxTorque(ID1, 1000);
  69. ax12a.setMaxTorque(ID2, 1000);
  70. servoSerial.begin(115200);
  71. ax12a.move(ID1,512);
  72. ax12a.move(ID2,512);
  73. servo1.setPosition(512, playtime);
  74. // pinMode(Turns, OUTPUT);
  75. pinMode(dir, OUTPUT);
  76. // pinMode(brake, OUTPUT);
  77. pinMode(pwma, OUTPUT);
  78. pinMode(button_oben, INPUT_PULLUP);
  79. pinMode(button_unten, INPUT_PULLUP);
  80. pinMode(Test_button, INPUT_PULLUP);
  81. //Kalibrieren();
  82. attachInterrupt(digitalPinToInterrupt(button_oben), nachUnten, FALLING);
  83. attachInterrupt(digitalPinToInterrupt(button_unten), nachOben, FALLING);
  84. attachInterrupt(digitalPinToInterrupt(Test_button), Start, FALLING);
  85. //start i2C
  86. //Wire.setClock(800000L); //fast clock
  87. checkMagnetPresence(); //check the magnet (blocks until magnet is found)
  88. ReadRawAngle(); //make a reading so the degAngle gets updated
  89. startAngle = degAngle; //update startAngle with degAngle - for taring
  90. }
  91. /*void motor(int prozent) {
  92. sollposition = (totalTurns * prozent * 0.01);
  93. Serial.print("sollposition: ");
  94. Serial.println(sollposition);
  95. if (sollposition > numberofTurns) {
  96. richtung = LOW;
  97. speed = 255;
  98. //Serial.println("Bewegung nach Oben");
  99. } else if (sollposition < numberofTurns) {
  100. richtung = HIGH;
  101. speed = 255;
  102. //Serial.println("Bewegung nach Unten");
  103. } else {
  104. speed = 0;
  105. Serial.println("In Sollposition");
  106. }
  107. }*/
  108. /*void Positionsabfrage() {
  109. if (prozent == -1 && Serial.available() > 0) { // check if prozent is not set and data is available to read
  110. int newProzent = Serial.parseInt(); // read the integer value from serial buffer
  111. if (newProzent >= 1 && newProzent <= 100) { // check if the value is within the valid range
  112. prozent = newProzent; // assign the new valid value to prozent
  113. previousProzent = prozent; // update previousProzent with the new valid value
  114. Serial.print("Received percentage value: ");
  115. Serial.println(prozent);
  116. } else {
  117. Serial.println("Invalid percentage value! Please enter a number between 0 and 100.");
  118. if (previousProzent != -1) { // check if there's a previous valid value
  119. prozent = previousProzent; // restore prozent to its previous valid value
  120. }
  121. }
  122. sollposition = (totalTurns * prozent * 0.01);
  123. Serial.print("sollposition: ");
  124. Serial.println(sollposition);
  125. prozent = -1;
  126. }
  127. }*/
  128. void loop() {
  129. /*if(Startup){
  130. Kalibrieren();
  131. Startup = 0;
  132. }
  133. //Positionsabfrage();
  134. */
  135. /* i++;
  136. if (i == 50) {
  137. Serial.print("NumberofTurns:");
  138. Serial.println(numberofTurns);
  139. //Serial.print("correctedAngle: ");
  140. //Serial.println(correctedAngle, 2);
  141. if (speed == 0) {
  142. Serial.println("In Sollposition");
  143. } else if (richtung == HIGH && speed == 255) {
  144. Serial.println("Bewegung nach Unten");
  145. } else if (richtung == LOW && speed == 255) {
  146. Serial.println("Bewegung nach Oben");
  147. }
  148. i = 0;*/
  149. if (Serial.available()){
  150. for(int n = 0; n < 10 ; n++){
  151. val[n] = Serial.read() - 48; //convert ASCII to int and assigns into array
  152. }
  153. position = 0;
  154. for (int i = 2; i < 5; i++) {
  155. position = position * 10 + val[i];
  156. }
  157. choice = val[0];
  158. Serial.print("Motor: ");
  159. Serial.print(choice);
  160. Serial.print(" position: ");
  161. Serial.print(position);
  162. switch (val[0]) {
  163. case 1:
  164. ax12_1(position);
  165. Serial.print("Ready");
  166. break;
  167. case 2:
  168. a116(position);
  169. Serial.print("Ready");
  170. break;
  171. case 3:
  172. ax12_2(position);
  173. Serial.print("Ready");
  174. break;
  175. case 4:
  176. //motor(position);
  177. prozent = position;
  178. sollposition = (totalTurns * prozent * 0.01);
  179. Serial.print("sollposition: ");
  180. Serial.println(sollposition);
  181. Serial.print("Ready");
  182. break;
  183. case 5:
  184. //auto_close();
  185. Serial.print("Ready");
  186. break;
  187. case 6:
  188. Kalibrieren();
  189. Serial.print("Ready");
  190. break;
  191. }
  192. }
  193. if (sollposition > numberofTurns) {
  194. richtung = LOW;
  195. speed = 255;
  196. //Serial.println("Bewegung nach Oben");
  197. } else if (sollposition < numberofTurns) {
  198. richtung = HIGH;
  199. speed = 255;
  200. //Serial.println("Bewegung nach Unten");
  201. }
  202. else {
  203. speed = 0;
  204. //Serial.println("In Sollposition");
  205. }
  206. digitalWrite(dir,richtung);
  207. analogWrite(pwma,speed);
  208. delay(50);
  209. ReadRawAngle(); //ask the value from the sensor
  210. correctAngle(); //tare the value
  211. checkQuadrant(); //check quadrant, check rotations, check absolute angular position
  212. i++;
  213. if (i == 50) {
  214. Serial.print("NumberofTurns:");
  215. Serial.println(numberofTurns);
  216. //Serial.print("correctedAngle: ");
  217. //Serial.println(correctedAngle, 2);
  218. if (speed == 0) {
  219. Serial.println("In Sollposition");
  220. } else if (richtung == HIGH && speed == 255) {
  221. Serial.println("Bewegung nach Unten");
  222. } else if (richtung == LOW && speed == 255) {
  223. Serial.println("Bewegung nach Oben");
  224. }
  225. i = 0;
  226. }
  227. }
  228. void ax12_1(int position){
  229. if((position<min_angle) || (position>max_angle)){
  230. Serial.print("invalide position. Try again");
  231. return;
  232. }
  233. ax12a.moveSpeed(ID1,position, playtime);
  234. }
  235. void ax12_2(int position){
  236. if((position<min_angle) || (position>max_angle)){
  237. Serial.print("invalide position. Try again");
  238. return;
  239. }
  240. ax12a.moveSpeed(ID2,position, playtime);
  241. }
  242. void a116(int position){
  243. if((position<min_angle) || (position>max_angle)){
  244. Serial.print("invalide position. Try again");
  245. return;
  246. }
  247. servo1.setPosition(position, playtime);
  248. }
  249. void Kalibrieren(){
  250. Serial.print("Start Kalibrieren");
  251. digitalWrite(dir,HIGH);
  252. analogWrite(pwma,255);
  253. Serial.println(digitalRead(button_unten));
  254. while(digitalRead(button_unten)){
  255. ReadRawAngle(); //ask the value from the sensor
  256. correctAngle(); //tare the value
  257. checkQuadrant();
  258. digitalWrite(dir,HIGH);
  259. analogWrite(pwma,255);
  260. }
  261. Serial.println("Archieved 0");
  262. numberofTurns = 0;
  263. while(digitalRead(button_oben)){
  264. ReadRawAngle(); //ask the value from the sensor
  265. correctAngle(); //tare the value
  266. checkQuadrant();
  267. digitalWrite(dir,LOW);
  268. analogWrite(pwma,255);
  269. }
  270. totalTurns = numberofTurns;
  271. Serial.print("TotalTurns:");
  272. Serial.println(totalTurns);
  273. sollposition = totalTurns * 0.5;
  274. while(numberofTurns != sollposition) {
  275. digitalWrite(dir,HIGH);
  276. analogWrite(pwma,255);
  277. ReadRawAngle(); //ask the value from the sensor
  278. correctAngle(); //tare the value
  279. checkQuadrant();
  280. }
  281. Serial.println("Kalib end");
  282. }
  283. void ReadRawAngle()
  284. {
  285. //7:0 - bits
  286. Wire.beginTransmission(0x36); //connect to the sensor
  287. Wire.write(0x0D); //figure 21 - register map: Raw angle (7:0)
  288. Wire.endTransmission(); //end transmission
  289. Wire.requestFrom(0x36, 1); //request from the sensor
  290. while(Wire.available() == 0); //wait until it becomes available
  291. lowbyte = Wire.read(); //Reading the data after the request
  292. //11:8 - 4 bits
  293. Wire.beginTransmission(0x36);
  294. Wire.write(0x0C); //figure 21 - register map: Raw angle (11:8)
  295. Wire.endTransmission();
  296. Wire.requestFrom(0x36, 1);
  297. while(Wire.available() == 0);
  298. highbyte = Wire.read();
  299. highbyte = highbyte << 8; //shifting to left
  300. rawAngle = highbyte | lowbyte; //int is 16 bits (as well as the word)
  301. //360/4096 = 0.087890625
  302. degAngle = rawAngle * 0.087890625;
  303. //Serial.print("Deg angle: ");
  304. //Serial.println(degAngle, 2); //absolute position of the encoder within the 0-360 circle
  305. }
  306. void correctAngle()
  307. {
  308. //recalculate angle
  309. correctedAngle = degAngle - startAngle; //this tares the position
  310. if(correctedAngle < 0) //if the calculated angle is negative, we need to "normalize" it
  311. {
  312. correctedAngle = correctedAngle + 360; //correction for negative numbers (i.e. -15 becomes +345)
  313. }
  314. else
  315. {
  316. //do nothing
  317. }
  318. //Serial.print("Corrected angle: ");
  319. //Serial.println(correctedAngle, 2); //print the corrected/tared angle
  320. }
  321. void checkQuadrant()
  322. {
  323. /*
  324. //Quadrants:
  325. 4 | 1
  326. ---|---
  327. 3 | 2
  328. */
  329. //Quadrant 1
  330. if(correctedAngle >= 0 && correctedAngle <=90)
  331. {
  332. quadrantNumber = 1;
  333. }
  334. //Quadrant 2
  335. if(correctedAngle > 90 && correctedAngle <=180)
  336. {
  337. quadrantNumber = 2;
  338. }
  339. //Quadrant 3
  340. if(correctedAngle > 180 && correctedAngle <=270)
  341. {
  342. quadrantNumber = 3;
  343. }
  344. //Quadrant 4
  345. if(correctedAngle > 270 && correctedAngle <360)
  346. {
  347. quadrantNumber = 4;
  348. }
  349. //Serial.print("Quadrant: ");
  350. //Serial.println(quadrantNumber); //print our position "quadrant-wise"
  351. if(quadrantNumber != previousquadrantNumber) //if we changed quadrant
  352. {
  353. if(quadrantNumber == 1 && previousquadrantNumber == 4)
  354. {
  355. numberofTurns--; // 4 --> 1 transition: CW rotation
  356. }
  357. if(quadrantNumber == 4 && previousquadrantNumber == 1)
  358. {
  359. numberofTurns++; // 1 --> 4 transition: CCW rotation
  360. }
  361. //this could be done between every quadrants so one can count every 1/4th of transition
  362. previousquadrantNumber = quadrantNumber; //update to the current quadrant
  363. }
  364. //Serial.print("Turns: ");
  365. //Serial.println(numberofTurns,0); //number of turns in absolute terms (can be negative which indicates CCW turns)
  366. //after we have the corrected angle and the turns, we can calculate the total absolute position
  367. totalAngle = (numberofTurns*360) + correctedAngle; //number of turns (+/-) plus the actual angle within the 0-360 range
  368. //Serial.print("Total angle: ");
  369. //Serial.println(totalAngle, 2); //absolute position of the motor expressed in degree angles, 2 digits
  370. }
  371. void checkMagnetPresence()
  372. {
  373. //This function runs in the setup() and it locks the MCU until the magnet is not positioned properly
  374. while((magnetStatus & 32) != 32) //while the magnet is not adjusted to the proper distance - 32: MD = 1
  375. {
  376. magnetStatus = 0; //reset reading
  377. Wire.beginTransmission(0x36); //connect to the sensor
  378. Wire.write(0x0B); //figure 21 - register map: Status: MD ML MH
  379. Wire.endTransmission(); //end transmission
  380. Wire.requestFrom(0x36, 1); //request from the sensor
  381. while(Wire.available() == 0); //wait until it becomes available
  382. magnetStatus = Wire.read(); //Reading the data after the request
  383. Serial.print("Magnet status: ");
  384. Serial.println(magnetStatus, BIN); //print it in binary so you can compare it to the table (fig 21)
  385. }
  386. //Status register output: 0 0 MD ML MH 0 0 0
  387. //MH: Too strong magnet - 100111 - DEC: 39
  388. //ML: Too weak magnet - 10111 - DEC: 23
  389. //MD: OK magnet - 110111 - DEC: 55
  390. //Serial.println("Magnet found!");
  391. //delay(1000);
  392. }