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

Commit bfb7e1e

Browse files
committed
This fixes #7. Accelerometers' data converted to angles. SDK initializes from accelerometers and doesn't require a specific pose upon initialization any more (which wasn't feasible and repeatable anyway). Calibration instructions and tool created.
1 parent fbfeb28 commit bfb7e1e

File tree

7 files changed

+118
-55
lines changed

7 files changed

+118
-55
lines changed

application/fpga/python/DobotDriver.py

Lines changed: 14 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@
88
Author: maxosprojects (March 18 2016)
99
Additional Authors: <put your name here>
1010
11-
Version: 0.3.0
11+
Version: 0.4.0
1212
1313
License: MIT
1414
"""
@@ -17,6 +17,7 @@
1717
import threading
1818
import time
1919
from serial import SerialException
20+
import math
2021

2122
_max_trys = 1
2223

@@ -26,6 +27,9 @@
2627
CMD_GET_ACCELS = 3
2728
CMD_SWITCH_TO_ACCEL_REPORT_MODE = 4
2829

30+
piToDegrees = 180.0 / math.pi
31+
halfPi = math.pi / 2.0
32+
2933

3034
class DobotDriver:
3135
def __init__(self, comport, rate=115200):
@@ -278,6 +282,15 @@ def stepsToCmdVal(self, steps):
278282
return 0x0242f000;
279283
return self.reverseBits32(long(500000/steps))
280284

285+
def accelToAngle(self, val, offset):
286+
return self.accelToRadians(val, offset) * piToDegrees
287+
288+
def accelToRadians(self, val, offset):
289+
try:
290+
return math.asin(float(val - offset) / 493.56)
291+
except ValueError:
292+
return halfPi
293+
281294
def Steps(self, j1, j2, j3, j1dir, j2dir, j3dir, deferred=False):
282295
'''
283296
Adds a command to the controller's queue to execute on FPGA.

application/fpga/python/DobotInverseKinematics.py

Lines changed: 21 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -22,11 +22,19 @@
2222
algorithm
2323
2424
xy plane is paralell to surface dobot is on. z is perpendicular
25-
1. first get distance, in xy plane, to current point from origin using forward kinematics, known angles, and pythagoreas thm. This is your radius. Your angle can be defined to be theta original. You now have your starting point in polar coordinates.
26-
2. Ignore the desired z position data for now. Get the polar coordinates for the desired point. The radius is not important now. The angle is though. Subtracting the desired angle from the current angle gives you the number of degrees and direction to rotate the base.
27-
3. The radius from step 1 (starting radius) gives you your current horizontal position (imagine it as x or y, doesn't matter). You also already know your current z position (potentially from step 1).
28-
4. The radius from step 2 (desired radius) gives you your desired horizontal position (imagine it as x or y, doesn't matter). Of course, the user has already input the desired z position. This is now a 2D problem with two arms that each rotate (2 degrees of freedom)
29-
5: use IK, see ik 2d video, to find number of degrees and direction to rotate rear and fore arms. Note that there are often two solutions. One (elbow down) is not possible.
25+
1. first get distance, in xy plane, to current point from origin using forward kinematics, known angles,
26+
and pythagoreas thm. This is your radius. Your angle can be defined to be theta original. You now have your
27+
starting point in polar coordinates
28+
2. Ignore the desired z position data for now. Get the polar coordinates for the desired point. The radius is
29+
not important now. The angle is though. Subtracting the desired angle from the current angle gives you the
30+
number of degrees and direction to rotate the base
31+
3. The radius from step 1 (starting radius) gives you your current horizontal position (imagine it as x or y,
32+
doesn't matter). You also already know your current z position (potentially from step 1)
33+
4. The radius from step 2 (desired radius) gives you your desired horizontal position (imagine it as x or y,
34+
doesn't matter). Of course, the user has already input the desired z position. This is now a 2D problem with
35+
two arms that each rotate (2 degrees of freedom)
36+
5: use IK, see ik 2d video, to find number of degrees and direction to rotate rear and fore arms. Note that there
37+
are often two solutions. One (elbow down) is not possible.
3038
6. Check that move is valid (e.g. not out of range, etc...)
3139
7. move
3240
@@ -58,7 +66,7 @@ def _debug(self, *args):
5866
#cartesian (x,y,z) coordinate
5967
#robot dimensions
6068
#output:
61-
#angles for robot arm base, rear, and fore arms in degree
69+
#angles for robot arm base, rear, and fore arms in degrees
6270
def convert_cartesian_coordinate_to_arm_angles(self, x, y, z):
6371

6472
# do a general check to see if even a maximally stretched arm could reach the point
@@ -151,7 +159,8 @@ def check_for_angle_limits_is_valid(self, baseAngle, rearArmAngle, foreArmAngle)
151159
ret = False
152160

153161
# check the foreArmAngle
154-
# the valid forearm angle is dependent on the rear arm angle. The real world angle of the forearm (0 degrees = horizontal) needs to be evaluated.
162+
# the valid forearm angle is dependent on the rear arm angle. The real world angle of the forearm
163+
# (0 degrees = horizontal) needs to be evaluated.
155164
# min empirically determined to be around -105 degrees. Using -102.
156165
# max empirically determined to be around 21 degrees. Using 18.
157166
if (-102 > foreArmAngle > 18):
@@ -161,11 +170,11 @@ def check_for_angle_limits_is_valid(self, baseAngle, rearArmAngle, foreArmAngle)
161170
return ret
162171

163172
"""
164-
#get polar coordinates for the current point
165-
#radius is simply given by the base angle
166-
# can read the angles from the IMU and empirically determine the radius and angle - I'm using this approach since it should account for any build up in error, assuming accelerometers
167-
#are accurate!!!!
168-
#alternatively can just use pythagorean thm on theoretical current x,y data
173+
# get polar coordinates for the current point
174+
# radius is simply given by the base angle
175+
# can read the angles from the IMU and empirically determine the radius and angle - I'm using this approach
176+
# since it should account for any build up in error, assuming accelerometers are accurate!!!!
177+
# alternatively can just use pythagorean thm on theoretical current x,y data
169178
170179
startRearArmAngle = get_rear_arm_angle
171180
startForeArmAngle = get_fore_arm_angle

