Nico пре 1 година
родитељ
комит
ae8b852783
3 измењених фајлова са 30 додато и 3 уклоњено
  1. 17 2
      Gripper/Gripper.ino
  2. 13 1
      Gripper_gui_test.py
  3. 0 0
      Stepper_Rotation/Stepper_Rotation.ino

+ 17 - 2
Gripper/Gripper.ino

@@ -17,6 +17,7 @@ SoftwareSerial servoSerial(10, 11);
 
 int input = 0;
 XYZrobotServo servo1(servoSerial, 2);
+XYZrobotServo servo2(servoSerial, 3);
 
 const uint8_t playtime = 100;
 const int max_angle = 712,min_angle = 312;
@@ -47,7 +48,7 @@ void ax12_2(int position){
   ax12a.moveSpeed(ID2,position, playtime);
 }
 
-void a116(int position){
+void a116_1(int position){
     if((position<min_angle) || (position>max_angle)){
     Serial.print("invalide position. Try again");
     return;
@@ -55,6 +56,14 @@ void a116(int position){
   servo1.setPosition(position, playtime);
 }
 
+void a116_2(int position){
+ /*   if((position<min_angle) || (position>max_angle)){
+    Serial.print("invalide position. Try again");
+    return;
+  }*/
+  servo2.setPosition(position, playtime);
+}
+
 void motor(int speed, int dir){
   if (dir == 0){
     digitalWrite(ain1,HIGH);
@@ -102,6 +111,7 @@ void setup() {
   ax12a.move(ID1,512);
   ax12a.move(ID2,512);
   servo1.setPosition(512, playtime);
+  servo2.setPosition(512, playtime);
 
   pinMode(button_oben,INPUT_PULLUP);
   pinMode(button_unten,INPUT_PULLUP);
@@ -136,7 +146,7 @@ void loop() {
     Serial.print("Ready");
     break;
     case 2:
-    a116(position);
+    a116_1(position);
     Serial.print("Ready");
     break;
     case 3:
@@ -151,6 +161,11 @@ void loop() {
     auto_close();
     Serial.print("Ready");
     break;
+    case 6:
+    position = map(position,0,360,0,1023);
+    a116_2(position);
+    Serial.print("Ready");
+    break;
   }
  }
 }

+ 13 - 1
Gripper_gui_test.py

@@ -20,6 +20,8 @@ layout = [
     [sg.Text('CLOSE'),sg.Slider(range=(312, 712), size=(slider_width, slider_hight), default_value=512, orientation='h', key='-SLIDER3-'),sg.Text('OPEN'), sg.Button('Reset', key='-BUTTON3-',size=(button_width,button_hight))], #enable_events=True,
     [sg.Text('Motor')],
     [sg.Text('DOWN'),sg.Slider(range=(-254, 254), size=(slider_width, slider_hight), default_value=0, orientation='h', key='-SLIDER4-'),sg.Text('   UP  '), sg.Button('Reset', key='-BUTTON4-',size=(button_width,button_hight))],
+    [sg.Text('Rotation')],
+    [sg.Text('LEFT'),sg.Slider(range=(0, 360), size=(slider_width, slider_hight), default_value=180, orientation='h', key='-SLIDER5-'),sg.Text('   RIGHT  '), sg.Button('Reset', key='-BUTTON10-',size=(button_width,button_hight))],
     [sg.Button('OK',key='-BUTTON9-',size=(button_width,button_hight)),sg.Button('Reset',key='-BUTTON5-',size=(button_width,button_hight)),sg.Button('Open',key='-BUTTON6-',size=(button_width,button_hight)),sg.Button('Close',key='-BUTTON7-',size=(button_width,button_hight)),sg.Button('auto Close',key='-BUTTON8-',size=(button_width,button_hight))]
 ]
 arduino = serial.Serial(port='/dev/ttyUSB0', baudrate=9600, timeout=.1)
@@ -37,12 +39,14 @@ def write():
     slider2_value = 512+(512-values['-SLIDER2-'])
     slider3_value = values['-SLIDER3-']
     slider4_value = values['-SLIDER4-']
+    slider5_value = values['-SLIDER5-']
 
     # Beispiel: Ausgabe der aktuellen Werte der Schieberegler
     print("Slider 1:", slider1_value)
     print("Slider 2:", slider2_value)
     print("Slider 3:", slider3_value)
     print("Slider 4:", slider4_value)
+    print("Slider 5:", slider5_value)
     val_1 = "0"
     if slider4_value < 0:
         slider4_value = numpy.abs(slider4_value)
@@ -51,10 +55,14 @@ def write():
     print("2 " + str(int(slider2_value)))
     print( "3 " + str(int(slider3_value)))
     print("4" +val_1+ str(int(slider4_value)))
+    print( "6 " + str(int(slider5_value)))
     write_read(str("1 "+str(int(slider1_value))))
     write_read(str("2 "+str(int(slider2_value))))
     write_read(str("3 "+str(int(slider3_value))))
     write_read(str("4"+val_1+str(int(slider4_value))))
+    if slider5_value < 100:
+        slider5_value = "0"+str(int(slider5_value))
+    write_read(str("6 "+str(slider5_value)))
 # GUI-Ereignisschleife
 while True:
     event, values = window.read()  
@@ -123,7 +131,11 @@ while True:
         while(arduino.readline() != b"" ):
             print(arduino.readline()) 
             print(arduino.readline())       
-
+    elif event == '-BUTTON10-':
+        print('Button 10 was clicked')
+        window['-SLIDER5-'].update(180)
+        values['-SLIDER5-']=180.0
+        write()
 
 # GUI schließen
 window.close()

Stepper_Rotation.ino → Stepper_Rotation/Stepper_Rotation.ino