40 from dynamixel_sdk
import *
47 return msvcrt.getch().decode()
49 import sys, tty, termios
50 fd = sys.stdin.fileno()
51 old_settings = termios.tcgetattr(fd)
54 tty.setraw(sys.stdin.fileno())
55 ch = sys.stdin.read(1)
57 termios.tcsetattr(fd, termios.TCSADRAIN, old_settings)
61 ADDR_TORQUE_ENABLE = 64
62 ADDR_GOAL_POSITION = 116
63 ADDR_PRESENT_POSITION = 132
66 PROTOCOL_VERSION = 2.0
71 DEVICENAME =
'/dev/ttyUSB0'
76 DXL_MINIMUM_POSITION_VALUE = 0
77 DXL_MAXIMUM_POSITION_VALUE = 1000
78 DXL_MOVING_STATUS_THRESHOLD = 20
80 portHandler = PortHandler(DEVICENAME)
81 packetHandler = PacketHandler(PROTOCOL_VERSION)
84 print(
"Set Goal Position of ID %s = %s" % (data.id, data.position))
85 dxl_comm_result, dxl_error = packetHandler.write4ByteTxRx(portHandler, data.id, ADDR_GOAL_POSITION, data.position)
88 dxl_present_position, dxl_comm_result, dxl_error = packetHandler.read4ByteTxRx(portHandler, req.id, ADDR_PRESENT_POSITION)
89 print(
"Present Position of ID %s = %s" % (req.id, dxl_present_position))
90 return dxl_present_position
93 rospy.init_node(
'read_write_py_node')
94 rospy.Subscriber(
'set_position', SetPosition, set_goal_pos_callback)
95 rospy.Service(
'get_position', GetPosition, get_present_pos)
101 portHandler.openPort()
102 print(
"Succeeded to open the port")
104 print(
"Failed to open the port")
105 print(
"Press any key to terminate...")
111 portHandler.setBaudRate(BAUDRATE)
112 print(
"Succeeded to change the baudrate")
114 print(
"Failed to change the baudrate")
115 print(
"Press any key to terminate...")
120 dxl_comm_result, dxl_error = packetHandler.write1ByteTxRx(portHandler, DXL_ID, ADDR_TORQUE_ENABLE, TORQUE_ENABLE)
121 if dxl_comm_result != COMM_SUCCESS:
122 print(
"%s" % packetHandler.getTxRxResult(dxl_comm_result))
123 print(
"Press any key to terminate...")
127 print(
"%s" % packetHandler.getRxPacketError(dxl_error))
128 print(
"Press any key to terminate...")
132 print(
"DYNAMIXEL has been successfully connected")
134 print(
"Ready to get & set Position.")
139 if __name__ ==
'__main__':