diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py index e988d3a0..7e6232e8 100644 --- a/lerobot/common/motors/dynamixel/dynamixel.py +++ b/lerobot/common/motors/dynamixel/dynamixel.py @@ -100,14 +100,9 @@ class DynamixelMotorsBus(MotorsBus): # Note: No need to convert back into unsigned int, since this byte preprocessing # already handles it for us. if n_bytes == 1: - data = [ - dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)), - ] + data = [value] elif n_bytes == 2: - data = [ - dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)), - dxl.DXL_HIBYTE(dxl.DXL_LOWORD(value)), - ] + data = [dxl.DXL_LOBYTE(value), dxl.DXL_HIBYTE(value)] elif n_bytes == 4: data = [ dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)), diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py index 3e8eb20a..23ea9884 100644 --- a/lerobot/common/motors/feetech/feetech.py +++ b/lerobot/common/motors/feetech/feetech.py @@ -88,14 +88,9 @@ class FeetechMotorsBus(MotorsBus): # Note: No need to convert back into unsigned int, since this byte preprocessing # already handles it for us. if n_bytes == 1: - data = [ - scs.SCS_LOBYTE(scs.SCS_LOWORD(value)), - ] + data = [value] elif n_bytes == 2: - data = [ - scs.SCS_LOBYTE(scs.SCS_LOWORD(value)), - scs.SCS_HIBYTE(scs.SCS_LOWORD(value)), - ] + data = [scs.SCS_LOBYTE(value), scs.SCS_HIBYTE(value)] elif n_bytes == 4: data = [ scs.SCS_LOBYTE(scs.SCS_LOWORD(value)),