-
Notifications
You must be signed in to change notification settings - Fork 3
/
setup.py
211 lines (180 loc) · 6.65 KB
/
setup.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
from distutils.core import setup, Extension
import distutils.core
from Cython.Distutils import build_ext
import subprocess
import os.path
import tempfile
import zipfile
patch = """diff DXL_SDK_LINUX_v1_01/include/dynamixel.h DXL_SDK_LINUX_v1_01/include/dynamixel.h
index 8a8ed70..270cfc6 100644
--- DXL_SDK_LINUX_v1_01/include/dynamixel.h
+++ DXL_SDK_LINUX_v1_01/include/dynamixel.h
@@ -26,6 +26,7 @@ void dxl_set_txpacket_instruction(int instruction);
#define INST_ACTION (5)\r
#define INST_RESET (6)\r
#define INST_SYNC_WRITE (131)\r
+#define INST_SYNC_READ (132)\r
\r
void dxl_set_txpacket_parameter(int index, int value);\r
void dxl_set_txpacket_length(int length);\r
diff DXL_SDK_LINUX_v1_01/src/dxl_hal.c DXL_SDK_LINUX_v1_01/src/dxl_hal.c
index d78c468..26b3e08 100644
--- DXL_SDK_LINUX_v1_01/src/dxl_hal.c
+++ DXL_SDK_LINUX_v1_01/src/dxl_hal.c
@@ -19,10 +19,9 @@ char gDeviceName[20];
int dxl_hal_open(int deviceIndex, float baudrate)
{
struct termios newtio;
- struct serial_struct serinfo;
char dev_name[100] = {0, };
- sprintf(dev_name, "/dev/ttyUSB%d", deviceIndex);
+ sprintf(dev_name, "/dev/ttyACM%d", deviceIndex);
strcpy(gDeviceName, dev_name);
memset(&newtio, 0, sizeof(newtio));
@@ -33,7 +32,7 @@ int dxl_hal_open(int deviceIndex, float baudrate)
goto DXL_HAL_OPEN_ERROR;
}
- newtio.c_cflag = B38400|CS8|CLOCAL|CREAD;
+ newtio.c_cflag = B1000000|CS8|CLOCAL|CREAD;
newtio.c_iflag = IGNPAR;
newtio.c_oflag = 0;
newtio.c_lflag = 0;
@@ -46,20 +45,6 @@ int dxl_hal_open(int deviceIndex, float baudrate)
if(gSocket_fd == -1)
return 0;
- if(ioctl(gSocket_fd, TIOCGSERIAL, &serinfo) < 0) {
- fprintf(stderr, "Cannot get serial info\\n");
- return 0;
- }
-
- serinfo.flags &= ~ASYNC_SPD_MASK;
- serinfo.flags |= ASYNC_SPD_CUST;
- serinfo.custom_divisor = serinfo.baud_base / baudrate;
-
- if(ioctl(gSocket_fd, TIOCSSERIAL, &serinfo) < 0) {
- fprintf(stderr, "Cannot set serial info\\n");
- return 0;
- }
-
dxl_hal_close();
gfByteTransTime = (float)((1000.0f / baudrate) * 12.0f);
@@ -73,7 +58,7 @@ int dxl_hal_open(int deviceIndex, float baudrate)
goto DXL_HAL_OPEN_ERROR;
}
- newtio.c_cflag = B38400|CS8|CLOCAL|CREAD;
+ newtio.c_cflag = B1000000|CS8|CLOCAL|CREAD;
newtio.c_iflag = IGNPAR;
newtio.c_oflag = 0;
newtio.c_lflag = 0;
@@ -99,25 +84,10 @@ void dxl_hal_close()
int dxl_hal_set_baud( float baudrate )
{
- struct serial_struct serinfo;
if(gSocket_fd == -1)
return 0;
- if(ioctl(gSocket_fd, TIOCGSERIAL, &serinfo) < 0) {
- fprintf(stderr, "Cannot get serial info\\n");
- return 0;
- }
-
- serinfo.flags &= ~ASYNC_SPD_MASK;
- serinfo.flags |= ASYNC_SPD_CUST;
- serinfo.custom_divisor = serinfo.baud_base / baudrate;
-
- if(ioctl(gSocket_fd, TIOCSSERIAL, &serinfo) < 0) {
- fprintf(stderr, "Cannot set serial info\\n");
- return 0;
- }
-
//dxl_hal_close();
//dxl_hal_open(gDeviceName, baudrate);
diff DXL_SDK_LINUX_v1_01/src/dynamixel.c DXL_SDK_LINUX_v1_01/src/dynamixel.c
index 3800c18..d292caf 100644
--- DXL_SDK_LINUX_v1_01/src/dynamixel.c
+++ DXL_SDK_LINUX_v1_01/src/dynamixel.c
@@ -58,7 +58,8 @@ void dxl_tx_packet(void)
&& gbInstructionPacket[INSTRUCTION] != INST_REG_WRITE
&& gbInstructionPacket[INSTRUCTION] != INST_ACTION
&& gbInstructionPacket[INSTRUCTION] != INST_RESET
- && gbInstructionPacket[INSTRUCTION] != INST_SYNC_WRITE )
+ && gbInstructionPacket[INSTRUCTION] != INST_SYNC_WRITE
+ && gbInstructionPacket[INSTRUCTION] != INST_SYNC_READ )
{
gbCommStatus = COMM_TXERROR;
giBusUsing = 0;
@@ -84,7 +85,8 @@ void dxl_tx_packet(void)
return;
}
- if( gbInstructionPacket[INSTRUCTION] == INST_READ )
+ if( gbInstructionPacket[INSTRUCTION] == INST_READ ||
+ gbInstructionPacket[INSTRUCTION] == INST_SYNC_READ )
dxl_hal_set_timeout( gbInstructionPacket[PARAMETER+1] + 6 );
else
dxl_hal_set_timeout( 6 );
"""
def patch_dxl_sdk():
sp = subprocess.Popen(["patch","-N","-r","-","-p0"],stdin=subprocess.PIPE, stdout=subprocess.PIPE)
print sp.communicate(input=patch)[0]
def download_dxl_sdk():
if os.path.exists("DXL_SDK_LINUX_v1_01"):
print "Dynamixel SDK already downloaded"
return
else:
try:
import pycurl
curl = pycurl.Curl()
curl.setopt(pycurl.URL, "http://support.robotis.com/en/baggage_files/dynamixel_sdk/dxl_sdk_linux_v1_01.zip" )
with tempfile.TemporaryFile() as tmpfile:
curl.setopt( pycurl.WRITEDATA,tmpfile )
curl.perform()
zf = zipfile.ZipFile( tmpfile, "r" )
zf.extractall()
except ImportError,e:
print "PyCURL not found, trying to manually download"
fname = tempfile.mkstemp()[1]
try:
subprocess.call(["curl","http://support.robotis.com/en/baggage_files/dynamixel_sdk/dxl_sdk_linux_v1_01.zip","-o",fname])
zf = zipfile.ZipFile( fname, "r" )
zf.extractall()
os.unlink(fname)
except:
print "Could not run curl as subprocess, trying wget"
subprocess.call(["wget","http://support.robotis.com/en/baggage_files/dynamixel_sdk/dxl_sdk_linux_v1_01.zip","-O",fname])
zf = zipfile.ZipFile( fname, "r" )
zf.extractall()
os.unlink(fname)
except Exception, e:
print """
****************************** FAIL *******************************************
* I tried really hard but I could not download the dynamixel SDK. This
* could be due to lack of network connection or maybe you could try
* installing curl or wget on your system.
*
* If that doesn't work, you will need to download it manually. It
* should be available at
*
* http://support.robotis.com/en/baggage_files/dynamixel_sdk/dxl_sdk_linux_v1_01.zip
*
* Once you have it, unzip it so that there is a directory called
* DXL_SDK_LINUX_v1_01 in the current directory and re-run
*
* python setup.py build
*
*******************************************************************************
"""
raise e
class build_bindings(build_ext):
def run(self):
download_dxl_sdk()
patch_dxl_sdk()
build_ext.run(self)
dynamixel_mod = Extension('usb2ax',
sources = ['DXL_SDK_LINUX_v1_01/src/dxl_hal.c',
'DXL_SDK_LINUX_v1_01/src/dynamixel.c',
'usb2ax.pyx'],
include_dirs = ['DXL_SDK_LINUX_v1_01/src/','DXL_SDK_LINUX_v1_01/include'])
setup (name = 'PyUSB2AX',
version = '1.0',
description = 'Python binding for controlling USB2AX',
ext_modules = [dynamixel_mod],
cmdclass = {"build_ext":build_bindings} )