From 7fbb13db4d482ddd65c581a7bd085648bbe1a418 Mon Sep 17 00:00:00 2001 From: leon Date: Fri, 1 Jul 2016 21:36:07 +0900 Subject: [PATCH 1/3] example - python (linux strange print out problem solved) --- python/protocol1_0/bulk_read.py | 16 +++++++++------ python/protocol1_0/factory_reset.py | 20 +++++++++++-------- python/protocol1_0/multi_port.py | 20 +++++++++++-------- python/protocol1_0/ping.py | 16 +++++++++------ python/protocol1_0/read_write.py | 16 +++++++++------ python/protocol1_0/sync_write.py | 16 +++++++++------ python/protocol2_0/broadcast_ping.py | 16 +++++++++------ python/protocol2_0/bulk_read_write.py | 16 +++++++++------ python/protocol2_0/factory_reset.py | 20 +++++++++++-------- python/protocol2_0/indirect_address.py | 16 +++++++++------ python/protocol2_0/multi_port.py | 20 +++++++++++-------- python/protocol2_0/ping.py | 16 +++++++++------ python/protocol2_0/read_write.py | 16 +++++++++------ python/protocol2_0/rebooting.py | 18 ++++++++++------- python/protocol2_0/sync_read_write.py | 16 +++++++++------ python/protocol_combined/protocol_combined.py | 16 +++++++++------ 16 files changed, 169 insertions(+), 105 deletions(-) diff --git a/python/protocol1_0/bulk_read.py b/python/protocol1_0/bulk_read.py index a7b288bf..5395fee7 100644 --- a/python/protocol1_0/bulk_read.py +++ b/python/protocol1_0/bulk_read.py @@ -18,19 +18,23 @@ # Be sure that Dynamixel MX properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 1000000) # -import os, sys, ctypes +import os, ctypes if os.name == 'nt': import msvcrt def getch(): return msvcrt.getch().decode() else: - import tty, termios + import sys, tty, termios fd = sys.stdin.fileno() old_settings = termios.tcgetattr(fd) - tty.setraw(sys.stdin.fileno()) def getch(): - return sys.stdin.read(1) + try: + tty.setraw(sys.stdin.fileno()) + ch = sys.stdin.read(1) + finally: + termios.tcsetattr(fd, termios.TCSADRAIN, old_settings) + return ch os.sys.path.append('../dynamixel_functions_py') # Path setting @@ -95,7 +99,7 @@ def getch(): else: print("Failed to open the port!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() @@ -105,7 +109,7 @@ def getch(): else: print("Failed to change the baudrate!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() diff --git a/python/protocol1_0/factory_reset.py b/python/protocol1_0/factory_reset.py index 00ec6f69..d8f983d8 100644 --- a/python/protocol1_0/factory_reset.py +++ b/python/protocol1_0/factory_reset.py @@ -22,19 +22,23 @@ # This example resets all properties of Dynamixel to default values, such as %% ID : 1 / Baudnum : 34 (Baudrate : 57600) # -import os, sys +import os if os.name == 'nt': import msvcrt def getch(): return msvcrt.getch().decode() else: - import tty, termios + import sys, tty, termios fd = sys.stdin.fileno() old_settings = termios.tcgetattr(fd) - tty.setraw(sys.stdin.fileno()) def getch(): - return sys.stdin.read(1) + try: + tty.setraw(sys.stdin.fileno()) + ch = sys.stdin.read(1) + finally: + termios.tcsetattr(fd, termios.TCSADRAIN, old_settings) + return ch os.sys.path.append('../dynamixel_functions_py') # Path setting @@ -79,7 +83,7 @@ def getch(): else: print("Failed to open the port!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() @@ -89,7 +93,7 @@ def getch(): else: print("Failed to change the baudrate!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() @@ -118,7 +122,7 @@ def getch(): print("Succeed to change the controller baudrate to : %d" % (FACTORYRST_DEFAULTBAUDRATE)) else: print("Failed to change the controller baudrate") - msvcrt.getch() + getch() quit() # Read Dynamixel baudnum @@ -144,7 +148,7 @@ def getch(): print("Succeed to change the controller baudrate to : %d" % (BAUDRATE)) else: print("Failed to change the controller baudrate") - msvcrt.getch() + getch() quit() sleep(0.2) diff --git a/python/protocol1_0/multi_port.py b/python/protocol1_0/multi_port.py index a384a51b..ca76ea10 100644 --- a/python/protocol1_0/multi_port.py +++ b/python/protocol1_0/multi_port.py @@ -18,19 +18,23 @@ # Be sure that Dynamixel MX properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 1000000 [1M]) # -import os, sys +import os if os.name == 'nt': import msvcrt def getch(): return msvcrt.getch().decode() else: - import tty, termios + import sys, tty, termios fd = sys.stdin.fileno() old_settings = termios.tcgetattr(fd) - tty.setraw(sys.stdin.fileno()) def getch(): - return sys.stdin.read(1) + try: + tty.setraw(sys.stdin.fileno()) + ch = sys.stdin.read(1) + finally: + termios.tcsetattr(fd, termios.TCSADRAIN, old_settings) + return ch os.sys.path.append('../dynamixel_functions_py') # Path setting @@ -85,7 +89,7 @@ def getch(): else: print("Failed to open the port!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() # Open port2 @@ -94,7 +98,7 @@ def getch(): else: print("Failed to open the port!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() @@ -104,7 +108,7 @@ def getch(): else: print("Failed to change the baudrate!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() # Set port2 baudrate @@ -113,7 +117,7 @@ def getch(): else: print("Failed to change the baudrate!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() diff --git a/python/protocol1_0/ping.py b/python/protocol1_0/ping.py index df602c64..16540790 100644 --- a/python/protocol1_0/ping.py +++ b/python/protocol1_0/ping.py @@ -18,19 +18,23 @@ # Be sure that Dynamixel MX properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 1000000 [1M]) # -import os, sys +import os if os.name == 'nt': import msvcrt def getch(): return msvcrt.getch().decode() else: - import tty, termios + import sys, tty, termios fd = sys.stdin.fileno() old_settings = termios.tcgetattr(fd) - tty.setraw(sys.stdin.fileno()) def getch(): - return sys.stdin.read(1) + try: + tty.setraw(sys.stdin.fileno()) + ch = sys.stdin.read(1) + finally: + termios.tcsetattr(fd, termios.TCSADRAIN, old_settings) + return ch os.sys.path.append('../dynamixel_functions_py') # Path setting @@ -64,7 +68,7 @@ def getch(): else: print("Failed to open the port!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() # Set port baudrate @@ -73,7 +77,7 @@ def getch(): else: print("Failed to change the baudrate!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() diff --git a/python/protocol1_0/read_write.py b/python/protocol1_0/read_write.py index 43a81dac..b2663159 100644 --- a/python/protocol1_0/read_write.py +++ b/python/protocol1_0/read_write.py @@ -18,19 +18,23 @@ # Be sure that Dynamixel MX properties are already set as ## ID : 1 / Baudnum : 1 (Baudrate : 1000000 [1M]) # -import os, sys +import os if os.name == 'nt': import msvcrt def getch(): return msvcrt.getch().decode() else: - import tty, termios + import sys, tty, termios fd = sys.stdin.fileno() old_settings = termios.tcgetattr(fd) - tty.setraw(sys.stdin.fileno()) def getch(): - return sys.stdin.read(1) + try: + tty.setraw(sys.stdin.fileno()) + ch = sys.stdin.read(1) + finally: + termios.tcsetattr(fd, termios.TCSADRAIN, old_settings) + return ch os.sys.path.append('../dynamixel_functions_py') # Path setting @@ -82,7 +86,7 @@ def getch(): else: print("Failed to open the port!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() # Set port baudrate @@ -91,7 +95,7 @@ def getch(): else: print("Failed to change the baudrate!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() diff --git a/python/protocol1_0/sync_write.py b/python/protocol1_0/sync_write.py index a49fa7f6..1ca8d7db 100644 --- a/python/protocol1_0/sync_write.py +++ b/python/protocol1_0/sync_write.py @@ -18,19 +18,23 @@ # Be sure that Dynamixel MX properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 1000000 [1M]) # -import os, sys, ctypes +import os, ctypes if os.name == 'nt': import msvcrt def getch(): return msvcrt.getch().decode() else: - import tty, termios + import sys, tty, termios fd = sys.stdin.fileno() old_settings = termios.tcgetattr(fd) - tty.setraw(sys.stdin.fileno()) def getch(): - return sys.stdin.read(1) + try: + tty.setraw(sys.stdin.fileno()) + ch = sys.stdin.read(1) + finally: + termios.tcsetattr(fd, termios.TCSADRAIN, old_settings) + return ch os.sys.path.append('../dynamixel_functions_py') # Path setting @@ -91,7 +95,7 @@ def getch(): else: print("Failed to open the port!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() # Set port baudrate @@ -100,7 +104,7 @@ def getch(): else: print("Failed to change the baudrate!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() diff --git a/python/protocol2_0/broadcast_ping.py b/python/protocol2_0/broadcast_ping.py index 6c5017d1..61f7de0d 100644 --- a/python/protocol2_0/broadcast_ping.py +++ b/python/protocol2_0/broadcast_ping.py @@ -18,19 +18,23 @@ # Be sure that Dynamixel PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000 [1M]) # -import os, sys, ctypes +import os, ctypes if os.name == 'nt': import msvcrt def getch(): return msvcrt.getch().decode() else: - import tty, termios + import sys, tty, termios fd = sys.stdin.fileno() old_settings = termios.tcgetattr(fd) - tty.setraw(sys.stdin.fileno()) def getch(): - return sys.stdin.read(1) + try: + tty.setraw(sys.stdin.fileno()) + ch = sys.stdin.read(1) + finally: + termios.tcsetattr(fd, termios.TCSADRAIN, old_settings) + return ch os.sys.path.append('../dynamixel_functions_py') # Path setting @@ -65,7 +69,7 @@ def getch(): else: print("Failed to open the port!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() # Set port baudrate @@ -74,7 +78,7 @@ def getch(): else: print("Failed to change the baudrate!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() # Try to broadcast ping the Dynamixel diff --git a/python/protocol2_0/bulk_read_write.py b/python/protocol2_0/bulk_read_write.py index 915504d6..c98a12cd 100644 --- a/python/protocol2_0/bulk_read_write.py +++ b/python/protocol2_0/bulk_read_write.py @@ -18,19 +18,23 @@ # Be sure that Dynamixel PRO properties are already set as %% ID : 1 and 2 / Baudnum : 3 (Baudrate : 1000000 [1M]) # -import os, sys, ctypes +import os, ctypes if os.name == 'nt': import msvcrt def getch(): return msvcrt.getch().decode() else: - import tty, termios + import sys, tty, termios fd = sys.stdin.fileno() old_settings = termios.tcgetattr(fd) - tty.setraw(sys.stdin.fileno()) def getch(): - return sys.stdin.read(1) + try: + tty.setraw(sys.stdin.fileno()) + ch = sys.stdin.read(1) + finally: + termios.tcsetattr(fd, termios.TCSADRAIN, old_settings) + return ch os.sys.path.append('../dynamixel_functions_py') # Path setting @@ -100,7 +104,7 @@ def getch(): else: print("Failed to open the port!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() # Set port baudrate @@ -109,7 +113,7 @@ def getch(): else: print("Failed to change the baudrate!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() diff --git a/python/protocol2_0/factory_reset.py b/python/protocol2_0/factory_reset.py index 99d88bda..337fd907 100644 --- a/python/protocol2_0/factory_reset.py +++ b/python/protocol2_0/factory_reset.py @@ -22,19 +22,23 @@ # This example resets all properties of Dynamixel to default values, such as %% ID : 1 / Baudnum : 1 (Baudrate : 57600) # -import os, sys +import os if os.name == 'nt': import msvcrt def getch(): return msvcrt.getch().decode() else: - import tty, termios + import sys, tty, termios fd = sys.stdin.fileno() old_settings = termios.tcgetattr(fd) - tty.setraw(sys.stdin.fileno()) def getch(): - return sys.stdin.read(1) + try: + tty.setraw(sys.stdin.fileno()) + ch = sys.stdin.read(1) + finally: + termios.tcsetattr(fd, termios.TCSADRAIN, old_settings) + return ch os.sys.path.append('../dynamixel_functions_py') # Path setting @@ -81,7 +85,7 @@ def getch(): else: print("Failed to open the port!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() # Set port baudrate @@ -90,7 +94,7 @@ def getch(): else: print("Failed to change the baudrate!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() @@ -119,7 +123,7 @@ def getch(): print("Succeed to change the controller baudrate to : %d" % (FACTORYRST_DEFAULTBAUDRATE)) else: print("Failed to change the controller baudrate") - msvcrt.getch() + getch() quit() # Read Dynamixel baudnum @@ -145,7 +149,7 @@ def getch(): print("Succeed to change the controller baudrate to : %d" % (BAUDRATE)) else: print("Failed to change the controller baudrate") - msvcrt.getch() + getch() quit() sleep(0.2) diff --git a/python/protocol2_0/indirect_address.py b/python/protocol2_0/indirect_address.py index af54bbea..0c6553ec 100644 --- a/python/protocol2_0/indirect_address.py +++ b/python/protocol2_0/indirect_address.py @@ -18,19 +18,23 @@ # Be sure that Dynamixel PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000 [1M]) # -import os, sys, ctypes +import os, ctypes if os.name == 'nt': import msvcrt def getch(): return msvcrt.getch().decode() else: - import tty, termios + import sys, tty, termios fd = sys.stdin.fileno() old_settings = termios.tcgetattr(fd) - tty.setraw(sys.stdin.fileno()) def getch(): - return sys.stdin.read(1) + try: + tty.setraw(sys.stdin.fileno()) + ch = sys.stdin.read(1) + finally: + termios.tcsetattr(fd, termios.TCSADRAIN, old_settings) + return ch os.sys.path.append('../dynamixel_functions_py') # Path setting @@ -106,7 +110,7 @@ def getch(): else: print("Failed to open the port!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() # Set port baudrate @@ -115,7 +119,7 @@ def getch(): else: print("Failed to change the baudrate!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() diff --git a/python/protocol2_0/multi_port.py b/python/protocol2_0/multi_port.py index 0d8fb158..57e88bc4 100644 --- a/python/protocol2_0/multi_port.py +++ b/python/protocol2_0/multi_port.py @@ -18,19 +18,23 @@ # Be sure that Dynamixel PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000) # -import os, sys +import os if os.name == 'nt': import msvcrt def getch(): return msvcrt.getch().decode() else: - import tty, termios + import sys, tty, termios fd = sys.stdin.fileno() old_settings = termios.tcgetattr(fd) - tty.setraw(sys.stdin.fileno()) def getch(): - return sys.stdin.read(1) + try: + tty.setraw(sys.stdin.fileno()) + ch = sys.stdin.read(1) + finally: + termios.tcsetattr(fd, termios.TCSADRAIN, old_settings) + return ch os.sys.path.append('../dynamixel_functions_py') # Path setting @@ -85,7 +89,7 @@ def getch(): else: print("Failed to open the port!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() # Open port2 @@ -94,7 +98,7 @@ def getch(): else: print("Failed to open the port!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() @@ -104,7 +108,7 @@ def getch(): else: print("Failed to change the baudrate!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() # Set port2 baudrate @@ -113,7 +117,7 @@ def getch(): else: print("Failed to change the baudrate!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() diff --git a/python/protocol2_0/ping.py b/python/protocol2_0/ping.py index 1bdcf642..890a10e5 100644 --- a/python/protocol2_0/ping.py +++ b/python/protocol2_0/ping.py @@ -18,19 +18,23 @@ # Be sure that Dynamixel PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000 [1M]) # -import os, sys +import os if os.name == 'nt': import msvcrt def getch(): return msvcrt.getch().decode() else: - import tty, termios + import sys, tty, termios fd = sys.stdin.fileno() old_settings = termios.tcgetattr(fd) - tty.setraw(sys.stdin.fileno()) def getch(): - return sys.stdin.read(1) + try: + tty.setraw(sys.stdin.fileno()) + ch = sys.stdin.read(1) + finally: + termios.tcsetattr(fd, termios.TCSADRAIN, old_settings) + return ch os.sys.path.append('../dynamixel_functions_py') # Path setting @@ -64,7 +68,7 @@ def getch(): else: print("Failed to open the port!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() # Set port baudrate @@ -73,7 +77,7 @@ def getch(): else: print("Failed to change the baudrate!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() diff --git a/python/protocol2_0/read_write.py b/python/protocol2_0/read_write.py index 27343552..4be88bb5 100644 --- a/python/protocol2_0/read_write.py +++ b/python/protocol2_0/read_write.py @@ -18,19 +18,23 @@ # Be sure that Dynamixel PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000 [1M]) # -import os, sys +import os if os.name == 'nt': import msvcrt def getch(): return msvcrt.getch().decode() else: - import tty, termios + import sys, tty, termios fd = sys.stdin.fileno() old_settings = termios.tcgetattr(fd) - tty.setraw(sys.stdin.fileno()) def getch(): - return sys.stdin.read(1) + try: + tty.setraw(sys.stdin.fileno()) + ch = sys.stdin.read(1) + finally: + termios.tcsetattr(fd, termios.TCSADRAIN, old_settings) + return ch os.sys.path.append('../dynamixel_functions_py') # Path setting @@ -82,7 +86,7 @@ def getch(): else: print("Failed to open the port!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() # Set port baudrate @@ -91,7 +95,7 @@ def getch(): else: print("Failed to change the baudrate!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() diff --git a/python/protocol2_0/rebooting.py b/python/protocol2_0/rebooting.py index f124c809..90e71a3d 100644 --- a/python/protocol2_0/rebooting.py +++ b/python/protocol2_0/rebooting.py @@ -18,19 +18,23 @@ # Be sure that Dynamixel PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000 [1M]) # -import os, sys +import os if os.name == 'nt': import msvcrt def getch(): return msvcrt.getch().decode() else: - import tty, termios + import sys, tty, termios fd = sys.stdin.fileno() old_settings = termios.tcgetattr(fd) - tty.setraw(sys.stdin.fileno()) def getch(): - return sys.stdin.read(1) + try: + tty.setraw(sys.stdin.fileno()) + ch = sys.stdin.read(1) + finally: + termios.tcsetattr(fd, termios.TCSADRAIN, old_settings) + return ch os.sys.path.append('../dynamixel_functions_py') # Path setting @@ -64,7 +68,7 @@ def getch(): else: print("Failed to open the port!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() # Set port baudrate @@ -73,12 +77,12 @@ def getch(): else: print("Failed to change the baudrate!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() # Trigger print("Press any key to reboot") -msvcrt.getch() +getch() print("See the Dynamixel LED flickering") # Try reboot diff --git a/python/protocol2_0/sync_read_write.py b/python/protocol2_0/sync_read_write.py index bd30fb27..81c52944 100644 --- a/python/protocol2_0/sync_read_write.py +++ b/python/protocol2_0/sync_read_write.py @@ -18,19 +18,23 @@ # Be sure that Dynamixel PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000 [1M]) # -import os, sys, ctypes +import os, ctypes if os.name == 'nt': import msvcrt def getch(): return msvcrt.getch().decode() else: - import tty, termios + import sys, tty, termios fd = sys.stdin.fileno() old_settings = termios.tcgetattr(fd) - tty.setraw(sys.stdin.fileno()) def getch(): - return sys.stdin.read(1) + try: + tty.setraw(sys.stdin.fileno()) + ch = sys.stdin.read(1) + finally: + termios.tcsetattr(fd, termios.TCSADRAIN, old_settings) + return ch os.sys.path.append('../dynamixel_functions_py') # Path setting @@ -96,7 +100,7 @@ def getch(): else: print("Failed to open the port!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() @@ -106,7 +110,7 @@ def getch(): else: print("Failed to change the baudrate!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() diff --git a/python/protocol_combined/protocol_combined.py b/python/protocol_combined/protocol_combined.py index 60add7c6..a2fcd3ae 100644 --- a/python/protocol_combined/protocol_combined.py +++ b/python/protocol_combined/protocol_combined.py @@ -21,19 +21,23 @@ # This example configures two different control tables (especially, if it uses Dynamixel and Dynamixel PRO). It may modify critical Dynamixel parameter on the control table, if Dynamixels have wrong ID. # -import os, sys +import os if os.name == 'nt': import msvcrt def getch(): return msvcrt.getch().decode() else: - import tty, termios + import sys, tty, termios fd = sys.stdin.fileno() old_settings = termios.tcgetattr(fd) - tty.setraw(sys.stdin.fileno()) def getch(): - return sys.stdin.read(1) + try: + tty.setraw(sys.stdin.fileno()) + ch = sys.stdin.read(1) + finally: + termios.tcsetattr(fd, termios.TCSADRAIN, old_settings) + return ch os.sys.path.append('../dynamixel_functions_py') # Path setting @@ -96,7 +100,7 @@ def getch(): else: print("Failed to open the port!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() @@ -106,7 +110,7 @@ def getch(): else: print("Failed to change the baudrate!") print("Press any key to terminate...") - msvcrt.getch() + getch() quit() From b6caf4fce4ec6f21840fe61b21d96ef3c65b5022 Mon Sep 17 00:00:00 2001 From: leon Date: Fri, 1 Jul 2016 21:48:24 +0900 Subject: [PATCH 2/3] example - python (protocol 2.0 sync_read_write \n removed) --- python/protocol2_0/sync_read_write.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/protocol2_0/sync_read_write.py b/python/protocol2_0/sync_read_write.py index 81c52944..99b21a80 100644 --- a/python/protocol2_0/sync_read_write.py +++ b/python/protocol2_0/sync_read_write.py @@ -195,7 +195,7 @@ def getch(): # Get Dynamixel#2 present position value dxl2_present_position = dynamixel.groupSyncReadGetData(groupread_num, DXL2_ID, ADDR_PRO_PRESENT_POSITION, LEN_PRO_PRESENT_POSITION) - print("[ID:%03d] GoalPos:%03d PresPos:%03d\t[ID:%03d] GoalPos:%03d PresPos:%03d\n" % (DXL1_ID, dxl_goal_position[index], dxl1_present_position, DXL2_ID, dxl_goal_position[index], dxl2_present_position)) + print("[ID:%03d] GoalPos:%03d PresPos:%03d\t[ID:%03d] GoalPos:%03d PresPos:%03d" % (DXL1_ID, dxl_goal_position[index], dxl1_present_position, DXL2_ID, dxl_goal_position[index], dxl2_present_position)) if not ((abs(dxl_goal_position[index] - dxl1_present_position) > DXL_MOVING_STATUS_THRESHOLD) or (abs(dxl_goal_position[index] - dxl2_present_position) > DXL_MOVING_STATUS_THRESHOLD)): break From 42d0c63f5efe0e3e280dd6f0552be795034d81d9 Mon Sep 17 00:00:00 2001 From: leon Date: Fri, 1 Jul 2016 21:50:52 +0900 Subject: [PATCH 3/3] ReleaseNote.txt updated --- ReleaseNote.txt | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/ReleaseNote.txt b/ReleaseNote.txt index cfd09b0c..01ac88eb 100644 --- a/ReleaseNote.txt +++ b/ReleaseNote.txt @@ -1,3 +1,13 @@ +============================================== + Dynamixel SDK v3.3.2 (Protocol 1.0/2.0) +============================================== + +- 06.30.2016 + +* SDK Python strange printout problem solved + +* Solved issue : #3, #8 + ============================================== Dynamixel SDK v3.3.1 (Protocol 1.0/2.0) ==============================================