线条厂各设备控制代码

This commit is contained in:
2026-01-05 18:11:56 +08:00
commit a6e9d0d734
23 changed files with 4289 additions and 0 deletions

View File

@ -0,0 +1,3 @@
from .hx_30_hm import *
from .port_handler import *
from .protocol_paket_handler import *

187
servo/servo_sdk/hx_30_hm.py Normal file
View File

@ -0,0 +1,187 @@
from .protocol_paket_handler import *
#baudrate define
HX_30HM_1M = 0
HX_30HM_0_5M = 1
HX_30HM_250K = 2
HX_30HM_128K = 3
HX_30HM_115200 = 4
HX_30HM_76800 = 5
HX_30HM_57600 = 6
HX_30HM_38400 = 7
#Memory table
#NVS
HX_30HM_SERVO_MAIN_VERSION = 3
HX_30HM_SERVO_SEC_VERSION = 4
HX_30HM_ID = 5
HX_30HM_BAUD_RATE = 6
HX_30HM_CW_DEAD = 26
HX_30HM_CCW_DEAD = 27
HX_30HM_POS_OFFSET_L = 31
HX_30HM_POS_OFFSET_H = 32
HX_30HM_MODE = 33
#SRAM
#Write read
HX_30HM_TORQUE_ENABLE = 40
HX_30HM_ACC = 41
HX_30HM_GOAL_POSITION_L = 42
HX_30HM_GOAL_POSITION_H = 43
HX_30HM_PWM_SPEED_L = 44
HX_30HM_PWM_SPEED_H = 45
HX_30HM_GOAL_SPEED_L = 46
HX_30HM_GOAL_SPEED_H = 47
HX_30HM_MAX_TORQUE_L = 48
HX_30HM_MAX_TORQUE_H = 49
#Only read
HX_30HM_PRESENT_POSITION_L = 56
HX_30HM_PRESENT_POSITION_H = 57
HX_30HM_PRESENT_SPEED_L = 58
HX_30HM_PRESENT_SPEED_H = 59
HX_30HM_PRESENT_LOAD_L = 60
HX_30HM_PRESENT_LOAD_H = 61
HX_30HM_PRESENT_VOLTAGE = 62
HX_30HM_PRESENT_TEMPERATURE = 63
HX_30HM_MOVING_STATUS = 66
HX_30HM_PRESENT_CURRENT_L = 69
HX_30HM_PRESENT_CURRENT_H = 70
class HxServoHandler(PacketHandler):
def __init__(self, PortHandler):
PacketHandler.__init__(self, PortHandler, 0)
self.GroupSyncWrite = GroupSyncWrite(self, HX_30HM_ACC, 7)
def selectMode(self, id, mode):
_mode = [max(0, min(mode, 3))]
return self.writeReadData(id, HX_30HM_MODE, 1, _mode)
def torqueEnable(self, id):
state = [1]
return self.writeReadData(id, HX_30HM_TORQUE_ENABLE, 1, state)
def torqueDisable(self, id):
state = [0]
return self.writeReadData(id, HX_30HM_TORQUE_ENABLE, 1, state)
def writeCurPosOffset(self, id):
state = [128]
return self.writeReadData(id, HX_30HM_TORQUE_ENABLE, 1, state)
def writePosOffset(self, id, offset):
_offset = max(-2047, min(offset, 2047))
_offset = self.toServo(_offset, 11)
txpacket = [self.getLowByte(_offset), self.getHighByte(_offset)]
return self.writeReadData(id, HX_30HM_POS_OFFSET_L, len(txpacket), txpacket)
def writeAcc(self, id, acc):
_acc = [max(0, min(acc, 254))]
return self.writeReadData(id, HX_30HM_ACC, 1, _acc)
def writeSpeed(self, id, speed):
_speed = max(0, min(speed, 3400))
txpacket = [self.getLowByte(_speed), self.getHighByte(_speed)]
return self.writeReadData(id, HX_30HM_GOAL_SPEED_L, len(txpacket), txpacket)
def writePos(self, id, pos):
_pos = max(-30719, min(pos, 30719))
_pos = self.toServo(_pos, 15)
txpacket = [self.getLowByte(_pos), self.getHighByte(_pos)]
return self.writeReadData(id, HX_30HM_GOAL_POSITION_L, len(txpacket), txpacket)
def writePosEx(self, id, pos, speed, acc):
_pos = max(-30719, min(pos, 30719))
_speed = max(0, min(speed, 3400))
_acc = max(0, min(acc, 254))
_pos = self.toServo(_pos, 15)
txpacket = [_acc,
self.getLowByte(_pos), self.getHighByte(_pos),
0,0,
self.getLowByte(_speed), self.getHighByte(_speed)]
return self.writeReadData(id, HX_30HM_ACC, len(txpacket), txpacket)
def writePwmSpeed(self, id, speed):
_speed = max(-1000, min(speed, 1000))
_speed = self.toServo(_speed, 10)
txpacket = [self.getLowByte(_speed), self.getHighByte(_speed)]
return self.writeReadData(id, HX_30HM_PWM_SPEED_L, len(txpacket), txpacket)
def writeMaxTorque(self, id, max_torque):
_max_torque = max(0, min(max_torque, 1000))
print(_max_torque)
txpacket = [self.getLowByte(_max_torque), self.getHighByte(_max_torque)]
return self.writeReadData(id, HX_30HM_MAX_TORQUE_L, len(txpacket), txpacket)
def writeRegPosEx(self, id, pos, speed, acc):
_pos = max(-30719, min(pos, 30719))
_speed = max(0, min(speed, 3400))
_acc = max(0, min(acc, 254))
_pos = self.toHost(_pos, 15)
txpacket = [_acc,
self.getLowByte(_pos), self.getHighByte(_pos),
0,0,
self.getLowByte(_speed), self.getHighByte(_speed)]
return self.regWriteTxRx(id, HX_30HM_ACC, len(txpacket), txpacket)
def regAction(self):
return self.action(BROADCAST_ID)
def syncWritePosEx(self, id, pos, speed, acc):
_pos = max(-30719, min(pos, 30719))
_speed = max(0, min(speed, 3400))
_acc = max(0, min(acc, 254))
txpacket = [_acc,
self.getLowByte(_pos), self.getHighByte(_pos),
0,0,
self.getLowByte(_speed), self.getHighByte(_speed)]
return self.GroupSyncWrite.addParam(id, txpacket)
def readPosOffset(self, id):
offset, result, error = self.read2ByteData(id, HX_30HM_POS_OFFSET_L)
# The representation of negative numbers
return -(~(offset - 1) & 0xFFFF) if offset > 2047 else offset, result, error
def readPos(self, id):
present_position, result, error = self.read2ByteData(id, HX_30HM_PRESENT_POSITION_L)
return self.toHost(present_position, 15), result, error
def readSpeed(self, id):
present_speed, result, error = self.read2ByteData(id, HX_30HM_PRESENT_SPEED_L)
return self.toHost(present_speed, 15), result, error
def readPosSpeed(self, id):
present_position_speed, result, error = self.read4ByteData(id, HX_30HM_PRESENT_POSITION_L)
present_position = self.getLowWord32(present_position_speed)
present_speed = self.get_Highword32(present_position_speed)
return self.toHost(present_position, 15), self.toHost(present_speed, 15), result, error
def readTemperature(self, id):
present_temp, result, error = self.read1ByteData(id, HX_30HM_PRESENT_TEMPERATURE)
return present_temp, result, error
def readVoltage(self, id):
present_vol, result, error = self.read1ByteData(id, HX_30HM_PRESENT_VOLTAGE)
return present_vol, result, error
def readCurrent(self, id):
present_cur, result, error = self.read2ByteData(id, HX_30HM_PRESENT_CURRENT_L)
return present_cur, result, error
def readLoad(self, id):
load, result, error = self.read2ByteData(id, HX_30HM_PRESENT_LOAD_L)
return self.toHost(load, 10), result, error
def readMoving(self, id):
moving, result, error = self.read1ByteData(id, HX_30HM_MOVING_STATUS)
return moving, result, error

