Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022 from .robotis_def import *
00023
00024
00025 class GroupBulkWrite:
00026 def __init__(self, port, ph):
00027 self.port = port
00028 self.ph = ph
00029
00030 self.is_param_changed = False
00031 self.param = []
00032 self.data_list = {}
00033
00034 self.clearParam()
00035
00036 def makeParam(self):
00037 if self.ph.getProtocolVersion() == 1.0 or not self.data_list:
00038 return
00039
00040 self.param = []
00041
00042 for dxl_id in self.data_list:
00043 if not self.data_list[dxl_id]:
00044 return
00045
00046 self.param.append(dxl_id)
00047 self.param.append(DXL_LOBYTE(self.data_list[dxl_id][1]))
00048 self.param.append(DXL_HIBYTE(self.data_list[dxl_id][1]))
00049 self.param.append(DXL_LOBYTE(self.data_list[dxl_id][2]))
00050 self.param.append(DXL_HIBYTE(self.data_list[dxl_id][2]))
00051
00052 self.param.extend(self.data_list[dxl_id][0])
00053
00054 def addParam(self, dxl_id, start_address, data_length, data):
00055 if self.ph.getProtocolVersion() == 1.0:
00056 return False
00057
00058 if dxl_id in self.data_list:
00059 return False
00060
00061 if len(data) > data_length:
00062 return False
00063
00064 self.data_list[dxl_id] = [data, start_address, data_length]
00065
00066 self.is_param_changed = True
00067 return True
00068
00069 def removeParam(self, dxl_id):
00070 if self.ph.getProtocolVersion() == 1.0:
00071 return
00072
00073 if dxl_id not in self.data_list:
00074 return
00075
00076 del self.data_list[dxl_id]
00077
00078 self.is_param_changed = True
00079
00080 def changeParam(self, dxl_id, start_address, data_length, data):
00081 if self.ph.getProtocolVersion() == 1.0:
00082 return False
00083
00084 if dxl_id not in self.data_list:
00085 return False
00086
00087 if len(data) > data_length:
00088 return False
00089
00090 self.data_list[dxl_id] = [data, start_address, data_length]
00091
00092 self.is_param_changed = True
00093 return True
00094
00095 def clearParam(self):
00096 if self.ph.getProtocolVersion() == 1.0:
00097 return
00098
00099 self.data_list.clear()
00100 return
00101
00102 def txPacket(self):
00103 if self.ph.getProtocolVersion() == 1.0 or len(self.data_list.keys()) == 0:
00104 return COMM_NOT_AVAILABLE
00105
00106 if self.is_param_changed is True or len(self.param) == 0:
00107 self.makeParam()
00108
00109 return self.ph.bulkWriteTxOnly(self.port, self.param, len(self.param))