Gripper.ino 2.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109
  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 = 200;
  18. int x;
  19. int val[10] = {0,0,0,0,0};
  20. int position,lastposition_ax12 = 512;
  21. int choice;
  22. void ax12(int position){
  23. if((position<300) || (position>700)){
  24. Serial.print("invalide position. Try again");
  25. return;
  26. }
  27. if(lastposition_ax12<position){
  28. for(int i = lastposition_ax12;i<position;i=i+1){
  29. ax12a.move(ID1,i);
  30. delay(10);
  31. }
  32. }
  33. if(lastposition_ax12>position){
  34. for(int i = lastposition_ax12;i>position;i=i-1){
  35. ax12a.move(ID1,i);
  36. delay(10);
  37. }
  38. }
  39. lastposition_ax12 = position;
  40. }
  41. void a116_1(int position){
  42. if((position<300) || (position>700)){
  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<300) || (position>700)){
  50. Serial.print("invalide position. Try again");
  51. return;
  52. }
  53. servo2.setPosition(position, playtime);
  54. }
  55. void setup() {
  56. Serial.begin(9600);
  57. Serial.setTimeout(1);
  58. ax12a.begin(BaudRate, DirectionPin, &Serial3);
  59. ax12a.setEndless(ID1, OFF);
  60. servoSerial.begin(115200);
  61. ax12a.move(ID1,512);
  62. servo1.setPosition(512, playtime);
  63. servo2.setPosition(512, playtime);
  64. }
  65. void loop() {
  66. if (Serial.available()){
  67. //Serial.print(test);
  68. for(int n = 0; n < 10 ; n++){
  69. val[n] = Serial.readString().toInt();
  70. //Serial.print(x);
  71. //Serial.print(n);
  72. }
  73. position = 0 ;
  74. for(int i = 2; i < 5;i++){
  75. position = position * 10 + val[i];
  76. }
  77. choice = val[0];
  78. Serial.print("Motor: ");
  79. Serial.print(choice);
  80. Serial.print(" position: ");
  81. Serial.print(position);
  82. switch(val[0]){
  83. case 1:
  84. ax12(position);
  85. break;
  86. case 2:
  87. a116_1(position);
  88. break;
  89. case 3:
  90. a116_2(position);
  91. break;
  92. }
  93. }
  94. }