application/fpga/python/DobotSDK.py

Lines changed: 24 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -1,26 +1,26 @@
11
"""
22
open-dobot SDK.
33
4-
SDK providing high-level functions to control Dobot via the driver to open firmware that controls Dobot FPGA.
4+
SDK providing high-level functions to control Dobot via the driver to open firmware, which, in turn, controls Dobot FPGA.
55
Abstracts specifics of commands sent to FPGA.
66
Find firmware and driver at https://github.com/maxosprojects/open-dobot
77
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.
8+
It is assumed that upon SDK initialization the arms are beetween 0 and 90 degrees - beetween their normal
9+
horizontal and vertical positions.
10+
Upon initialization accelerometers are read to figure out current arms' configuration. Accelerometers get confused
11+
when rear arm leans backwards from the dobot base or when forearm bends towards the base.
12+
Also, Inverse Kinematics at the moment don't account for when forearm is looking up (higher than it's
13+
normal horizontal position). So be gentle and give dobot some feasible initial configuration in case it happened
14+
to be beyond the mentioned limits.
15+
Refer to docs/images/ to find more about reference frame, arm names and more.
1616
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.
17+
SDK keeps track of the current end effector pose, thus in case the arm slips or motors are disabled while
18+
in move (with the "Laser Adjustment" button) it has to be re-initialized and SDK re-initialized.
1919
2020
Author: maxosprojects (March 18 2016)
2121
Additional Authors: <put your name here>
2222
23-
Version: 0.3.0
23+
Version: 0.4.0
2424
2525
License: MIT
2626
"""
@@ -32,6 +32,10 @@
3232
from DobotDriver import DobotDriver
3333
from DobotInverseKinematics import DobotInverseKinematics
3434
import timeit
35+
import math
36+
37+
# calibration-tool.py for details
38+
accelOffsets = (1024, 1024)
3539

3640
# The NEMA 17 stepper motors that Dobot uses are 200 steps per revolution.
3741
stepperMotorStepsPerRevolution = 200.0
@@ -54,15 +58,15 @@ def __init__(self, port, rate=115200, timeout=0.025, debug=False):
5458
self._driver = DobotDriver(port, rate)
5559
self._driver.Open(timeout)
5660
self._ik = DobotInverseKinematics(debug=debug)
57-
self._x = 160.0
58-
self._y = 0.0
59-
self._z = 215.0
60-
self._baseAngle = 0.0
61-
self._rearAngle = 90.0
62-
self._foreAngle = 0.0
61+
# Initialize arms current configuration from accelerometers
62+
accels = self._driver.GetAccelerometers()
63+
accelRear = accels[1]
64+
accelFore = accels[2]
65+
rearAngle = math.pi / 2 - self._driver.accelToRadians(accelRear, accelOffsets[0])
66+
foreAngle = self._driver.accelToRadians(accelFore, accelOffsets[1])
6367
self._baseSteps = long(0)
64-
self._rearSteps = long(0)
65-
self._foreSteps = long(0)
68+
self._rearSteps = long((rearAngle / math.pi / 2.0) * rearArmActualStepsPerRevolution + 0.5)
69+
self._foreSteps = long((foreAngle / math.pi / 2.0) * foreArmActualStepsPerRevolution + 0.5)
6670

