Skip to content

Commit

Permalink
Merge pull request #13 from ROBOTIS-GIT/develop
Browse files Browse the repository at this point in the history
Dynamixel SDK v3.3.1 (Protocol 1.0/2.0)
  • Loading branch information
LeonJung authored Jun 30, 2016
2 parents 1cdbcc6 + ef79f53 commit ef7967b
Show file tree
Hide file tree
Showing 21 changed files with 294 additions and 90 deletions.
10 changes: 10 additions & 0 deletions ReleaseNote.txt
Original file line number Diff line number Diff line change
@@ -1,3 +1,13 @@
==============================================
Dynamixel SDK v3.3.1 (Protocol 1.0/2.0)
==============================================

- 06.30.2016

* SDK Python Errors in linux debugged

* Solved issue : #3, #8

==============================================
Dynamixel SDK v3.3.0 (Protocol 1.0/2.0)
==============================================
Expand Down
4 changes: 2 additions & 2 deletions python/dynamixel_functions_py/dynamixel_functions.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@
from ctypes import cdll
dxl_lib = cdll.LoadLibrary("../../c/build/win32/output/dxl_x86_c.dll") # for windows 32bit
# dxl_lib = cdll.LoadLibrary("../../c/build/win64/output/dxl_x64_c.dll") # for windows 64bit
# dxl_lib = cdll.LoadLibrary("../../c/build/linux32/dxl_x86_c.so") # for linux 32bit
# dxl_lib = cdll.LoadLibrary("../../c/build/linux64/dxl_x64_c.so") # for linux 64bit
# dxl_lib = cdll.LoadLibrary("../../c/build/linux32/libdxl_x86_c.so") # for linux 32bit
# dxl_lib = cdll.LoadLibrary("../../c/build/linux64/libdxl_x64_c.so") # for linux 64bit

# port_handler
portHandler = dxl_lib.portHandler
Expand Down
23 changes: 18 additions & 5 deletions python/protocol1_0/bulk_read.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,23 @@
# Be sure that Dynamixel MX properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 1000000)
#

import msvcrt
import ctypes
import init_path
from dynamixel_functions_py import dynamixel_functions as dynamixel # Uses Dynamixel SDK library
import os, sys, ctypes

if os.name == 'nt':
import msvcrt
def getch():
return msvcrt.getch().decode()
else:
import tty, termios
fd = sys.stdin.fileno()
old_settings = termios.tcgetattr(fd)
tty.setraw(sys.stdin.fileno())
def getch():
return sys.stdin.read(1)

os.sys.path.append('../dynamixel_functions_py') # Path setting

import dynamixel_functions as dynamixel # Uses Dynamixel SDK library

# Control table address
ADDR_MX_TORQUE_ENABLE = 24 # Control table address is different in Dynamixel model
Expand Down Expand Up @@ -129,7 +142,7 @@

while 1:
print("Press any key to continue! (or press ESC to quit!)")
if msvcrt.getch().decode() == chr(ESC_ASCII_VALUE):
if getch() == chr(ESC_ASCII_VALUE):
break

# Write Dynamixel#1 goal position
Expand Down
20 changes: 17 additions & 3 deletions python/protocol1_0/factory_reset.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,24 @@
# This example resets all properties of Dynamixel to default values, such as %% ID : 1 / Baudnum : 34 (Baudrate : 57600)
#

import os, sys

if os.name == 'nt':
import msvcrt
def getch():
return msvcrt.getch().decode()
else:
import tty, termios
fd = sys.stdin.fileno()
old_settings = termios.tcgetattr(fd)
tty.setraw(sys.stdin.fileno())
def getch():
return sys.stdin.read(1)

os.sys.path.append('../dynamixel_functions_py') # Path setting

from time import sleep
import msvcrt
import init_path
from dynamixel_functions_py import dynamixel_functions as dynamixel # Uses Dynamixel SDK library
import dynamixel_functions as dynamixel # Uses Dynamixel SDK library

# Control table address
ADDR_MX_BAUDRATE = 4 # Control table address is different in Dynamixel model
Expand Down
8 changes: 0 additions & 8 deletions python/protocol1_0/init_path.py

This file was deleted.

22 changes: 18 additions & 4 deletions python/protocol1_0/multi_port.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,23 @@
# Be sure that Dynamixel MX properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 1000000 [1M])
#

import msvcrt
import init_path
from dynamixel_functions_py import dynamixel_functions as dynamixel # Uses Dynamixel SDK library
import os, sys