View File

@ -0,0 +1,113 @@
import time
import serial
import sys
import platform
DEFAULT_BAUDRATE = 1000000
LATENCY_TIMER = 50
class PortHandler(object):
def __init__(self, port_name):
self.is_open = False
self.baudrate = DEFAULT_BAUDRATE
self.packet_start_time = 0.0
self.packet_timeout = 0.0
self.tx_time_per_byte = 0.0
self.is_using = False
self.port_name = port_name
self.ser = None
def openPort(self):
return self.setBaudRate(self.baudrate)
def closePort(self):
self.ser.close()
self.is_open = False
def clearPort(self):
self.ser.flush()
def setPortName(self, port_name):
self.port_name = port_name
def getPortName(self):
return self.port_name
def setBaudRate(self, baudrate):
baud = self.getCFlagBaud(baudrate)
if baud <= 0:
# self.setupPort(38400)
# self.baudrate = baudrate
return False # TODO: setCustomBaudrate(baudrate)
else:
self.baudrate = baudrate
return self.setupPort(baud)
def getBaudRate(self):
return self.baudrate
def getBytesAvailable(self):
return self.ser.in_waiting
def readPort(self, length):
if (sys.version_info > (3, 0)):
return self.ser.read(length)
else:
return [ord(ch) for ch in self.ser.read(length)]
def writePort(self, packet):
return self.ser.write(packet)
def setPacketTimeout(self, packet_length):
self.packet_start_time = self.getCurrentTime()
self.packet_timeout = (self.tx_time_per_byte * packet_length) + (self.tx_time_per_byte * 3.0) + LATENCY_TIMER
def setPacketTimeoutMillis(self, msec):
self.packet_start_time = self.getCurrentTime()
self.packet_timeout = msec
def isPacketTimeout(self):
if self.getTimeSinceStart() > self.packet_timeout:
self.packet_timeout = 0
return True
return False
def getCurrentTime(self):
return round(time.time() * 1000000000) / 1000000.0
def getTimeSinceStart(self):
time_since = self.getCurrentTime() - self.packet_start_time
if time_since < 0.0:
self.packet_start_time = self.getCurrentTime()
return time_since
def setupPort(self, cflag_baud):
if self.is_open:
self.closePort()
self.ser = serial.Serial(
port=self.port_name,
baudrate=self.baudrate,
# parity = serial.PARITY_ODD,
# stopbits = serial.STOPBITS_TWO,
bytesize=serial.EIGHTBITS,
timeout=0
)
self.is_open = True
self.ser.reset_input_buffer()
self.tx_time_per_byte = (1000.0 / self.baudrate) * 10.0
return True
def getCFlagBaud(self, baudrate):
if baudrate in [4800, 9600, 14400, 19200, 38400, 57600, 115200, 128000, 250000, 500000, 1000000]:
return baudrate
else:
return -1

