Skip to content
This repository was archived by the owner on Dec 22, 2022. It is now read-only.

Commit 8c8f081

Browse files
committed
cleaning up example-sdk.py
1 parent a8fda29 commit 8c8f081

File tree

2 files changed

+99
-46
lines changed

2 files changed

+99
-46
lines changed

application/fpga/python/DobotSDK.py

Lines changed: 20 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -83,19 +83,7 @@ def __init__(self, port, rate=115200, timeout=0.025, debug=False, fake=False):
8383
# self._baseSteps = long(0)
8484
# self._rearSteps = long(0)
8585
# self._foreSteps = long(0)
86-
accels = self._driver.GetAccelerometers()
87-
accelRear = accels[1]
88-
accelFore = accels[2]
89-
rearAngle = math.pi / 2 - self._driver.accelToRadians(accelRear, accelOffsets[0])
90-
foreAngle = self._driver.accelToRadians(accelFore, accelOffsets[1])
91-
self._baseSteps = long(0)
92-
self._rearSteps = long((rearAngle / math.pi / 2.0) * rearArmActualStepsPerRevolution + 0.5)
93-
self._foreSteps = long((foreAngle / math.pi / 2.0) * foreArmActualStepsPerRevolution + 0.5)
94-
self._driver.SetCounters(self._baseSteps, self._rearSteps, self._foreSteps)
95-
print "Initializing with steps:", self._baseSteps, self._rearSteps, self._foreSteps
96-
print "Reading back what was set:", self._driver.GetCounters()
97-
print "--=========--"
98-
86+
self._initializeAccelerometers()
9987

10088
def _debug(self, *args):
10189
if self._debugOn:
@@ -105,6 +93,25 @@ def _debug(self, *args):
10593
print arg,
10694
print
10795

96+
def _initializeAccelerometers(self):
97+
print "--=========--"
98+
accels = self._driver.GetAccelerometers()
99+
accelRear = accels[1]
100+
accelFore = accels[2]
101+
rearAngle = math.pi / 2 - self._driver.accelToRadians(accelRear, accelOffsets[0])
102+
foreAngle = self._driver.accelToRadians(accelFore, accelOffsets[1])
103+
self._baseSteps = long(0)
104+
self._rearSteps = long((rearAngle / math.pi / 2.0) * rearArmActualStepsPerRevolution + 0.5)
105+
self._foreSteps = long((foreAngle / math.pi / 2.0) * foreArmActualStepsPerRevolution + 0.5)
106+
self._driver.SetCounters(self._baseSteps, self._rearSteps, self._foreSteps)
107+
print "Initializing with steps:", self._baseSteps, self._rearSteps, self._foreSteps
108+
print "Reading back what was set:", self._driver.GetCounters()
109+
currBaseAngle = piTwo * self._baseSteps / baseActualStepsPerRevolution
110+
currRearAngle = piHalf - piTwo * self._rearSteps / rearArmActualStepsPerRevolution
111+
currForeAngle = piTwo * self._foreSteps / foreArmActualStepsPerRevolution
112+
print 'Current estimated coordinates:', self._getCoordinatesFromAngles(currBaseAngle, currRearAngle, currForeAngle)
113+
print "--=========--"
114+
108115
def _moveArmToAngles(self, baseAngle, rearArmAngle, foreArmAngle, duration):
109116
self._baseAngle = baseAngle
110117
self._rearAngle = rearArmAngle

application/fpga/python/example-sdk.py