if os.name == 'nt':
import msvcrt
def getch():
return msvcrt.getch().decode()
else:
import tty, termios
fd = sys.stdin.fileno()
old_settings = termios.tcgetattr(fd)
tty.setraw(sys.stdin.fileno())
def getch():
return sys.stdin.read(1)

os.sys.path.append('../dynamixel_functions_py') # Path setting

import dynamixel_functions as dynamixel # Uses Dynamixel SDK library

# Control table address
ADDR_MX_TORQUE_ENABLE = 24 # Control table address is different in Dynamixel model
Expand Down Expand Up @@ -124,7 +138,7 @@

while 1:
print("Press any key to continue! (or press ESC to quit!)")
if msvcrt.getch().decode() == chr(ESC_ASCII_VALUE):
if getch() == chr(ESC_ASCII_VALUE):
break

# Write Dynamixel#1 goal position
Expand Down
20 changes: 17 additions & 3 deletions python/protocol1_0/ping.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,23 @@
# Be sure that Dynamixel MX properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 1000000 [1M])
#

import msvcrt
import init_path
from dynamixel_functions_py import dynamixel_functions as dynamixel # Uses Dynamixel SDK library
import os, sys

if os.name == 'nt':
import msvcrt
def getch():
return msvcrt.getch().decode()
else:
import tty, termios
fd = sys.stdin.fileno()
old_settings = termios.tcgetattr(fd)
tty.setraw(sys.stdin.fileno())
def getch():
return sys.stdin.read(1)

os.sys.path.append('../dynamixel_functions_py') # Path setting

import dynamixel_functions as dynamixel # Uses Dynamixel SDK library

# Protocol version
PROTOCOL_VERSION = 1 # See which protocol version is used in the Dynamixel
Expand Down
22 changes: 18 additions & 4 deletions python/protocol1_0/read_write.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,23 @@
# Be sure that Dynamixel MX properties are already set as ## ID : 1 / Baudnum : 1 (Baudrate : 1000000 [1M])
#

import msvcrt
import init_path
from dynamixel_functions_py import dynamixel_functions as dynamixel # Uses Dynamixel SDK library
import os, sys

if os.name == 'nt':
import msvcrt
def getch():
return msvcrt.getch().decode()
else:
import tty, termios
fd = sys.stdin.fileno()
old_settings = termios.tcgetattr(fd)
tty.setraw(sys.stdin.fileno())
def getch():
return sys.stdin.read(1)

os.sys.path.append('../dynamixel_functions_py') # Path setting

import dynamixel_functions as dynamixel # Uses Dynamixel SDK library

# Control table address
ADDR_MX_TORQUE_ENABLE = 24 # Control table address is different in Dynamixel model
Expand Down Expand Up @@ -93,7 +107,7 @@

while 1:
print("Press any key to continue! (or press ESC to quit!)")
if msvcrt.getch().decode() == chr(ESC_ASCII_VALUE):
if getch() == chr(ESC_ASCII_VALUE):
break

# Write goal position
Expand Down
23 changes: 18 additions & 5 deletions python/protocol1_0/sync_write.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,23 @@
# Be sure that Dynamixel MX properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 1000000 [1M])
#

import msvcrt
import ctypes
import init_path
from dynamixel_functions_py import dynamixel_functions as dynamixel # Uses Dynamixel SDK library
import os, sys, ctypes

if os.name == 'nt':
import msvcrt
def getch():
return msvcrt.getch().decode()
else:
import tty, termios
fd = sys.stdin.fileno()
old_settings = termios.tcgetattr(fd)
tty.setraw(sys.stdin.fileno())
def getch():
return sys.stdin.read(1)

os.sys.path.append('../dynamixel_functions_py') # Path setting

import dynamixel_functions as dynamixel # Uses Dynamixel SDK library

# Control table address
ADDR_MX_TORQUE_ENABLE = 24 # Control table address is different in Dynamixel model
Expand Down Expand Up @@ -112,7 +125,7 @@

while 1:
print("Press any key to continue! (or press ESC to quit!)")
if msvcrt.getch().decode() == chr(ESC_ASCII_VALUE):
if getch() == chr(ESC_ASCII_VALUE):
break

# Add Dynamixel#1 goal position value to the Syncwrite storage
Expand Down
21 changes: 17 additions & 4 deletions python/protocol2_0/broadcast_ping.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,23 @@
# Be sure that Dynamixel PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000 [1M])
#