View File

@ -0,0 +1,713 @@
TXPACKET_MAX_LEN = 250
RXPACKET_MAX_LEN = 250
# for Protocol Packet
PKT_HEADER0 = 0
PKT_HEADER1 = 1
PKT_ID = 2
PKT_LENGTH = 3
PKT_INSTRUCTION = 4
PKT_ERROR = 4
PKT_PARAMETER0 = 5
# Protocol Error bit
ERRBIT_VOLTAGE = 1 #0x01
ERRBIT_SENSOR = 2 #0x02
ERRBIT_OVERHEAT = 4 #0x04
ERRBIT_CURRENT = 8 #0x08
ERRBIT_ANGLE = 16 #0x10
ERRBIT_OVERLOAD = 32 #0x20
BROADCAST_ID = 254 #0xFE
# Instruction for Servo Protocol
INST_PING = 1 #0x01
INST_READ = 2 #0x02
INST_WRITE = 3 #0x03
INST_REG_WRITE = 4 #0x04
INST_ACTION = 5 #0x05
INST_RESET = 6 #0x06
INST_SYNC_READ = 130 #0x82
INST_SYNC_WRITE = 131 #0x83
# Communication Result
COMM_SUCCESS = 0 # tx or rx packet communication success
COMM_PORT_BUSY = -1 # Port is busy (in use)
COMM_TX_FAIL = -2 # Failed transmit instruction packet
COMM_RX_FAIL = -3 # Failed get status packet
COMM_TX_ERROR = -4 # Incorrect instruction packet
COMM_RX_WAITING = -5 # Now receiving status packet
COMM_RX_TIMEOUT = -6 # There is no status packet
COMM_RX_CORRUPT = -7 # Incorrect status packet
COMM_NOT_AVAILABLE = -9 #Protocol does not support this function
class PacketHandler(object):
def __init__(self, PortHandler, endianness):
self.PortHandler = PortHandler
self.endianness = endianness # 0: little-endian 1:big-endian
def getEndian(self):
return self.endianness
def setEndian(self, e):
self.endianness = e
def toHost(self, a, b):
if (a & (1 << b)):
return -(a & ~(1 << b))
else:
return a
def toServo(self, a, b):
if (a < 0):
return (-a | (1 << b))
else:
return a
def makeWord16(self, a, b):
if self.endianness == 0:
return (a & 0xFF) | ((b & 0xFF) << 8)
else:
return (b & 0xFF) | ((a & 0xFF) << 8)
def makeWord32(self, a, b):
return (a & 0xFFFF) | (b & 0xFFFF) << 16
def getLowWord32(self, l):
return l & 0xFFFF
def get_Highword32(self, h):
return (h >> 16) & 0xFFFF
def getLowByte(self, w):
if self.endianness == 0:
return w & 0xFF
else:
return (w >> 8) & 0xFF
def getHighByte(self, w):
if self.endianness == 0:
return (w >> 8) & 0xFF
else:
return w & 0xFF
def getTxRxResult(self, result):
if result == COMM_SUCCESS:
return "[TxRxResult] Communication success!"
elif result == COMM_PORT_BUSY:
return "[TxRxResult] Port is in use!"
elif result == COMM_TX_FAIL:
return "[TxRxResult] Failed transmit instruction packet!"
elif result == COMM_RX_FAIL:
return "[TxRxResult] Failed get status packet from device!"
elif result == COMM_TX_ERROR:
return "[TxRxResult] Incorrect instruction packet!"
elif result == COMM_RX_WAITING:
return "[TxRxResult] Now receiving status packet!"
elif result == COMM_RX_TIMEOUT:
return "[TxRxResult] There is no status packet!"
elif result == COMM_RX_CORRUPT:
return "[TxRxResult] Incorrect status packet!"
elif result == COMM_NOT_AVAILABLE:
return "[TxRxResult] Protocol does not support this function!"
else:
return ""
def getRxPacketError(self, error):
if error & ERRBIT_VOLTAGE:
return "[ServoStatus] Input voltage error!"
if error & ERRBIT_SENSOR:
return "[ServoStatus] Sensor error!"
if error & ERRBIT_OVERHEAT:
return "[ServoStatus] Overheat error!"
if error & ERRBIT_CURRENT:
return "[ServoStatus] Current error!"
if error & ERRBIT_ANGLE:
return "[ServoStatus] Angle error!"
if error & ERRBIT_OVERLOAD:
return "[ServoStatus] Overload error!"
return ""
def txPacket(self, txpacket):
checksum = 0
total_packet_length = txpacket[PKT_LENGTH] + 4 # 4: HEADER0 HEADER1 ID LENGTH
if self.PortHandler.is_using:
return COMM_PORT_BUSY
self.PortHandler.is_using = True
# check max packet length
if total_packet_length > TXPACKET_MAX_LEN:
self.PortHandler.is_using = False
return COMM_TX_ERROR
# make packet header
txpacket[PKT_HEADER0] = 0xFF
txpacket[PKT_HEADER1] = 0xFF
# add a checksum to the packet
for index in range(2, total_packet_length - 1): # except header, checksum
checksum += txpacket[index]
txpacket[total_packet_length - 1] = ~checksum & 0xFF
# tx packet
self.PortHandler.clearPort()
written_packet_length = self.PortHandler.writePort(txpacket)
if total_packet_length != written_packet_length:
self.PortHandler.is_using = False
return COMM_TX_FAIL
return COMM_SUCCESS
def rxPacket(self):
rxpacket = []
result = COMM_TX_FAIL
checksum = 0
rx_length = 0
wait_length = 6 # minimum length (HEADER0 HEADER1 ID LENGTH ERROR CHKSUM)
while True:
rxpacket.extend(self.PortHandler.readPort(wait_length - rx_length))
rx_length = len(rxpacket)
if rx_length >= wait_length:
# find packet header
index = 0
for index in range(0, (rx_length - 1)):
if (rxpacket[index] == 0xFF) and (rxpacket[index + 1] == 0xFF):
break
if index == 0: # found at the beginning of the packet
if (rxpacket[PKT_ID] > 0xFD) or (rxpacket[PKT_LENGTH] > RXPACKET_MAX_LEN) or (
rxpacket[PKT_ERROR] > 0x7F):
# unavailable ID or unavailable Length or unavailable Error
# remove the first byte in the packet
del rxpacket[0]
rx_length -= 1
continue
# re-calculate the exact length of the rx packet
if wait_length != (rxpacket[PKT_LENGTH] + PKT_LENGTH + 1):
wait_length = rxpacket[PKT_LENGTH] + PKT_LENGTH + 1
continue
if rx_length < wait_length:
# check timeout
if self.PortHandler.isPacketTimeout():
if rx_length == 0:
result = COMM_RX_TIMEOUT
else:
result = COMM_RX_CORRUPT
break
else:
continue
# calculate checksum
for i in range(2, wait_length - 1): # except header, checksum
checksum += rxpacket[i]
checksum = ~checksum & 0xFF
# verify checksum
if rxpacket[wait_length - 1] == checksum:
result = COMM_SUCCESS
else:
result = COMM_RX_CORRUPT
break
else:
# remove unnecessary packets
del rxpacket[0: index]
rx_length -= index
else:
# check timeout
if self.PortHandler.isPacketTimeout():
if rx_length == 0:
result = COMM_RX_TIMEOUT
else:
result = COMM_RX_CORRUPT
break
self.PortHandler.is_using = False
return rxpacket, result
def txRxPacket(self, txpacket):
rxpacket = None
error = 0
# tx packet
result = self.txPacket(txpacket)
if result != COMM_SUCCESS:
return rxpacket, result, error
# (ID == Broadcast ID) == no need to wait for status packet or not available
if txpacket[PKT_ID] == BROADCAST_ID:
self.PortHandler.is_using = False
return rxpacket, result, error
# set packet timeout
if txpacket[PKT_INSTRUCTION] == INST_READ:
self.PortHandler.setPacketTimeout(txpacket[PKT_PARAMETER0 + 1] + 6)
else:
self.PortHandler.setPacketTimeout(6) # HEADER0 HEADER1 ID LENGTH ERROR CHECKSUM
# rx packet
while True:
rxpacket, result = self.rxPacket()
if result != COMM_SUCCESS or txpacket[PKT_ID] == rxpacket[PKT_ID]:
break
if result == COMM_SUCCESS and txpacket[PKT_ID] == rxpacket[PKT_ID]:
error = rxpacket[PKT_ERROR]
return rxpacket, result, error
def ping(self, id):
error = 0
txpacket = [0] * 6
if id > BROADCAST_ID:
return COMM_NOT_AVAILABLE, error
txpacket[PKT_ID] = id
txpacket[PKT_LENGTH] = 2
txpacket[PKT_INSTRUCTION] = INST_PING
rxpacket, result, error = self.txRxPacket(txpacket)
return rxpacket, result, error
def action(self, id):
txpacket = [0] * 6
txpacket[PKT_ID] = id
txpacket[PKT_LENGTH] = 2
txpacket[PKT_INSTRUCTION] = INST_ACTION
_, result, _ = self.txRxPacket(txpacket)
return result
def readData(self, id, address, length):
txpacket = [0] * 8
data = []
if id > BROADCAST_ID:
return data, COMM_NOT_AVAILABLE, 0
txpacket[PKT_ID] = id
txpacket[PKT_LENGTH] = 4
txpacket[PKT_INSTRUCTION] = INST_READ
txpacket[PKT_PARAMETER0 + 0] = address
txpacket[PKT_PARAMETER0 + 1] = length
rxpacket, result, error = self.txRxPacket(txpacket)
if result == COMM_SUCCESS:
error = rxpacket[PKT_ERROR]
data.extend(rxpacket[PKT_PARAMETER0: PKT_PARAMETER0 + length])
return data, result, error
def read1ByteData(self, id, address):
data, result, error = self.readData(id, address, 1)
data_read = data[0] if (result == COMM_SUCCESS) else 0
return data_read, result, error
def read2ByteData(self, id, address):
data, result, error = self.readData(id, address, 2)
data_read = self.makeWord16(data[0], data[1]) if (result == COMM_SUCCESS) else 0
return data_read, result, error
def read4ByteData(self, id, address):
data, result, error = self.readData(id, address, 4)
data_read = self.makeWord32(self.makeWord16(data[0], data[1]),
self.makeWord16(data[2], data[3])) if (result == COMM_SUCCESS) else 0
return data_read, result, error
def writeDataOnly(self, id, address, length, data):
txpacket = [0] * (length + 7)
txpacket[PKT_ID] = id
txpacket[PKT_LENGTH] = length + 3
txpacket[PKT_INSTRUCTION] = INST_WRITE
txpacket[PKT_PARAMETER0] = address
txpacket[PKT_PARAMETER0 + 1: PKT_PARAMETER0 + 1 + length] = data[0: length]
result = self.txPacket(txpacket)
self.PortHandler.is_using = False
return result
def writeReadData(self, id, address, length, data):
txpacket = [0] * (length + 7)
txpacket[PKT_ID] = id
txpacket[PKT_LENGTH] = length + 3
txpacket[PKT_INSTRUCTION] = INST_WRITE
txpacket[PKT_PARAMETER0] = address
txpacket[PKT_PARAMETER0 + 1: PKT_PARAMETER0 + 1 + length] = data[0: length]
rxpacket, result, error = self.txRxPacket(txpacket)
return result, error
def write1ByteDataOnly(self, id, address, data):
data_write = [data]
return self.writeDataOnly(id, address, 1, data_write)
def writeRead1ByteData(self, id, address, data):
data_write = [data]
return self.writeReadData(id, address, 1, data_write)
def write2ByteDataOnly(self, id, address, data):
data_write = [self.getLowByte(data), self.getHighByte(data)]
return self.writeDataOnly(id, address, 2, data_write)
def writeRead2ByteData(self, id, address, data):
data_write = [self.getLowByte(data), self.getHighByte(data)]
return self.writeReadData(id, address, 2, data_write)
def write4ByteDataOnly(self, id, address, data):
data_write = [self.getLowByte(self.getLowWord32(data)),
self.getHighByte(self.getLowWord32(data)),
self.getLowByte(self.get_Highword32(data)),
self.getHighByte(self.get_Highword32(data))]
return self.writeDataOnly(id, address, 4, data_write)
def writeRead4ByteData(self, id, address, data):
data_write = [self.getLowByte(self.getLowWord32(data)),
self.getHighByte(self.getLowWord32(data)),
self.getLowByte(self.get_Highword32(data)),
self.getHighByte(self.get_Highword32(data))]
return self.writeReadData(id, address, 4, data_write)
def regWriteTxOnly(self, id, address, length, data):
txpacket = [0] * (length + 7)
txpacket[PKT_ID] = id
txpacket[PKT_LENGTH] = length + 3
txpacket[PKT_INSTRUCTION] = INST_REG_WRITE
txpacket[PKT_PARAMETER0] = address
txpacket[PKT_PARAMETER0 + 1: PKT_PARAMETER0 + 1 + length] = data[0: length]
result = self.txPacket(txpacket)
self.PortHandler.is_using = False
return result
def regWriteTxRx(self, id, address, length, data):
txpacket = [0] * (length + 7)
txpacket[PKT_ID] = id
txpacket[PKT_LENGTH] = length + 3
txpacket[PKT_INSTRUCTION] = INST_REG_WRITE
txpacket[PKT_PARAMETER0] = address
txpacket[PKT_PARAMETER0 + 1: PKT_PARAMETER0 + 1 + length] = data[0: length]
_, result, error = self.txRxPacket(txpacket)
return result, error
def syncReadTx(self, start_address, data_length, param, param_length):
txpacket = [0] * (param_length + 8)
# 8: HEADER0 HEADER1 ID LEN INST START_ADDR DATA_LEN CHKSUM
txpacket[PKT_ID] = BROADCAST_ID
txpacket[PKT_LENGTH] = param_length + 4 # 7: INST START_ADDR DATA_LEN CHKSUM
txpacket[PKT_INSTRUCTION] = INST_SYNC_READ
txpacket[PKT_PARAMETER0 + 0] = start_address
txpacket[PKT_PARAMETER0 + 1] = data_length
txpacket[PKT_PARAMETER0 + 2: PKT_PARAMETER0 + 2 + param_length] = param[0: param_length]
result = self.txPacket(txpacket)
return result
def syncReadRx(self, data_length, param_length):
wait_length = (6 + data_length) * param_length
self.PortHandler.setPacketTimeout(wait_length)
rxpacket = []
rx_length = 0
while True:
rxpacket.extend(self.PortHandler.readPort(wait_length - rx_length))
rx_length = len(rxpacket)
if rx_length >= wait_length:
result = COMM_SUCCESS
break
else:
# check timeout
if self.PortHandler.isPacketTimeout():
if rx_length == 0:
result = COMM_RX_TIMEOUT
else:
result = COMM_RX_CORRUPT
break
self.PortHandler.is_using = False
return result, rxpacket
def syncWriteTxOnly(self, start_address, data_length, param, param_length):
txpacket = [0] * (param_length + 8)
# 8: HEADER0 HEADER1 ID LEN INST START_ADDR DATA_LEN ... CHKSUM
txpacket[PKT_ID] = BROADCAST_ID
txpacket[PKT_LENGTH] = param_length + 4 # 4: INST START_ADDR DATA_LEN ... CHKSUM
txpacket[PKT_INSTRUCTION] = INST_SYNC_WRITE
txpacket[PKT_PARAMETER0 + 0] = start_address
txpacket[PKT_PARAMETER0 + 1] = data_length
txpacket[PKT_PARAMETER0 + 2: PKT_PARAMETER0 + 2 + param_length] = param[0: param_length]
_, result, _ = self.txRxPacket(txpacket)
return result
def reset(self, id):
error = 0
txpacket = [0] * 6
if id > BROADCAST_ID:
return COMM_NOT_AVAILABLE, error
txpacket[PKT_ID] = id
txpacket[PKT_LENGTH] = 2
txpacket[PKT_INSTRUCTION] = INST_RESET
rxpacket, result, error = self.txRxPacket(txpacket)
return result, error
class GroupSyncRead:
def __init__(self, handler, start_address, data_length):
self.handler = handler
self.start_address = start_address
self.data_length = data_length
self.last_result = False
self.is_param_changed = False
self.param = []
self.data_dict = {}
self.clearParam()
def makeParam(self):
if not self.data_dict: # len(self.data_dict.keys()) == 0:
return
self.param = []
for scs_id in self.data_dict:
self.param.append(scs_id)
def addParam(self, id):
if id in self.data_dict: # scs_id already exist
return False
self.data_dict[id] = [] # [0] * self.data_length
self.is_param_changed = True
return True
def removeParam(self, id):
if id not in self.data_dict: # NOT exist
return
del self.data_dict[id]
self.is_param_changed = True
def clearParam(self):
self.data_dict.clear()
def txPacket(self):
if len(self.data_dict.keys()) == 0:
return COMM_NOT_AVAILABLE
if self.is_param_changed is True or not self.param:
self.makeParam()
return self.handler.syncReadTx(self.start_address,
self.data_length,
self.param,
len(self.data_dict.keys()))
def rxPacket(self):
self.last_result = True
result = COMM_RX_FAIL
if len(self.data_dict.keys()) == 0:
return COMM_NOT_AVAILABLE
result, rxpacket = self.handler.syncReadRx(self.data_length, len(self.data_dict.keys()))
if len(rxpacket) >= (self.data_length + 6):
for id in self.data_dict:
self.data_dict[id], result = self.readRx(rxpacket, id, self.data_length)
if result != COMM_SUCCESS:
self.last_result = False
else:
self.last_result = False
return result
def txRxPacket(self):
result = self.txPacket()
if result != COMM_SUCCESS:
return result
return self.rxPacket()
def readRx(self, rxpacket, id, data_length):
data = []
rx_length = len(rxpacket)
rx_index = 0
while (rx_index + 6 + data_length) <= rx_length:
headpacket = [0x00, 0x00, 0x00]
while rx_index < rx_length:
headpacket[2] = headpacket[1]
headpacket[1] = headpacket[0]
headpacket[0] = rxpacket[rx_index]
rx_index += 1
if (headpacket[2] == 0xFF) and (headpacket[1] == 0xFF) and headpacket[0] == id:
break
if (rx_index+3+data_length) > rx_length:
break
if rxpacket[rx_index] != (data_length+2):
rx_index += 1
continue
rx_index += 1
Error = rxpacket[rx_index]
rx_index += 1
calSum = id + (data_length+2) + Error
data = [Error]
data.extend(rxpacket[rx_index : rx_index+data_length])
for i in range(0, data_length):
calSum += rxpacket[rx_index]
rx_index += 1
calSum = ~calSum & 0xFF
if calSum != rxpacket[rx_index]:
return None, COMM_RX_CORRUPT
return data, COMM_SUCCESS
return None, COMM_RX_CORRUPT
def isAvailable(self, id, address, data_length):
#if self.last_result is False or scs_id not in self.data_dict:
if id not in self.data_dict:
return False, 0
if (address < self.start_address) or (self.start_address + self.data_length - data_length < address):
return False, 0
if not self.data_dict[id]:
return False, 0
if len(self.data_dict[id])<(data_length+1):
return False, 0
return True, self.data_dict[id][0]
def getData(self, id, address, data_length):
if data_length == 1:
return self.data_dict[id][address-self.start_address+1]
elif data_length == 2:
return self.handler.makeWord16(self.data_dict[id][address-self.start_address+1],
self.data_dict[id][address-self.start_address+2])
elif data_length == 4:
return self.handler.makeWord32(self.handler.makeWord16(self.data_dict[id][address-self.start_address+1],
self.data_dict[id][address-self.start_address+2]),
self.handler.makeWord16(self.data_dict[id][address-self.start_address+3],
self.data_dict[id][address-self.start_address+4]))
else:
return 0
class GroupSyncWrite:
def __init__(self, handler, start_address, data_length):
self.handler = handler
self.start_address = start_address
self.data_length = data_length
self.is_param_changed = False
self.param = []
self.data_dict = {}
self.clearParam()
def makeParam(self):
if not self.data_dict:
return
self.param = []
for id in self.data_dict:
if not self.data_dict[id]:
return
self.param.append(id)
self.param.extend(self.data_dict[id])
def addParam(self, id, data):
if id in self.data_dict: # id already exist
return False
if len(data) > self.data_length: # input data is longer than set
return False
self.data_dict[id] = data
self.is_param_changed = True
return True
def removeParam(self, id):
if id not in self.data_dict: # NOT exist
return
del self.data_dict[id]
self.is_param_changed = True
def changeParam(self, id, data):
if id not in self.data_dict: # NOT exist
return False
if len(data) > self.data_length: # input data is longer than set
return False
self.data_dict[id] = data
self.is_param_changed = True
return True
def clearParam(self):
self.data_dict.clear()
def txPacket(self):
if len(self.data_dict.keys()) == 0:
return COMM_NOT_AVAILABLE
if self.is_param_changed is True or not self.param:
self.makeParam()
# print(self.data_dict)
return self.handler.syncWriteTxOnly(self.start_address, self.data_length, self.param,
len(self.data_dict.keys()) * (1 + self.data_length))