class uArmSwift: def __init__(self): self.swift = SwiftAPI(filters={'hwid': 'USB VID:PID=2341:0042'}, cmd_pend_size=2, callback_thread_pool_size=1) if not self.swift.connected: print('lose connect') self.swift.waiting_ready() device_info = self.swift.get_device_info() print(device_info) firmware_version = device_info['firmware_version'] if firmware_version and not firmware_version.startswith( ('0.', '1.', '2.', '3.')): self.swift.set_speed_factor(0.00005) self.swift.set_mode(0) self.speed = 500000 self.swift.set_wrist(angle=90) self.wristAngle = self.swift.get_servo_angle(0, timeout=10) def set_position(self, x=100, y=0, z=100, wait=False): self.swift.set_position(x, y, z, speed=self.speed, wait=wait) def set_polar(self, stretch, rotation, height, wait=False): self.swift.set_polar(stretch, rotation, height, speed=self.speed, wait=wait) def set_servo_angle(self, num, angle, wait=False): if num < 0 and num > 3: print("num is wrong") self.swift.set_servo_angle(num, angle, wait, speed=self.speed, wait=wait) def set_wrist(self, angle=90, wait=False): # 第四电机 self.swift.set_wrist(angle, wait) def set_pump(self, on=False): self.swift.set_pump(on) def set_buzzer(self, freq=1000, duration=1, wait=False): self.swift.set_buzzer(freq, duration, wait) def get_position(self): return self.swift.get_position() def get_servo_angle(self, id=0): return self.swift.get_servo_angle(id, timeout=10) def is_moving(self): return self.swift.get_is_moving() def disconnect(self): self.swift.disconnect()
firmware_version = device_info['firmware_version'] if firmware_version and not firmware_version.startswith(('0.', '1.', '2.', '3.')): swift1.set_speed_factor(0.00001) time.sleep(1) d = { "A" : 0, "A#" : 1, "B" : 2, "C" : 3, "C#" : 4, "D" : 5, "D#" : 6, "E" : 7, "F" : 8, "F#" : 9, "G" : 10, "G#" : 11 } def freq(sc, pitch): return 440 * pow(2, ( d[sc] + pitch * 12 ) / 12) # midiData = pretty_midi.PrettyMIDI('') swift1.set_buzzer(frequency=freq("C", -1), duration=0.5)
# # Author: Vinman <*****@*****.**> <*****@*****.**> import os import sys import time sys.path.append(os.path.join(os.path.dirname(__file__), '../../..')) from uarm.wrapper import SwiftAPI """ api test: set """ swift = SwiftAPI(filters={'hwid': 'USB VID:PID=2341:0042'}) swift.waiting_ready() swift.set_buzzer(frequency=1000, duration=2, wait=True) print(swift.set_pump(on=True)) time.sleep(2) print(swift.set_pump(on=False)) print(swift.set_gripper(catch=True)) time.sleep(2) print(swift.set_gripper(catch=False)) time.sleep(4) swift.flush_cmd() swift.disconnect()
class uArm(): def __init__(self): self.scope = 10 self.x0 = 160 self.y0 = 0 self.swift = SwiftAPI(filters={'hwid':'USB VID:PID=2341:0042'}) self.swift.waiting_ready(timeout=3) # self.swift.set_speed_factor(0.005) # if you change this, be prepared for different movements! self.swift.set_mode(mode=0) time.sleep(0.5) self.swift.set_servo_angle(angle=90) self.swift.set_wrist(angle=90) self.swift.set_position(x=200,y=0,z=20) # start it off with a salute self.swift.set_buzzer(frequency=1000, duration=1) # signal ready self.lstValidCharSet = ['?','A','B','C','D','E','F','G','H','I','J','K','L','M','N','O','P','Q','R','S','T','U','V','W','X','Y','Z',\ '-','0','1','2','3','4','5','6','7','8','9'] self.lstLetter = [self.QuestionMark, self.LetterA, self.LetterB, self.LetterC, self.LetterD, self.LetterE, self.LetterF,\ self.LetterG, self.LetterH, self.LetterI, self.LetterJ, self.LetterK, self.LetterL, self.LetterM, self.LetterN,\ self.LetterO, self.LetterP, self.LetterQ, self.LetterR, self.LetterS, self.LetterT, self.LetterU, self.LetterV,\ self.LetterW, self.LetterX, self.LetterY, self.LetterZ, self.Hyphen, self.Number0, self.Number1, self.Number2,\ self.Number3, self.Number4, self.Number5, self.Number6, self.Number7, self.Number8, self.Number9] def __del__(self): input("PLEASE SUPPORT uARM ARM!!, then strike ENTER to continue ...") self.swift.set_buzzer(frequency=600, duration=2) self.swift.set_position(x=200,y=0,z=20) self.swift.flush_cmd() self.swift.disconnect() del self.swift self.swift = None def arm(self): """ Using this method to allow raw access to the uArm if required """ return self.swift def insert_pen(self): self.swift.set_buzzer(frequency=1000, duration=0.5) # signal ready self.swift.set_servo_angle(angle=90) time.sleep(0.5) self.swift.set_wrist(angle=90) time.sleep(0.5) self.swift.set_position(x=200,y=0,z=0) while (self.swift.get_is_moving()): continue input("Set pen in universal holder, then strike ENTER to continue ...") self.swift.set_position(x=200,y=0,z=10) return def pen_up(self): while (self.swift.get_is_moving()): continue x, y, z = self.swift.get_position() self.swift.set_position(x, y, 10) time.sleep(0.5) return 10 def pen_down(self): while (self.swift.get_is_moving()): continue x, y, z = self.swift.get_position() self.swift.set_position(x, y, 0) time.sleep(0.5) return 0 def setScope(self, strName): """ based upon the length of strName, determine the scope (char width) and starting X, Y positions assuming that the center of the page is 160,0 x extent is 110 - 210, y extent 80 - (-80) (x axis is PARALLEL to the arm, short edge of the paper) """ if type(strName) == str: strName = strName[:26] # going to truncate user input to a 26 characters max intLenName = len(strName) if (intLenName < 4): self.scope = 40.0 # keeping it real else: self.scope = math.floor(160.0/(intLenName * 1.1)) self.x0 = 160 - (0.5 * self.scope) self.y0 = self.scope * intLenName * 1.1 / 2 return def LetterSelect(self, c): """ given char c, return the plotting function index 0 resolves to the question mark character """ index = 0 if type(c) == str: if c == ' ': return self.SpaceBar else: c = c.upper() if c in self.lstValidCharSet: index = self.lstValidCharSet.index(c) - self.lstValidCharSet.index('A') + 1 # 0th item is '?' # if c in ['A','B','C','D','E','F','G','H','I','J','K','L','M','N','O','P','Q','R','S','T','U','V','W','X','Y','Z']: # index = ord(c) - ord('A') + 1 # using question mark as the 0th index item return self.lstLetter[index] # return the function to use
class MinionArm: def __init__(self): self.swift = SwiftAPI(filters={'hwid': 'USB VID:PID=2341:0042'}) self.swift.waiting_ready() device_info = self.swift.get_device_info() print(device_info) firmware_version = device_info['firmware_version'] if firmware_version and not firmware_version.startswith( ('0.', '1.', '2.', '3.')): self.swift.set_speed_factor(0.0005) self.speed = 110000 self.test() self.board = "right" def test(self): # self.swift.set_buzzer(frequency=1000, duration=0.5, wait=True) self.swift.reset(wait=True, speed=self.speed) self.move(1250, 0, 150, self.speed) print(self.swift.get_position()) # self.swift.set_buzzer(frequency=1000, duration=0.5, wait=True) def home(self): print("going home") self.swift.set_position(x=150, y=0, speed=self.speed * 0.5, wait=True) self.move(145, 0, 100, self.speed * 1.5) time.sleep(2) # self.swift.set_buzzer(frequency=1000, duration=0.5, wait=True) def rest(self): print("going to rest position") self.swift.set_position(x=150, speed=self.speed * 0.5, wait=True) self.swift.set_position(x=125, y=0, speed=self.speed * 0.5, wait=True) self.move(125, 0, 40, self.speed * 0.5) time.sleep(2) self.swift.set_buzzer(frequency=1000, duration=0.5) def move(self, x, y, z, speed): self.swift.set_position(x, y, z, speed, wait=True) def flip(self): print("flipping") # self.home() self.swift.set_buzzer(frequency=1000, duration=0.5, wait=True) if self.board == "right": self.flip_left() self.board = "left" else: self.flip_right() self.board = "right" self.home() self.swift.set_buzzer(frequency=500, duration=1.0, wait=True) def flip_left(self): self.move(180, 0, 150, self.speed) self.move(240, 0, 150, self.speed) # self.move(220, 10, 140, self.speed*.2) self.move(220, 40, 150, self.speed * .2) # self.move(220, 40, 110, self.speed*.2) # self.move(220, 60, 100, self.speed*.2) self.move(220, 50, 30, self.speed * .2) time.sleep(1) self.move(180, 50, 20, self.speed * .2) time.sleep(2) def flip_right(self): self.move(180, 0, 150, self.speed) self.move(240, -10, 150, self.speed) # self.move(220, -20, 140, self.speed*.2) self.move(220, -40, 150, self.speed * .2) # self.move(220, -50, 110, self.speed*.2) # self.move(220, -60, 100, self.speed*.2) self.move(220, -60, 20, self.speed * .2) self.move(180, -50, 20, self.speed * .2) time.sleep(2) def move_to_galton_cal_pos(self): self.move(180, 0, 150, self.speed) self.move(240, 0, 150, self.speed) wait = input("waiting") self.home() def disconnect(self): self.swift.disconnect()