6771
def _debug(self, *args):
6872
if self._debugOn:
Lines changed: 49 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,49 @@
1+
#! /usr/bin/env python
2+
3+
"""
4+
open-dobot Calibration Tool.
5+
6+
This tool continuously reports accelerometers and angles from those.
7+
8+
Use this tool to find offsets for your accelerometers:
9+
1. Turn off power on the arm and disconnect USB cable
10+
2. Remove accelerometers from the arm and put them on a flat surface that has no inclination
11+
3. Connect USB cable
12+
4. Enable accelerometers reporting mode
13+
4.1. Push and "sensor Calibration" button
14+
4.2. Push and release "Reset" button
15+
4.3. Start this tool (still holding "Sensor Calibration" button)
16+
4.4. Wait for the accelerometer data to start flowing on your console/whatever_you_use_to_start_this_tool
17+
4.5. Release the "Sensor Calibration" button
18+
5 Gently push the accelerometers so that they are evenly on the surface. Don't touch any contacts/leads.
19+
You can push them one by one, not necessary to push both at the same time
20+
6. Note the "Raw" data from accelerometers reported on the console. Those are your accelerometers' offsets
21+
7. Turn off power on the arm, disconnect USB cable, mount accelerometers back onto the arm
22+
23+
Author: maxosprojects (March 18 2016)
24+
Additional Authors: <put your name here>
25+
26+
Version: 0.4.0
27+
28+
License: MIT
29+
"""
30+
import math
31+
32+
from DobotDriver import DobotDriver
33+
34+
driver = DobotDriver('/dev/tty.usbmodem1421', 115200)
35+
driver.Open()
36+
37+
# Offsets must be found using this tool for your Dobot once
38+
# (rear arm, forearm)
39+
offsets = (1024, 1024)
40+
41+
def toEndEffectorHeight(rear, fore):
42+
return 88.0 - 160.0 * math.sin(fore) + 135.0 * math.sin(rear)
43+
44+
while True:
45+
ret = driver.GetAccelerometers()
46+
print "Rear arm: {0:10f} | Forearm: {1:10f} | End effector height: {2:10f} | Raw rear arm: {3:4d} | Raw forearm: {4:4d}".format(\
47+
driver.accelToAngle(ret[1], offsets[0]), driver.accelToAngle(ret[2], offsets[1]),\
48+
toEndEffectorHeight(driver.accelToRadians(ret[1], offsets[0]), driver.accelToRadians(ret[2], offsets[1])),\
49+
ret[1], ret[2])

application/fpga/python/example-accelerometers.py

Lines changed: 0 additions & 15 deletions
This file was deleted.

application/fpga/python/example-sdk.py

Lines changed: 10 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -19,17 +19,20 @@
1919

2020
dobot = Dobot('/dev/tty.usbmodem1421', debug=True)
2121

22-
dobot.moveTo(160.0, 0.0, 60.0, 1)
22+
duration = 1
23+
24+
dobot.moveTo(160.0, 0.0, 60.0, duration)
2325
print '======================================'
2426
for i in range(3):
25-
dobot.moveTo(160.0, 60.0, 60.0, 1)
27+
dobot.moveTo(160.0, 60.0, 60.0, duration)
2628
print '======================================'
27-
dobot.moveTo(220.0, 60.0, 60.0, 1)
29+
dobot.moveTo(220.0, 60.0, 60.0, duration)
2830
print '======================================'
29-
dobot.moveTo(220.0, -60.0, 60.0, 1)
31+
dobot.moveTo(220.0, -60.0, 60.0, duration)
3032
print '======================================'
31-
dobot.moveTo(160.0, -60.0, 60.0, 1)
33+
dobot.moveTo(160.0, -60.0, 60.0, duration)
3234
print '======================================'
33-
dobot.moveTo(160.0, 0.0, 60.0, 1)
35+
dobot.moveTo(160.0, 0.0, 60.0, duration)
36+
print '======================================'
37+
dobot.moveTo(160.0, 0.0, 215.0, duration)
3438
print '======================================'
35-
dobot.moveTo(160.0, 0.0, 215.0, 1)

docs/images/full-description.png

122 KB
Loading

0 commit comments

Comments
 (0)