Gripper.ino 3.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172
  1. #include "Arduino.h"
  2. #include "AX12A.h"
  3. #define DirectionPin (10u)
  4. #define BaudRate (1000000ul)
  5. #define ID1 (4u)
  6. #define ID2 (5u)
  7. #include <XYZrobotServo.h>
  8. #ifdef SERIAL_PORT_HARDWARE_OPEN
  9. #define servoSerial SERIAL_PORT_HARDWARE_OPEN
  10. #else
  11. #include <SoftwareSerial.h>
  12. SoftwareSerial servoSerial(10, 11);
  13. #endif
  14. int input = 0;
  15. XYZrobotServo servo1(servoSerial, 2);
  16. const uint8_t playtime = 100;
  17. const int max_angle = 712,min_angle = 312;
  18. const byte button_oben = 20;
  19. const byte button_unten = 21;
  20. int ain1 = 4;
  21. int ain2 = 5;
  22. int pwma = 8;
  23. int x ,position;
  24. int val[10] = {0,0,0,0,0};
  25. int choice;
  26. void ax12_1(int position){
  27. if((position<min_angle) || (position>max_angle)){
  28. Serial.print("invalide position. Try again");
  29. return;
  30. }
  31. ax12a.moveSpeed(ID1,position, playtime);
  32. }
  33. void ax12_2(int position){
  34. if((position<min_angle) || (position>max_angle)){
  35. Serial.print("invalide position. Try again");
  36. return;
  37. }
  38. ax12a.moveSpeed(ID2,position, playtime);
  39. }
  40. void a116(int position){
  41. if((position<min_angle) || (position>max_angle)){
  42. Serial.print("invalide position. Try again");
  43. return;
  44. }
  45. servo1.setPosition(position, playtime);
  46. }
  47. void motor(int speed, int dir){
  48. if (dir == 0){
  49. digitalWrite(ain1,HIGH);
  50. digitalWrite(ain2,LOW);
  51. }
  52. else{
  53. digitalWrite(ain1,LOW);
  54. digitalWrite(ain2,HIGH);
  55. }
  56. analogWrite(pwma,speed);
  57. }
  58. void auto_close(){
  59. // Serial.print("Servo 1: ");
  60. // Serial.println(ax12a.readLoad(ID1));
  61. // Serial.print("Servo 2: ");
  62. // Serial.println(ax12a.readLoad(ID2));
  63. // delay(300);
  64. while(((ax12a.readLoad(ID1)<1450)) && (ax12a.readLoad(ID2)<1400)){
  65. Serial.print("Servo 1: ");
  66. Serial.println(ax12a.readLoad(ID1));
  67. Serial.print("Servo 2: ");
  68. Serial.println(ax12a.readLoad(ID2));
  69. ax12a.move(ID1,max_angle);
  70. ax12a.move(ID2,min_angle);
  71. }
  72. ax12a.move(ID1,ax12a.readPosition(ID1)+10);
  73. ax12a.move(ID2,ax12a.readPosition(ID2)-10);
  74. }
  75. void setup() {
  76. Serial.begin(9600);
  77. Serial.setTimeout(1);
  78. ax12a.begin(BaudRate, DirectionPin, &Serial3);
  79. ax12a.setEndless(ID1, OFF);
  80. ax12a.setEndless(ID2, OFF);
  81. ax12a.setMaxTorque(ID1, 1000);
  82. ax12a.setMaxTorque(ID2, 1000);
  83. servoSerial.begin(115200);
  84. ax12a.move(ID1,512);
  85. ax12a.move(ID2,512);
  86. servo1.setPosition(512, playtime);
  87. pinMode(button_oben,INPUT_PULLUP);
  88. pinMode(button_unten,INPUT_PULLUP);
  89. attachInterrupt(digitalPinToInterrupt(button_oben),interrupt1, LOW);
  90. attachInterrupt(digitalPinToInterrupt(button_unten),interrupt2,LOW);
  91. }
  92. void loop() {
  93. //Serial.print("Servo 1: ");
  94. //Serial.println(ax12a.readLoad(ID1));
  95. //Serial.print("Servo 2: ");
  96. //Serial.println(ax12a.readLoad(ID2));
  97. //delay(300);
  98. if (Serial.available()){
  99. //Serial.print(test);
  100. for(int n = 0; n < 10 ; n++){
  101. val[n] = Serial.readString().toInt();
  102. }
  103. position = 0 ;
  104. for(int i = 2; i < 5;i++){
  105. position = position * 10 + val[i];
  106. }
  107. choice = val[0];
  108. Serial.print("Motor: ");
  109. Serial.print(choice);
  110. Serial.print(" position: ");
  111. Serial.print(position);
  112. switch(val[0]){
  113. case 1:
  114. ax12_1(position);
  115. Serial.print("Ready");
  116. break;
  117. case 2:
  118. a116(position);
  119. Serial.print("Ready");
  120. break;
  121. case 3:
  122. ax12_2(position);
  123. Serial.print("Ready");
  124. break;
  125. case 4:
  126. motor(position,val[1]);
  127. Serial.print("Ready");
  128. break;
  129. case 5:
  130. auto_close();
  131. Serial.print("Ready");
  132. break;
  133. }
  134. }
  135. }
  136. void interrupt1(){
  137. //Serial.println("interrupt button oben");
  138. digitalWrite(36,HIGH);
  139. motor(254,1);
  140. motor(0,1);
  141. digitalWrite(36,LOW);
  142. }
  143. void interrupt2(){
  144. //Serial.println("interrupt button unten");
  145. digitalWrite(36,HIGH);
  146. motor(254,0);
  147. motor(0,0);
  148. digitalWrite(36,LOW);
  149. }