group_sync_write.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 
00004 ################################################################################
00005 # Copyright 2017 ROBOTIS CO., LTD.
00006 #
00007 # Licensed under the Apache License, Version 2.0 (the "License");
00008 # you may not use this file except in compliance with the License.
00009 # You may obtain a copy of the License at
00010 #
00011 #     http://www.apache.org/licenses/LICENSE-2.0
00012 #
00013 # Unless required by applicable law or agreed to in writing, software
00014 # distributed under the License is distributed on an "AS IS" BASIS,
00015 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00016 # See the License for the specific language governing permissions and
00017 # limitations under the License.
00018 ################################################################################
00019 
00020 # Author: Ryu Woon Jung (Leon)
00021 
00022 from .robotis_def import *
00023 
00024 
00025 class GroupSyncWrite:
00026     def __init__(self, port, ph, start_address, data_length):
00027         self.port = port
00028         self.ph = ph
00029         self.start_address = start_address
00030         self.data_length = data_length
00031 
00032         self.is_param_changed = False
00033         self.param = []
00034         self.data_dict = {}
00035 
00036         self.clearParam()
00037 
00038     def makeParam(self):
00039         if not self.data_dict:
00040             return
00041 
00042         self.param = []
00043 
00044         for dxl_id in self.data_dict:
00045             if not self.data_dict[dxl_id]:
00046                 return
00047 
00048             self.param.append(dxl_id)
00049             self.param.extend(self.data_dict[dxl_id])
00050 
00051     def addParam(self, dxl_id, data):
00052         if dxl_id in self.data_dict:  # dxl_id already exist
00053             return False
00054 
00055         if len(data) > self.data_length:  # input data is longer than set
00056             return False
00057 
00058         self.data_dict[dxl_id] = data
00059 
00060         self.is_param_changed = True
00061         return True
00062 
00063     def removeParam(self, dxl_id):
00064         if dxl_id not in self.data_dict:  # NOT exist
00065             return
00066 
00067         del self.data_dict[dxl_id]
00068 
00069         self.is_param_changed = True
00070 
00071     def changeParam(self, dxl_id, data):
00072         if dxl_id not in self.data_dict:  # NOT exist
00073             return False
00074 
00075         if len(data) > self.data_length:  # input data is longer than set
00076             return False
00077 
00078         self.data_dict[dxl_id] = data
00079 
00080         self.is_param_changed = True
00081         return True
00082 
00083     def clearParam(self):
00084         self.data_dict.clear()
00085 
00086     def txPacket(self):
00087         if len(self.data_dict.keys()) == 0:
00088             return COMM_NOT_AVAILABLE
00089 
00090         if self.is_param_changed is True or not self.param:
00091             self.makeParam()
00092 
00093         return self.ph.syncWriteTxOnly(self.port, self.start_address, self.data_length, self.param,
00094                                        len(self.data_dict.keys()) * (1 + self.data_length))


ros
Author(s): Pyo , Zerom , Leon
autogenerated on Sat Jun 8 2019 18:32:11