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

Commit

Permalink
cleaning up example-sdk.py
Browse files Browse the repository at this point in the history
  • Loading branch information
maxosprojects committed Apr 10, 2016
1 parent a8fda29 commit 8c8f081
Show file tree
Hide file tree
Showing 2 changed files with 99 additions and 46 deletions.
33 changes: 20 additions & 13 deletions application/fpga/python/DobotSDK.py
Original file line number Diff line number Diff line change
Expand Up @@ -83,19 +83,7 @@ def __init__(self, port, rate=115200, timeout=0.025, debug=False, fake=False):
# self._baseSteps = long(0)
# self._rearSteps = long(0)
# self._foreSteps = long(0)
accels = self._driver.GetAccelerometers()
accelRear = accels[1]
accelFore = accels[2]
rearAngle = math.pi / 2 - self._driver.accelToRadians(accelRear, accelOffsets[0])
foreAngle = self._driver.accelToRadians(accelFore, accelOffsets[1])
self._baseSteps = long(0)
self._rearSteps = long((rearAngle / math.pi / 2.0) * rearArmActualStepsPerRevolution + 0.5)
self._foreSteps = long((foreAngle / math.pi / 2.0) * foreArmActualStepsPerRevolution + 0.5)
self._driver.SetCounters(self._baseSteps, self._rearSteps, self._foreSteps)
print "Initializing with steps:", self._baseSteps, self._rearSteps, self._foreSteps
print "Reading back what was set:", self._driver.GetCounters()
print "--=========--"

self._initializeAccelerometers()

def _debug(self, *args):
if self._debugOn:
Expand All @@ -105,6 +93,25 @@ def _debug(self, *args):
print arg,
print

def _initializeAccelerometers(self):
print "--=========--"
accels = self._driver.GetAccelerometers()
accelRear = accels[1]
accelFore = accels[2]
rearAngle = math.pi / 2 - self._driver.accelToRadians(accelRear, accelOffsets[0])
foreAngle = self._driver.accelToRadians(accelFore, accelOffsets[1])
self._baseSteps = long(0)
self._rearSteps = long((rearAngle / math.pi / 2.0) * rearArmActualStepsPerRevolution + 0.5)
self._foreSteps = long((foreAngle / math.pi / 2.0) * foreArmActualStepsPerRevolution + 0.5)
self._driver.SetCounters(self._baseSteps, self._rearSteps, self._foreSteps)
print "Initializing with steps:", self._baseSteps, self._rearSteps, self._foreSteps
print "Reading back what was set:", self._driver.GetCounters()
currBaseAngle = piTwo * self._baseSteps / baseActualStepsPerRevolution
currRearAngle = piHalf - piTwo * self._rearSteps / rearArmActualStepsPerRevolution
currForeAngle = piTwo * self._foreSteps / foreArmActualStepsPerRevolution
print 'Current estimated coordinates:', self._getCoordinatesFromAngles(currBaseAngle, currRearAngle, currForeAngle)
print "--=========--"

