group_bulk_write.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 ################################################################################
5 # Copyright 2017 ROBOTIS CO., LTD.
6 #
7 # Licensed under the Apache License, Version 2.0 (the "License");
8 # you may not use this file except in compliance with the License.
9 # You may obtain a copy of the License at
10 #
11 # http://www.apache.org/licenses/LICENSE-2.0
12 #
13 # Unless required by applicable law or agreed to in writing, software
14 # distributed under the License is distributed on an "AS IS" BASIS,
15 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
16 # See the License for the specific language governing permissions and
17 # limitations under the License.
18 ################################################################################
19 
20 # Author: Ryu Woon Jung (Leon)
21 
22 from .robotis_def import *
23 
24 
26  def __init__(self, port, ph):
27  self.port = port
28  self.ph = ph
29 
30  self.is_param_changed = False
31  self.param = []
32  self.data_list = {}
33 
34  self.clearParam()
35 
36  def makeParam(self):
37  if self.ph.getProtocolVersion() == 1.0 or not self.data_list:
38  return
39 
40  self.param = []
41 
42  for dxl_id in self.data_list:
43  if not self.data_list[dxl_id]:
44  return
45 
46  self.param.append(dxl_id)
47  self.param.append(DXL_LOBYTE(self.data_list[dxl_id][1]))
48  self.param.append(DXL_HIBYTE(self.data_list[dxl_id][1]))
49  self.param.append(DXL_LOBYTE(self.data_list[dxl_id][2]))
50  self.param.append(DXL_HIBYTE(self.data_list[dxl_id][2]))
51 
52  self.param.extend(self.data_list[dxl_id][0])
53 
54  def addParam(self, dxl_id, start_address, data_length, data):
55  if self.ph.getProtocolVersion() == 1.0:
56  return False
57 
58  if dxl_id in self.data_list: # dxl_id already exist
59  return False
60 
61  if len(data) > data_length: # input data is longer than set
62  return False
63 
64  self.data_list[dxl_id] = [data, start_address, data_length]
65 
66  self.is_param_changed = True
67  return True
68 
69  def removeParam(self, dxl_id):
70  if self.ph.getProtocolVersion() == 1.0:
71  return
72 
73  if dxl_id not in self.data_list: # NOT exist
74  return
75 
76  del self.data_list[dxl_id]
77 
78  self.is_param_changed = True
79 
80  def changeParam(self, dxl_id, start_address, data_length, data):
81  if self.ph.getProtocolVersion() == 1.0:
82  return False
83 
84  if dxl_id not in self.data_list: # NOT exist
85  return False
86 
87  if len(data) > data_length: # input data is longer than set
88  return False
89 
90  self.data_list[dxl_id] = [data, start_address, data_length]
91 
92  self.is_param_changed = True
93  return True
94 
95  def clearParam(self):
96  if self.ph.getProtocolVersion() == 1.0:
97  return
98 
99  self.data_list.clear()
100  return
101 
102  def txPacket(self):
103  if self.ph.getProtocolVersion() == 1.0 or len(self.data_list.keys()) == 0:
104  return COMM_NOT_AVAILABLE
105 
106  if self.is_param_changed is True or len(self.param) == 0:
107  self.makeParam()
108 
109  return self.ph.bulkWriteTxOnly(self.port, self.param, len(self.param))
def changeParam(self, dxl_id, start_address, data_length, data)
def addParam(self, dxl_id, start_address, data_length, data)
#define DXL_LOBYTE(w)
#define DXL_HIBYTE(w)


dynamixel_sdk
Author(s): Gilbert , Zerom , Darby Lim , Leon
autogenerated on Fri Apr 16 2021 02:25:55