Lines changed: 79 additions & 33 deletions
Original file line numberDiff line numberDiff line change
@@ -16,40 +16,86 @@
1616
'''
1717

1818
from DobotSDK import Dobot
19+
import time
20+
21+
# The top Z to go to.
22+
up = 50
23+
# The bottom Z to go to.
24+
down = 39
25+
# Maximum speed in mm/s
26+
speed = 700
27+
# Acceleration in mm/s^2
28+
acceleration = 400
1929

20-
# for i in range(10):
2130
# dobot = Dobot('/dev/tty.usbmodem1421', debug=True, fake=True)
2231
dobot = Dobot('/dev/tty.usbmodem1421', debug=True)
2332

24-
dobot.CalibrateJoint(1, dobot.freqToCmdVal(2000), dobot.freqToCmdVal(50), 1, 5, 1, 0)
25-
while True:
26-
dobot.moveWithSpeed(200.0, 80.0, 60, 400, 300)
27-
dobot.moveWithSpeed(200.0, 80.0, 40, 400, 300)
28-
dobot.moveWithSpeed(200.0, 80.0, 60, 400, 300)
29-
dobot.moveWithSpeed(200.0, -80.0, 60, 400, 300)
30-
dobot.moveWithSpeed(200.0, -80.0, 40, 400, 300)
31-
dobot.moveWithSpeed(200.0, -80.0, 60, 400, 300)
32-
# dobot.moveWithSpeed(200.0, 50.0, 44.0, 100)
33-
# dobot.moveWithSpeed(200.0, -50.0, 44.0, 100)
34-
# dobot.moveWithSpeed(200.0, 0.0, 44.0, 100)
35-
36-
# dobot.moveWithSpeed(160.0, 0.0, 115.0, 100)
37-
# dobot.moveWithSpeed(160.0, 0.0, 215.0, 100)
38-
# dobot.moveWithSpeed(160.0, 0.0, 115.0, 100)
39-
# dobot.moveWithSpeed(120.0, 0.0, 115.0, 100)
40-
# dobot.moveWithSpeed(160.0, -100.0, 215.0, 100)
41-
42-
# print '======================================'
43-
# for i in range(3):
44-
# dobot.moveTo(160.0, 60.0, 60.0, duration)
45-
# print '======================================'
46-
# dobot.moveTo(220.0, 60.0, 60.0, duration)
47-
# print '======================================'
48-
# dobot.moveTo(220.0, -60.0, 60.0, duration)
49-
# print '======================================'
50-
# dobot.moveTo(160.0, -60.0, 60.0, duration)
51-
# print '======================================'
52-
# dobot.moveTo(160.0, 0.0, 60.0, duration)
53-
# print '======================================'
54-
# dobot.moveTo(160.0, 0.0, 215.0, duration)
55-
# print '======================================'
33+
# Enable calibration routine if you have a limit switch/photointerrupter installed on the arm.
34+
# See example-switch.py for details.
35+
# Move both arms to approximately 45 degrees.
36+
# dobot.moveWithSpeed(260.0, 0.0, 85, 700, acceleration)
37+
# time.sleep(2)
38+
# dobot.CalibrateJoint(1, dobot.freqToCmdVal(2000), dobot.freqToCmdVal(50), 1, 5, 1, 0)
39+
40+
# Line
41+
# dobot.moveWithSpeed(200.0, 80.0, up, speed, acceleration)
42+
# dobot.moveWithSpeed(200.0, 80.0, down, speed, acceleration)
43+
# dobot.moveWithSpeed(200.0, -90.0, down, speed, acceleration)
44+
# dobot.moveWithSpeed(200.0, -90.0, up, speed, acceleration)
45+
46+
# dobot.moveWithSpeed(200.0, -90.0, down, speed, acceleration)
47+
# dobot.moveWithSpeed(200.0, 80.0, down, speed, acceleration)
48+
# dobot.moveWithSpeed(200.0, 80.0, up, speed, acceleration)
49+
# dobot.moveWithSpeed(200.0, -90.0, up, speed, acceleration)
50+
51+
# Rectangle with zig-zag inside
52+
dobot.moveWithSpeed(170.0, -90.0, up, speed, acceleration)
53+
dobot.moveWithSpeed(170.0, -90.0, down, speed, acceleration)
54+
dobot.moveWithSpeed(170.0, 80.0, down, speed, acceleration)
55+
dobot.moveWithSpeed(230.0, 80.0, down, speed, acceleration)
56+
dobot.moveWithSpeed(230.0, -90.0, down, speed, acceleration)
57+
dobot.moveWithSpeed(170.0, -90.0, down, speed, acceleration)
58+
x = 230
59+
y = 0
60+
for y in range(-90, 81, 5):
61+
if x == 170:
62+
x = 230
63+
else:
64+
x = 170
65+
dobot.moveWithSpeed(x, y, down, speed, acceleration)
66+
67+
dobot.moveWithSpeed(x, y, up, speed, acceleration)
68+
dobot.moveWithSpeed(200.0, -90.0, up, speed, acceleration)
69+
70+
# Jog
71+
# while True:
72+
# dobot.moveWithSpeed(200.0, 80.0, up, speed, acceleration)
73+
# dobot.moveWithSpeed(200.0, 80.0, down, speed, acceleration)
74+
# dobot.moveWithSpeed(200.0, 80.0, up, speed, acceleration)
75+
# dobot.moveWithSpeed(200.0, 80.0, 200, speed, acceleration)
76+
# dobot.moveWithSpeed(200.0, -80.0, up, speed, acceleration)
77+
# dobot.moveWithSpeed(200.0, -80.0, down, speed, acceleration)
78+
# dobot.moveWithSpeed(200.0, -80.0, up, speed, acceleration)
79+
80+
# Dashed line
81+
# while True:
82+
# dobot.moveWithSpeed(200.0, 80.0, up, speed, acceleration)
83+
# dobot.moveWithSpeed(200.0, 80.0, down, speed, acceleration)
84+
# dobot.moveWithSpeed(200.0, 70.0, down, speed, acceleration)
85+
# dobot.moveWithSpeed(200.0, 70.0, up, speed, acceleration)
86+
# dobot.moveWithSpeed(200.0, 40.0, up, speed, acceleration)
87+
# dobot.moveWithSpeed(200.0, 40.0, down, speed, acceleration)
88+
# dobot.moveWithSpeed(200.0, 30.0, down, speed, acceleration)
89+
# dobot.moveWithSpeed(200.0, 30.0, up, speed, acceleration)
90+
# dobot.moveWithSpeed(200.0, 0.0, up, speed, acceleration)
91+
# dobot.moveWithSpeed(200.0, 0.0, down, speed, acceleration)
92+
# dobot.moveWithSpeed(200.0, -10.0, down, speed, acceleration)
93+
# dobot.moveWithSpeed(200.0, -10.0, up, speed, acceleration)
94+
# dobot.moveWithSpeed(200.0, -40.0, up, speed, acceleration)
95+
# dobot.moveWithSpeed(200.0, -40.0, down, speed, acceleration)
96+
# dobot.moveWithSpeed(200.0, -50.0, down, speed, acceleration)
97+
# dobot.moveWithSpeed(200.0, -50.0, up, speed, acceleration)
98+
# dobot.moveWithSpeed(200.0, -80.0, up, speed, acceleration)
99+
# dobot.moveWithSpeed(200.0, -80.0, down, speed, acceleration)
100+
# dobot.moveWithSpeed(200.0, -90.0, down, speed, acceleration)
101+
# dobot.moveWithSpeed(200.0, -90.0, up, speed, acceleration)

0 commit comments

Comments
 (0)