autotest: correct bytes decoding for Python3 in Logger documentation

This commit is contained in:
Peter Barker 2020-03-29 08:25:22 +11:00 committed by Peter Barker
parent b8dba9886f
commit 53ced35f9d

View File

@ -1056,6 +1056,8 @@ class AutoTest(ABC):
def find_format_defines(self, filepath): def find_format_defines(self, filepath):
ret = {} ret = {}
for line in open(filepath,'rb').readlines(): for line in open(filepath,'rb').readlines():
if type(line) == bytes:
line = line.decode("utf-8")
m = re.match('#define (\w+_(?:LABELS|FMT|UNITS|MULTS))\s+(".*")', line) m = re.match('#define (\w+_(?:LABELS|FMT|UNITS|MULTS))\s+(".*")', line)
if m is None: if m is None:
continue continue
@ -1089,6 +1091,8 @@ class AutoTest(ABC):
message_infos = [] message_infos = []
for line in open(filepath,'rb').readlines(): for line in open(filepath,'rb').readlines():
# print("line: %s" % line) # print("line: %s" % line)
if type(line) == bytes:
line = line.decode("utf-8")
line = re.sub("//.*", "", line) # trim comments line = re.sub("//.*", "", line) # trim comments
if re.match("\s*$", line): if re.match("\s*$", line):
# blank line # blank line
@ -1141,6 +1145,8 @@ class AutoTest(ABC):
linestate_within = 90 linestate_within = 90
linestate = linestate_none linestate = linestate_none
for line in open(filepath,'rb').readlines(): for line in open(filepath,'rb').readlines():
if type(line) == bytes:
line = line.decode("utf-8")
line = re.sub("//.*", "", line) # trim comments line = re.sub("//.*", "", line) # trim comments
if re.match("\s*$", line): if re.match("\s*$", line):
# blank line # blank line
@ -1222,6 +1228,8 @@ class AutoTest(ABC):
filepath = os.path.join(root, f) filepath = os.path.join(root, f)
count = 0 count = 0
for line in open(filepath,'rb').readlines(): for line in open(filepath,'rb').readlines():
if type(line) == bytes:
line = line.decode("utf-8")
if state == state_outside: if state == state_outside:
if re.match("\s*AP::logger\(\)[.]Write\(", line): if re.match("\s*AP::logger\(\)[.]Write\(", line):
state = state_inside state = state_inside