Skip to content

Commit f823a2d

Browse files
Update read_write.py
- position length bug fixed.
1 parent 398f3c9 commit f823a2d

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

python/tests/protocol1_0/read_write.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -116,15 +116,15 @@ def getch():
116116
break
117117

118118
# Write goal position
119-
dxl_comm_result, dxl_error = packetHandler.write4ByteTxRx(portHandler, DXL_ID, ADDR_MX_GOAL_POSITION, dxl_goal_position[index])
119+
dxl_comm_result, dxl_error = packetHandler.write2ByteTxRx(portHandler, DXL_ID, ADDR_MX_GOAL_POSITION, dxl_goal_position[index])
120120
if dxl_comm_result != COMM_SUCCESS:
121121
print("%s" % packetHandler.getTxRxResult(dxl_comm_result))
122122
elif dxl_error != 0:
123123
print("%s" % packetHandler.getRxPacketError(dxl_error))
124124

125125
while 1:
126126
# Read present position
127-
dxl_present_position, dxl_comm_result, dxl_error = packetHandler.read4ByteTxRx(portHandler, DXL_ID, ADDR_MX_PRESENT_POSITION)
127+
dxl_present_position, dxl_comm_result, dxl_error = packetHandler.read2ByteTxRx(portHandler, DXL_ID, ADDR_MX_PRESENT_POSITION)
128128
if dxl_comm_result != COMM_SUCCESS:
129129
print("%s" % packetHandler.getTxRxResult(dxl_comm_result))
130130
elif dxl_error != 0:

0 commit comments

Comments
 (0)