port_handler.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 import time
00023 import serial
00024 import sys
00025 import platform
00026 
00027 LATENCY_TIMER = 16
00028 DEFAULT_BAUDRATE = 1000000
00029 
00030 
00031 class PortHandler(object):
00032     def __init__(self, port_name):
00033         self.is_open = False
00034         self.baudrate = DEFAULT_BAUDRATE
00035         self.packet_start_time = 0.0
00036         self.packet_timeout = 0.0
00037         self.tx_time_per_byte = 0.0
00038 
00039         self.is_using = False
00040         self.port_name = port_name
00041         self.ser = None
00042 
00043     def openPort(self):
00044         return self.setBaudRate(self.baudrate)
00045 
00046     def closePort(self):
00047         self.ser.close()
00048         self.is_open = False
00049 
00050     def clearPort(self):
00051         self.ser.flush()
00052 
00053     def setPortName(self, port_name):
00054         self.port_name = port_name
00055 
00056     def getPortName(self):
00057         return self.port_name
00058 
00059     def setBaudRate(self, baudrate):
00060         baud = self.getCFlagBaud(baudrate)
00061 
00062         if baud <= 0:
00063             # self.setupPort(38400)
00064             # self.baudrate = baudrate
00065             return False  # TODO: setCustomBaudrate(baudrate)
00066         else:
00067             self.baudrate = baudrate
00068             return self.setupPort(baud)
00069 
00070     def getBaudRate(self):
00071         return self.baudrate
00072 
00073     def getBytesAvailable(self):
00074         return self.ser.in_waiting
00075 
00076     def readPort(self, length):
00077         if (sys.version_info > (3, 0)):
00078             return self.ser.read(length)
00079         else:
00080             return [ord(ch) for ch in self.ser.read(length)]
00081 
00082     def writePort(self, packet):
00083         return self.ser.write(packet)
00084 
00085     def setPacketTimeout(self, packet_length):
00086         self.packet_start_time = self.getCurrentTime()
00087         self.packet_timeout = (self.tx_time_per_byte * packet_length) + (LATENCY_TIMER * 2.0) + 2.0
00088 
00089     def setPacketTimeoutMillis(self, msec):
00090         self.packet_start_time = self.getCurrentTime()
00091         self.packet_timeout = msec
00092 
00093     def isPacketTimeout(self):
00094         if self.getTimeSinceStart() > self.packet_timeout:
00095             self.packet_timeout = 0
00096             return True
00097 
00098         return False
00099 
00100     def getCurrentTime(self):
00101         return round(time.time() * 1000000000) / 1000000.0
00102 
00103     def getTimeSinceStart(self):
00104         time_since = self.getCurrentTime() - self.packet_start_time
00105         if time_since < 0.0:
00106             self.packet_start_time = self.getCurrentTime()
00107 
00108         return time_since
00109 
00110     def setupPort(self, cflag_baud):
00111         if self.is_open:
00112             self.closePort()
00113 
00114         self.ser = serial.Serial(
00115             port=self.port_name,
00116             baudrate=self.baudrate,
00117             # parity = serial.PARITY_ODD,
00118             # stopbits = serial.STOPBITS_TWO,
00119             bytesize=serial.EIGHTBITS,
00120             timeout=0
00121         )
00122 
00123         self.is_open = True
00124 
00125         self.ser.reset_input_buffer()
00126 
00127         self.tx_time_per_byte = (1000.0 / self.baudrate) * 10.0
00128 
00129         return True
00130 
00131     def getCFlagBaud(self, baudrate):
00132         if platform.system() == 'Darwin':
00133             if baudrate in [9600, 19200, 38400, 57600, 115200]:
00134                 return baudrate
00135             else:
00136                 return -1
00137         else:
00138             if baudrate in [9600, 19200, 38400, 57600, 115200, 230400, 460800, 500000, 576000, 921600, 1000000, 1152000,
00139                             2000000, 2500000, 3000000, 3500000, 4000000]:
00140                 return baudrate
00141             else:
00142                 return -1            


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