1
0
Pārlūkot izejas kodu

working after the big failure

Nico 1 gadu atpakaļ
vecāks
revīzija
07d2a88909
2 mainītis faili ar 27 papildinājumiem un 45 dzēšanām
  1. 25 40
      Gripper/Gripper.ino
  2. 2 5
      Gripper_gui_test.py

+ 25 - 40
Gripper/Gripper.ino

@@ -1,10 +1,10 @@
 #include "Arduino.h"
 #include "AX12A.h"
 
-#define DirectionPin 	(10u)
-#define BaudRate  		(1000000ul)
-#define ID1				(4u)
-#define ID2				(5u)
+#define DirectionPin   (10u)
+#define BaudRate      (1000000ul)
+#define ID1       (4u)
+#define ID2       (5u)
 
 #include <XYZrobotServo.h>
 
@@ -17,50 +17,33 @@ SoftwareSerial servoSerial(10, 11);
 
 int input = 0;
 XYZrobotServo servo1(servoSerial, 2);
-XYZrobotServo servo2(servoSerial, 3);
 
 const uint8_t playtime = 200;
 
-
-int x;
+int x ,position;
 int val[10] = {0,0,0,0,0};
-int position,lastposition_ax12 = 512;
 int choice;
 
-void ax12(int position){
-  if((position<300) || (position>700)){
+void ax12_1(int position){
+     if((position<300) || (position>700)){
     Serial.print("invalide position. Try again");
-    return;
-  }
-  if(lastposition_ax12<position){
-  for(int i = lastposition_ax12;i<position;i=i+1){
-    ax12a.move(ID1,i);
-    delay(10);
-  }
-  }
-  if(lastposition_ax12>position){
-    for(int i = lastposition_ax12;i>position;i=i-1){
-    ax12a.move(ID1,i);
-    delay(10);
-  }
-  }
-
-  lastposition_ax12 = position;
+    return;}
+  ax12a.moveSpeed(ID1,position, playtime);
 }
 
-void a116_1(int position){
-    if((position<300) || (position>700)){
+void ax12_2(int position){
+     if((position<300) || (position>700)){
     Serial.print("invalide position. Try again");
-    return;
-  }
-  servo1.setPosition(position, playtime);
+    return;}
+  ax12a.moveSpeed(ID2,position, playtime);
 }
-void a116_2(int position){
+
+void a116(int position){
     if((position<300) || (position>700)){
     Serial.print("invalide position. Try again");
     return;
   }
-  servo2.setPosition(position, playtime);
+  servo1.setPosition(position, playtime);
 }
 
 void setup() {
@@ -69,20 +52,19 @@ void setup() {
 
   ax12a.begin(BaudRate, DirectionPin, &Serial3);
   ax12a.setEndless(ID1, OFF);
+  ax12a.setEndless(ID2, OFF);
 
   servoSerial.begin(115200);
 
   ax12a.move(ID1,512);
+  ax12a.move(ID2,512);
   servo1.setPosition(512, playtime);
-  servo2.setPosition(512, playtime);
 }
 void loop() {
  if (Serial.available()){
    //Serial.print(test);
    for(int n = 0; n < 10 ; n++){
     val[n] = Serial.readString().toInt();
-    //Serial.print(x);
-    //Serial.print(n);
 
    }
    position = 0 ;
@@ -96,14 +78,17 @@ void loop() {
    Serial.print(position);
   switch(val[0]){
     case 1:
-    ax12(position);
+    ax12_1(position);
+    Serial.print("Ready");
     break;
     case 2:
-    a116_1(position);
+    a116(position);
+    Serial.print("Ready");
     break;
     case 3:
-    a116_2(position);
+    ax12_2(position);
+    Serial.print("Ready");
     break;
   }
  }
-}
+}

+ 2 - 5
Gripper_gui_test.py

@@ -18,10 +18,10 @@ layout = [
     [sg.Slider(range=(300, 700), size=(slider_width, slider_hight), default_value=512, orientation='h', key='-SLIDER4-'), sg.Button('Reset', key='-BUTTON4-',size=(button_width,button_hight))],
     [sg.Button('OK',size=(button_width,button_hight)),sg.Button('Reset',key='-BUTTON5-',size=(button_width,button_hight))]
 ]
-arduino = serial.Serial(port='COM7', baudrate=9600, timeout=.1)
+arduino = serial.Serial(port='/dev/ttyUSB0', baudrate=9600, timeout=.1)
 def write_read(x):
     arduino.write(bytes(x, 'utf-8'))
-    time.sleep(0.5)
+    time.sleep(0.1)
     data = arduino.readline()
     print(data)
     return data
@@ -74,11 +74,8 @@ while True:
     print( "3 " + str(int(slider3_value)))
     print("4 " + str(int(slider4_value)))
     write_read(str("1 "+str(int(slider1_value))))
-    time.sleep(1)
     write_read(str("2 "+str(int(slider2_value))))
-    time.sleep(1)
     write_read(str("3 "+str(int(slider3_value))))
-    time.sleep(1)
     write_read(str("4 "+str(int(slider4_value))))
 
 # GUI schließen