1+ """
2+ open-dobot SDK.
3+
4+ SDK providing high-level functions to control Dobot via the driver to open firmware that controls Dobot FPGA.
5+ Abstracts specifics of commands sent to FPGA.
6+ Find firmware and driver at https://github.com/maxosprojects/open-dobot
7+
8+ It is assumed that upon SDK initialization the arms are set as follows:
9+ - rear arm is set vertically
10+ - forearm is set horizontally
11+ Refer to docs/images/arm-description.png and docs/images/reference-frame.png to find more about reference
12+ frame and arm names.
13+ SDK keeps track of the current end effector pose, thus in case the arm slips or motors are disabled while
14+ in move (with the "Laser Adjustment" button) it has to be re-initialized - the arm set to initial configuration
15+ (end effector to initial pose) and SDK re-initialized.
16+
17+ Proper initialization based on data from accelerometers is under development (planned for 0.4.0). This would
18+ enable to initialize from almost any end effector pose.
19+
20+ Author: maxosprojects (March 18 2016)
21+ Additional Authors: <put your name here>
22+
23+ Version: 0.3.0
24+
25+ License: MIT
26+ """
27+
128import serial
229import threading
330import time
1037stepperMotorStepsPerRevolution = 200.0
1138# FPGA board has all stepper drivers' stepping pins set to microstepping.
1239baseMicrosteppingMultiplier = 16.0
13- upperArmMicrosteppingMultiplier = 16.0
14- lowerArmMicrosteppingMultiplier = 16.0
40+ rearArmMicrosteppingMultiplier = 16.0
41+ foreArmMicrosteppingMultiplier = 16.0
1542# The NEMA 17 stepper motors Dobot uses are connected to a planetary gearbox, the black cylinders
1643# with 10:1 reduction ratio
1744stepperPlanetaryGearBoxMultiplier = 10.0
1845
1946# calculate the actual number of steps it takes for each stepper motor to rotate 360 degrees
2047baseActualStepsPerRevolution = stepperMotorStepsPerRevolution * baseMicrosteppingMultiplier * stepperPlanetaryGearBoxMultiplier
21- upperArmActualStepsPerRevolution = stepperMotorStepsPerRevolution * upperArmMicrosteppingMultiplier * stepperPlanetaryGearBoxMultiplier
22- lowerArmActualStepsPerRevolution = stepperMotorStepsPerRevolution * lowerArmMicrosteppingMultiplier * stepperPlanetaryGearBoxMultiplier
48+ rearArmActualStepsPerRevolution = stepperMotorStepsPerRevolution * rearArmMicrosteppingMultiplier * stepperPlanetaryGearBoxMultiplier
49+ foreArmActualStepsPerRevolution = stepperMotorStepsPerRevolution * foreArmMicrosteppingMultiplier * stepperPlanetaryGearBoxMultiplier
2350
2451class Dobot :
25- def __init__ (self , port , rate = 115200 , timeout = 0.025 ):
52+ def __init__ (self , port , rate = 115200 , timeout = 0.025 , debug = False ):
53+ self ._debugOn = debug
2654 self ._driver = DobotDriver (port , rate )
2755 self ._driver .Open (timeout )
28- self ._ik = DobotInverseKinematics ()
56+ self ._ik = DobotInverseKinematics (debug = debug )
2957 self ._x = 160.0
3058 self ._y = 0.0
3159 self ._z = 215.0
3260 self ._baseAngle = 0.0
3361 self ._rearAngle = 90.0
34- self ._frontAngle = 0.0
62+ self ._foreAngle = 0.0
3563 self ._baseSteps = long (0 )
3664 self ._rearSteps = long (0 )
37- self ._frontSteps = long (0 )
38-
39- def _reverseBits32 (self , val ):
40- # return long(bin(val&0xFFFFFFFF)[:1:-1], 2)
41- return int ('{0:032b}' .format (val )[::- 1 ], 2 )
65+ self ._foreSteps = long (0 )
4266
43- def _freqToCmdVal (self , freq ):
44- '''
45- Converts stepping frequency into a command value that dobot takes.
46- '''
47- if freq == 0 :
48- return 0x0242f000 ;
49- return this . _reverseBits32 ( long ( 25000000 / freq ))
67+ def _debug (self , * args ):
68+ if self . _debugOn :
69+ # Since "print" is not a function the expansion (*) cannot be used
70+ # as it is not an operator. So this is a workaround.
71+ for arg in args :
72+ print arg ,
73+ print
5074
51- def _stepsToCmdVal (self , steps ):
75+ def moveTo (self , x , y , z , duration ):
5276 '''
53- Converts number of steps for dobot to do in 20ms into a command value that dobot
54- takes to set the stepping frequency.
77+ Moves the arm to the location with provided coordinates. Makes sure it takes exactly
78+ the amount of time provided in "duration" argument to get end effector to the location.
79+ All axes arrive at the same time.
80+ SDK keeps track of the current end effector pose.
81+ The origin is at the arm's base (the rotating base plate - joint1).
82+ Refer to docs/images/arm-description.png and docs/images/reference-frame.png to find
83+ more about reference frame and arm names.
84+ Current limitations:
85+ - rear arm cannot go beyond initial 90 degrees (backwards from initial vertical position),
86+ so plan carefully the coordinates
87+ - forearm cannot go above initial horizontal position
88+ Not yet implemented:
89+ - the move is not linear as motors run the whole path at constant speed
90+ - acceleration/deceleration
91+ - rear arm cannot go beyond 90 degrees (see current limitations) and there are no checks
92+ for that - it will simply go opposite direction instead
5593 '''
56- if steps == 0 :
57- return 0x0242f000 ;
58- return self ._reverseBits32 (long (500000 / steps ))
59-
60- def moveTo (self , x , y , z ):
6194 xx = float (x )
6295 yy = float (y )
6396 zz = float (z )
@@ -68,75 +101,78 @@ def moveTo(self, x, y, z):
68101 print 'Unreachable'
69102 return
70103
71- print 'ik base angle' , moveToAngles [0 ]
72- print 'ik upper angle' , moveToAngles [1 ]
73- print 'ik lower angle' , moveToAngles [2 ]
104+ self . _debug ( 'ik base angle' , moveToAngles [0 ])
105+ self . _debug ( 'ik rear angle' , moveToAngles [1 ])
106+ self . _debug ( 'ik fore angle' , moveToAngles [2 ])
74107
75- moveToUpperArmAngleFloat = moveToAngles [1 ]
76- moveToLowerArmAngleFloat = moveToAngles [2 ]
108+ moveToRearArmAngleFloat = moveToAngles [1 ]
109+ moveToForeArmAngleFloat = moveToAngles [2 ]
77110
78- transformedUpperArmAngle = 90.0 - moveToUpperArmAngleFloat
111+ transformedRearArmAngle = 90.0 - moveToRearArmAngleFloat
79112 # -90 different from c++ code, accounts for fact that arm starts at the c++ simulation's 90
80113 # note that this line is different from the similar line in the move angles function.
81- # Has to do with the inverse kinematics function and the fact that the lower arm angle is
82- # calculated relative to the upper arm angle.
83- transformedLowerArmAngle = 270.0 + transformedUpperArmAngle - moveToLowerArmAngleFloat
84- print 'transformed upper angle' , transformedUpperArmAngle
85- print 'transformed lower angle' , transformedLowerArmAngle
114+ # Has to do with the inverse kinematics function and the fact that the forearm angle is
115+ # calculated relative to the rear arm angle.
116+ transformedForeArmAngle = 270.0 + transformedRearArmAngle - moveToForeArmAngleFloat
117+ self . _debug ( 'transformed rear angle' , transformedRearArmAngle )
118+ self . _debug ( 'transformed fore angle' , transformedForeArmAngle )
86119
87120 # check that the final angles are mechanically valid. note that this check only considers final
88121 # angles, and not angles while the arm is moving
89122 # need to pass in real world angles
90- # real world base and upper arm angles are those returned by the ik function.
91- # real world lower arm angle is -1 * transformedLowerArmAngle
92- if not self ._ik .check_for_angle_limits_is_valid (moveToAngles [0 ], moveToAngles [1 ], - 1 * transformedLowerArmAngle ):
123+ # real world base and rear arm angles are those returned by the ik function.
124+ # real world fore arm angle is -1 * transformedForeArmAngle
125+ if not self ._ik .check_for_angle_limits_is_valid (moveToAngles [0 ], moveToAngles [1 ], - 1 * transformedForeArmAngle ):
93126 return
94127
95- self ._moveArmToAngles (moveToAngles [0 ], transformedUpperArmAngle , transformedLowerArmAngle )
128+ self ._moveArmToAngles (moveToAngles [0 ], transformedRearArmAngle , transformedForeArmAngle , duration )
96129
97- def _moveArmToAngles (self , baseAngle , upperArmAngle , lowerArmAngle ):
130+ def _moveArmToAngles (self , baseAngle , rearArmAngle , foreArmAngle , duration ):
98131 self ._baseAngle = baseAngle
99- self ._rearAngle = upperArmAngle
100- self ._frontAngle = lowerArmAngle
132+ self ._rearAngle = rearArmAngle
133+ self ._foreAngle = foreArmAngle
134+ dur = float (duration )
101135
102- baseStepNumber = long ((abs ( baseAngle ) / 360.0 ) * baseActualStepsPerRevolution + 0.5 )
103- upperArmStepNumber = long ((abs (upperArmAngle ) / 360.0 ) * upperArmActualStepsPerRevolution + 0.5 )
104- lowerArmStepNumber = long ((abs (lowerArmAngle ) / 360.0 ) * lowerArmActualStepsPerRevolution + 0.5 )
136+ baseStepLocation = long ((baseAngle / 360.0 ) * baseActualStepsPerRevolution + 0.5 )
137+ rearArmStepLocation = long ((abs (rearArmAngle ) / 360.0 ) * rearArmActualStepsPerRevolution + 0.5 )
138+ foreArmStepLocation = long ((abs (foreArmAngle ) / 360.0 ) * foreArmActualStepsPerRevolution + 0.5 )
105139
106- print "Base Step Number " , baseStepNumber
107- print "Upper Arm Step Number " , upperArmStepNumber
108- print "Lower Arm Step Number " , lowerArmStepNumber
140+ self . _debug ( "Base Step Location " , baseStepLocation )
141+ self . _debug ( "Rear Arm Step Location " , rearArmStepLocation )
142+ self . _debug ( "Forearm Step Location " , foreArmStepLocation )
109143
110- baseDiff = baseStepNumber - self ._baseSteps
111- rearDiff = upperArmStepNumber - self ._rearSteps
112- print 'rearDiff' , rearDiff
113- frontDiff = lowerArmStepNumber - self ._frontSteps
144+ baseDiff = baseStepLocation - self ._baseSteps
145+ rearDiff = rearArmStepLocation - self ._rearSteps
146+ foreDiff = foreArmStepLocation - self ._foreSteps
147+ self ._debug ('baseDiff' , baseDiff )
148+ self ._debug ('rearDiff' , rearDiff )
149+ self ._debug ('foreDiff' , foreDiff )
114150
115- self ._baseSteps = baseStepNumber
116- self ._rearSteps = upperArmStepNumber
117- self ._frontSteps = lowerArmStepNumber
151+ self ._baseSteps = baseStepLocation
152+ self ._rearSteps = rearArmStepLocation
153+ self ._foreSteps = foreArmStepLocation
118154
119155 baseDir = 1
120156 rearDir = 1
121- frontDir = 1
157+ foreDir = 1
122158
123159 if (baseDiff < 1 ):
124160 baseDir = 0
125161 if (rearDiff < 1 ):
126162 rearDir = 0
127- if (frontDiff > 1 ):
128- frontDir = 0
163+ if (foreDiff > 1 ):
164+ foreDir = 0
129165
130- baseSliced = self ._sliceStepsToValues (abs (baseDiff ), 1 )
131- rearSliced = self ._sliceStepsToValues (abs (rearDiff ), 1 )
132- frontSliced = self ._sliceStepsToValues (abs (frontDiff ), 1 )
166+ baseSliced = self ._sliceStepsToValues (abs (baseDiff ), dur )
167+ rearSliced = self ._sliceStepsToValues (abs (rearDiff ), dur )
168+ foreSliced = self ._sliceStepsToValues (abs (foreDiff ), dur )
133169
134- for base , upper , lower in zip (baseSliced , rearSliced , frontSliced ):
170+ for base , rear , fore in zip (baseSliced , rearSliced , foreSliced ):
135171 ret = [0 , 0 ]
136172 # If ret[0] == 0 then command timed out or crc failed.
137173 # If ret[1] == 0 then command queue was full.
138174 while ret [0 ] == 0 or ret [1 ] == 0 :
139- ret = self ._driver .Steps (base , upper , lower , baseDir , rearDir , frontDir )
175+ ret = self ._driver .Steps (base , rear , fore , baseDir , rearDir , foreDir )
140176
141177 def _sliceStepsToValues (self , steps , duration ):
142178 '''
@@ -147,32 +183,7 @@ def _sliceStepsToValues(self, steps, duration):
147183 num = long (duration / 0.02 )
148184 chunk = (steps / num )
149185 for _ in range (num ):
150- ret .append (self ._stepsToCmdVal (chunk ))
186+ ret .append (self ._driver . stepsToCmdVal (chunk ))
151187 return ret
152188
153189
154-
155- if __name__ == '__main__' :
156-
157- dobot = Dobot ('/dev/tty.usbmodem1421' )
158-
159- # while True:
160- dobot .moveTo (160.0 , 0.0 , 150.0 )
161- print '======================================'
162- dobot .moveTo (160.0 , 60.0 , 150.0 )
163- print '======================================'
164- dobot .moveTo (220.0 , 60.0 , 150.0 )
165- print '======================================'
166- dobot .moveTo (220.0 , 0.0 , 150.0 )
167- print '======================================'
168- dobot .moveTo (160.0 , 0.0 , 150.0 )
169- print '======================================'
170- dobot .moveTo (160.0 , 60.0 , 150.0 )
171- print '======================================'
172- dobot .moveTo (220.0 , 60.0 , 150.0 )
173- print '======================================'
174- dobot .moveTo (220.0 , 0.0 , 150.0 )
175- print '======================================'
176- dobot .moveTo (160.0 , 0.0 , 150.0 )
177- print '======================================'
178- dobot .moveTo (160.0 , 0.0 , 215.0 )
0 commit comments