mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tools: pre-commit: small py3 compliance
This commit is contained in:
parent
1c1fa820b4
commit
d36a028420
@ -17,12 +17,9 @@ import subprocess
|
|||||||
|
|
||||||
class AP_PreCommit(object):
|
class AP_PreCommit(object):
|
||||||
|
|
||||||
def __init__(self):
|
|
||||||
pass
|
|
||||||
|
|
||||||
@staticmethod
|
@staticmethod
|
||||||
def progress(message):
|
def progress(message):
|
||||||
print("***** %s" % (message, ))
|
print(f"***** {message}")
|
||||||
|
|
||||||
@staticmethod
|
@staticmethod
|
||||||
def has_flake8_tag(filepath):
|
def has_flake8_tag(filepath):
|
||||||
@ -36,7 +33,7 @@ class AP_PreCommit(object):
|
|||||||
try:
|
try:
|
||||||
subprocess.check_output(["flake8"] + files_to_check, stderr=subprocess.STDOUT)
|
subprocess.check_output(["flake8"] + files_to_check, stderr=subprocess.STDOUT)
|
||||||
except subprocess.CalledProcessError as e:
|
except subprocess.CalledProcessError as e:
|
||||||
self.progress("Flake8 check failed: (%s)" % (e.output))
|
self.progress(f"Flake8 check failed: ({e.output})")
|
||||||
return False
|
return False
|
||||||
return True
|
return True
|
||||||
|
|
||||||
@ -44,7 +41,7 @@ class AP_PreCommit(object):
|
|||||||
def split_git_diff_output(output):
|
def split_git_diff_output(output):
|
||||||
'''split output from git-diff into a list of (status, filepath) tuples'''
|
'''split output from git-diff into a list of (status, filepath) tuples'''
|
||||||
ret = []
|
ret = []
|
||||||
if type(output) is bytes:
|
if isinstance(output, bytes):
|
||||||
output = output.decode('utf-8')
|
output = output.decode('utf-8')
|
||||||
for line in output.split("\n"):
|
for line in output.split("\n"):
|
||||||
if len(line) == 0:
|
if len(line) == 0:
|
||||||
@ -72,7 +69,7 @@ class AP_PreCommit(object):
|
|||||||
# rename, check destination
|
# rename, check destination
|
||||||
(status, filepath) = (output_tuple[0], output_tuple[2])
|
(status, filepath) = (output_tuple[0], output_tuple[2])
|
||||||
else:
|
else:
|
||||||
raise ValueError("Unknown status %s" % str(output_tuple[0]))
|
raise ValueError(f"Unknown status {output_tuple[0]}")
|
||||||
else:
|
else:
|
||||||
(status, filepath) = output_tuple
|
(status, filepath) = output_tuple
|
||||||
if filepath in dirty:
|
if filepath in dirty:
|
||||||
|
Loading…
Reference in New Issue
Block a user