import msvcrt
import ctypes
import init_path
from dynamixel_functions_py import dynamixel_functions as dynamixel # Uses Dynamixel SDK library
import os, sys, ctypes

if os.name == 'nt':
import msvcrt
def getch():
return msvcrt.getch().decode()
else:
import tty, termios
fd = sys.stdin.fileno()
old_settings = termios.tcgetattr(fd)
tty.setraw(sys.stdin.fileno())
def getch():
return sys.stdin.read(1)

os.sys.path.append('../dynamixel_functions_py') # Path setting

import dynamixel_functions as dynamixel # Uses Dynamixel SDK library

# Protocol version
PROTOCOL_VERSION = 2 # See which protocol version is used in the Dynamixel
Expand Down
23 changes: 18 additions & 5 deletions python/protocol2_0/bulk_read_write.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,23 @@
# Be sure that Dynamixel PRO properties are already set as %% ID : 1 and 2 / Baudnum : 3 (Baudrate : 1000000 [1M])
#

import msvcrt
import ctypes
import init_path
from dynamixel_functions_py import dynamixel_functions as dynamixel # Uses Dynamixel SDK library
import os, sys, ctypes

if os.name == 'nt':
import msvcrt
def getch():
return msvcrt.getch().decode()
else:
import tty, termios
fd = sys.stdin.fileno()
old_settings = termios.tcgetattr(fd)
tty.setraw(sys.stdin.fileno())
def getch():
return sys.stdin.read(1)

os.sys.path.append('../dynamixel_functions_py') # Path setting

import dynamixel_functions as dynamixel # Uses Dynamixel SDK library

# Control table address
ADDR_PRO_TORQUE_ENABLE = 562 # Control table address is different in Dynamixel model
Expand Down Expand Up @@ -133,7 +146,7 @@

while 1:
print("Press any key to continue! (or press ESC to quit!)")
if msvcrt.getch().decode() == chr(ESC_ASCII_VALUE):
if getch() == chr(ESC_ASCII_VALUE):
break

# Add parameter storage for Dynamixel#1 goal position
Expand Down
20 changes: 17 additions & 3 deletions python/protocol2_0/factory_reset.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,24 @@
# This example resets all properties of Dynamixel to default values, such as %% ID : 1 / Baudnum : 1 (Baudrate : 57600)
#

import os, sys

if os.name == 'nt':
import msvcrt
def getch():
return msvcrt.getch().decode()
else:
import tty, termios
fd = sys.stdin.fileno()
old_settings = termios.tcgetattr(fd)
tty.setraw(sys.stdin.fileno())
def getch():
return sys.stdin.read(1)

os.sys.path.append('../dynamixel_functions_py') # Path setting

from time import sleep
import msvcrt
import init_path
from dynamixel_functions_py import dynamixel_functions as dynamixel # Uses Dynamixel SDK library
import dynamixel_functions as dynamixel # Uses Dynamixel SDK library

# Control table address
ADDR_PRO_BAUDRATE = 8 # Control table address is different in Dynamixel model
Expand Down
23 changes: 18 additions & 5 deletions python/protocol2_0/indirect_address.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,23 @@
# Be sure that Dynamixel PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000 [1M])
#

import msvcrt
import ctypes
import init_path
from dynamixel_functions_py import dynamixel_functions as dynamixel # Uses Dynamixel SDK library
import os, sys, ctypes

if os.name == 'nt':
import msvcrt
def getch():
return msvcrt.getch().decode()
else:
import tty, termios
fd = sys.stdin.fileno()
old_settings = termios.tcgetattr(fd)
tty.setraw(sys.stdin.fileno())
def getch():
return sys.stdin.read(1)

os.sys.path.append('../dynamixel_functions_py') # Path setting

import dynamixel_functions as dynamixel # Uses Dynamixel SDK library

# Control table address # Control table address is different in Dynamixel model
ADDR_PRO_INDIRECTADDRESS_FOR_WRITE = 49 # EEPROM region
Expand Down Expand Up @@ -193,7 +206,7 @@

while 1:
print("Press any key to continue! (or press ESC to quit!)")
if msvcrt.getch().decode() == chr(ESC_ASCII_VALUE):
if getch() == chr(ESC_ASCII_VALUE):
break

# Add Dynamixel#1 goal position value to the Syncwrite storage
Expand Down
8 changes: 0 additions & 8 deletions python/protocol2_0/init_path.py

This file was deleted.

Loading

0 comments on commit ef7967b

Please sign in to comment.