def _moveArmToAngles(self, baseAngle, rearArmAngle, foreArmAngle, duration):
self._baseAngle = baseAngle
self._rearAngle = rearArmAngle
Expand Down
112 changes: 79 additions & 33 deletions application/fpga/python/example-sdk.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,40 +16,86 @@
'''

from DobotSDK import Dobot
import time

# The top Z to go to.
up = 50
# The bottom Z to go to.
down = 39
# Maximum speed in mm/s
speed = 700
# Acceleration in mm/s^2
acceleration = 400

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

dobot.CalibrateJoint(1, dobot.freqToCmdVal(2000), dobot.freqToCmdVal(50), 1, 5, 1, 0)
while True:
dobot.moveWithSpeed(200.0, 80.0, 60, 400, 300)
dobot.moveWithSpeed(200.0, 80.0, 40, 400, 300)
dobot.moveWithSpeed(200.0, 80.0, 60, 400, 300)
dobot.moveWithSpeed(200.0, -80.0, 60, 400, 300)
dobot.moveWithSpeed(200.0, -80.0, 40, 400, 300)
dobot.moveWithSpeed(200.0, -80.0, 60, 400, 300)
# dobot.moveWithSpeed(200.0, 50.0, 44.0, 100)
# dobot.moveWithSpeed(200.0, -50.0, 44.0, 100)
# dobot.moveWithSpeed(200.0, 0.0, 44.0, 100)

# dobot.moveWithSpeed(160.0, 0.0, 115.0, 100)
# dobot.moveWithSpeed(160.0, 0.0, 215.0, 100)
# dobot.moveWithSpeed(160.0, 0.0, 115.0, 100)
# dobot.moveWithSpeed(120.0, 0.0, 115.0, 100)
# dobot.moveWithSpeed(160.0, -100.0, 215.0, 100)

# print '======================================'
# for i in range(3):
# dobot.moveTo(160.0, 60.0, 60.0, duration)
# print '======================================'
# dobot.moveTo(220.0, 60.0, 60.0, duration)
# print '======================================'
# dobot.moveTo(220.0, -60.0, 60.0, duration)
# print '======================================'
# dobot.moveTo(160.0, -60.0, 60.0, duration)
# print '======================================'
# dobot.moveTo(160.0, 0.0, 60.0, duration)
# print '======================================'
# dobot.moveTo(160.0, 0.0, 215.0, duration)
# print '======================================'
# Enable calibration routine if you have a limit switch/photointerrupter installed on the arm.
# See example-switch.py for details.
# Move both arms to approximately 45 degrees.
# dobot.moveWithSpeed(260.0, 0.0, 85, 700, acceleration)
# time.sleep(2)
# dobot.CalibrateJoint(1, dobot.freqToCmdVal(2000), dobot.freqToCmdVal(50), 1, 5, 1, 0)

# Line
# dobot.moveWithSpeed(200.0, 80.0, up, speed, acceleration)
# dobot.moveWithSpeed(200.0, 80.0, down, speed, acceleration)
# dobot.moveWithSpeed(200.0, -90.0, down, speed, acceleration)
# dobot.moveWithSpeed(200.0, -90.0, up, speed, acceleration)

# dobot.moveWithSpeed(200.0, -90.0, down, speed, acceleration)
# dobot.moveWithSpeed(200.0, 80.0, down, speed, acceleration)
# dobot.moveWithSpeed(200.0, 80.0, up, speed, acceleration)
# dobot.moveWithSpeed(200.0, -90.0, up, speed, acceleration)

# Rectangle with zig-zag inside
dobot.moveWithSpeed(170.0, -90.0, up, speed, acceleration)
dobot.moveWithSpeed(170.0, -90.0, down, speed, acceleration)
dobot.moveWithSpeed(170.0, 80.0, down, speed, acceleration)
dobot.moveWithSpeed(230.0, 80.0, down, speed, acceleration)
dobot.moveWithSpeed(230.0, -90.0, down, speed, acceleration)
dobot.moveWithSpeed(170.0, -90.0, down, speed, acceleration)
x = 230
y = 0
for y in range(-90, 81, 5):
if x == 170:
x = 230
else:
x = 170
dobot.moveWithSpeed(x, y, down, speed, acceleration)

dobot.moveWithSpeed(x, y, up, speed, acceleration)
dobot.moveWithSpeed(200.0, -90.0, up, speed, acceleration)

# Jog
# while True:
# dobot.moveWithSpeed(200.0, 80.0, up, speed, acceleration)
# dobot.moveWithSpeed(200.0, 80.0, down, speed, acceleration)
# dobot.moveWithSpeed(200.0, 80.0, up, speed, acceleration)
# dobot.moveWithSpeed(200.0, 80.0, 200, speed, acceleration)
# dobot.moveWithSpeed(200.0, -80.0, up, speed, acceleration)
# dobot.moveWithSpeed(200.0, -80.0, down, speed, acceleration)
# dobot.moveWithSpeed(200.0, -80.0, up, speed, acceleration)

# Dashed line
# while True:
# dobot.moveWithSpeed(200.0, 80.0, up, speed, acceleration)
# dobot.moveWithSpeed(200.0, 80.0, down, speed, acceleration)
# dobot.moveWithSpeed(200.0, 70.0, down, speed, acceleration)
# dobot.moveWithSpeed(200.0, 70.0, up, speed, acceleration)
# dobot.moveWithSpeed(200.0, 40.0, up, speed, acceleration)
# dobot.moveWithSpeed(200.0, 40.0, down, speed, acceleration)
# dobot.moveWithSpeed(200.0, 30.0, down, speed, acceleration)
# dobot.moveWithSpeed(200.0, 30.0, up, speed, acceleration)
# dobot.moveWithSpeed(200.0, 0.0, up, speed, acceleration)
# dobot.moveWithSpeed(200.0, 0.0, down, speed, acceleration)
# dobot.moveWithSpeed(200.0, -10.0, down, speed, acceleration)
# dobot.moveWithSpeed(200.0, -10.0, up, speed, acceleration)
# dobot.moveWithSpeed(200.0, -40.0, up, speed, acceleration)
# dobot.moveWithSpeed(200.0, -40.0, down, speed, acceleration)
# dobot.moveWithSpeed(200.0, -50.0, down, speed, acceleration)
# dobot.moveWithSpeed(200.0, -50.0, up, speed, acceleration)
# dobot.moveWithSpeed(200.0, -80.0, up, speed, acceleration)
# dobot.moveWithSpeed(200.0, -80.0, down, speed, acceleration)
# dobot.moveWithSpeed(200.0, -90.0, down, speed, acceleration)
# dobot.moveWithSpeed(200.0, -90.0, up, speed, acceleration)

0 comments on commit 8c8f081

Please sign in to comment.