Gripper.ino 4.1 KB

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