22 from .robotis_def
import *
48 if self.ph.getProtocolVersion() == 1.0:
49 self.param.append(self.
data_dict[dxl_id][2])
50 self.param.append(dxl_id)
51 self.param.append(self.
data_dict[dxl_id][1])
53 self.param.append(dxl_id)
59 def addParam(self, dxl_id, start_address, data_length):
64 self.
data_dict[dxl_id] = [data, start_address, data_length]
78 self.data_dict.clear()
82 if len(self.data_dict.keys()) == 0:
83 return COMM_NOT_AVAILABLE
88 if self.ph.getProtocolVersion() == 1.0:
89 return self.ph.bulkReadTx(self.
port, self.
param, len(self.data_dict.keys()) * 3)
91 return self.ph.bulkReadTx(self.
port, self.
param, len(self.data_dict.keys()) * 5)
98 if len(self.data_dict.keys()) == 0:
99 return COMM_NOT_AVAILABLE
102 self.
data_dict[dxl_id][PARAM_NUM_DATA], result, _ = self.ph.readRx(self.
port, dxl_id,
103 self.
data_dict[dxl_id][PARAM_NUM_LENGTH])
104 if result != COMM_SUCCESS:
107 if result == COMM_SUCCESS:
114 if result != COMM_SUCCESS:
123 start_addr = self.
data_dict[dxl_id][PARAM_NUM_ADDRESS]
125 if (address < start_addr)
or (start_addr + self.
data_dict[dxl_id][PARAM_NUM_LENGTH] - data_length < address):
130 def getData(self, dxl_id, address, data_length):
131 if not self.
isAvailable(dxl_id, address, data_length):
134 start_addr = self.
data_dict[dxl_id][PARAM_NUM_ADDRESS]
137 return self.
data_dict[dxl_id][PARAM_NUM_DATA][address - start_addr]
138 elif data_length == 2:
140 self.
data_dict[dxl_id][PARAM_NUM_DATA][address - start_addr + 1])
141 elif data_length == 4:
143 self.
data_dict[dxl_id][PARAM_NUM_DATA][address - start_addr + 1]),
145 self.
data_dict[dxl_id][PARAM_NUM_DATA][address - start_addr + 3]))
#define DXL_MAKEDWORD(a, b)
def isAvailable(self, dxl_id, address, data_length)
#define DXL_MAKEWORD(a, b)
def getData(self, dxl_id, address, data_length)
def addParam(self, dxl_id, start_address, data_length)
def __init__(self, port, ph)
def removeParam(self, dxl_id)