Skip to content

Commit

Permalink
Tools: correct Python cleanliness problems
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker authored and Lokesh-Carbonix committed Oct 3, 2023
1 parent b7935b4 commit e0cd85d
Show file tree
Hide file tree
Showing 10 changed files with 22 additions and 22 deletions.
4 changes: 2 additions & 2 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -3912,7 +3912,7 @@ def fly_guided_move_local(self, x, y, z_up, timeout=100):
MAV_POS_TARGET_TYPE_MASK.POS_ONLY | MAV_POS_TARGET_TYPE_MASK.LAST_BYTE, # mask specifying use-only-x-y-z
x, # x
y, # y
-z_up,# z
-z_up, # z
0, # vx
0, # vy
0, # vz
Expand Down Expand Up @@ -7294,7 +7294,7 @@ def fly_each_frame(self):
# to carry the path to the JSON.
actual_model = model.split(":")[0]
defaults = self.model_defaults_filepath(actual_model)
if type(defaults) != list:
if not isinstance(defaults, list):
defaults = [defaults]
self.customise_SITL_commandline(
["--defaults", ','.join(defaults), ],
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -3203,7 +3203,7 @@ def fly_each_frame(self):
# to carry the path to the JSON.
actual_model = model.split(":")[0]
defaults = self.model_defaults_filepath(actual_model)
if type(defaults) != list:
if not isinstance(defaults, list):
defaults = [defaults]
self.customise_SITL_commandline(
["--defaults", ','.join(defaults), ],
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/autotest.py
Original file line number Diff line number Diff line change
Expand Up @@ -739,7 +739,7 @@ def run_tests(steps):
try:
success = run_step(step)
testinstance = None
if type(success) == tuple:
if isinstance(type, tuple):
(success, testinstance) = success
if success:
results.add(step, '<span class="passed-text">PASSED</span>',
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/bisect-helper.py
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ def run_program(self, prefix, cmd_list):
# select not available on Windows... probably...
time.sleep(0.1)
continue
if type(x) == bytes:
if isinstance(x, bytes):
x = x.decode('utf-8')
self.program_output += x
x = x.rstrip()
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/check_autotest_speedup.py
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ def run_program(self, prefix, cmd_list):
# select not available on Windows... probably...
time.sleep(0.1)
continue
if type(x) == bytes:
if isinstance(x, bytes):
x = x.decode('utf-8')
self.program_output += x
x = x.rstrip()
Expand Down
22 changes: 11 additions & 11 deletions Tools/autotest/common.py
Original file line number Diff line number Diff line change
Expand Up @@ -2068,7 +2068,7 @@ def test_parameter_documentation_get_all_parameters(self):
def find_format_defines(self, lines):
ret = {}
for line in lines:
if type(line) == bytes:
if isinstance(line, bytes):
line = line.decode("utf-8")
m = re.match(r'#define (\w+_(?:LABELS|FMT|UNITS|MULTS))\s+(".*")', line)
if m is None:
Expand Down Expand Up @@ -2118,7 +2118,7 @@ def all_log_format_ids(self):
message_infos = []
for line in structure_lines:
# print("line: %s" % line)
if type(line) == bytes:
if isinstance(line, bytes):
line = line.decode("utf-8")
line = re.sub("//.*", "", line) # trim comments
if re.match(r"\s*$", line):
Expand Down Expand Up @@ -2183,7 +2183,7 @@ def all_log_format_ids(self):
linestate_within = 90
linestate = linestate_none
for line in open(filepath, 'rb').readlines():
if type(line) == bytes:
if isinstance(line, bytes):
line = line.decode("utf-8")
line = re.sub("//.*", "", line) # trim comments
if re.match(r"\s*$", line):
Expand Down Expand Up @@ -2279,7 +2279,7 @@ def all_log_format_ids(self):
continue
count = 0
for line in open(filepath, 'rb').readlines():
if type(line) == bytes:
if isinstance(line, bytes):
line = line.decode("utf-8")
if state == state_outside:
if (re.match(r"\s*AP::logger\(\)[.]Write(?:Streaming)?\(", line) or
Expand Down Expand Up @@ -4640,7 +4640,7 @@ def get_parameter(self, *args, **kwargs):

def send_get_parameter_direct(self, name):
encname = name
if sys.version_info.major >= 3 and type(encname) != bytes:
if sys.version_info.major >= 3 and not isinstance(encname, bytes):
encname = bytes(encname, 'ascii')
self.mav.mav.param_request_read_send(self.sysid_thismav(),
1,
Expand Down Expand Up @@ -4951,7 +4951,7 @@ def verify_parameter_values(self, parameter_stuff, max_delta=0.0):
for param in parameter_stuff:
fetched_value = self.get_parameter(param)
wanted_value = parameter_stuff[param]
if type(wanted_value) == tuple:
if isinstance(wanted_value, tuple):
max_delta = wanted_value[1]
wanted_value = wanted_value[0]
if abs(fetched_value - wanted_value) > max_delta:
Expand Down Expand Up @@ -8379,7 +8379,7 @@ def rate_to_interval_us(self, rate):

def set_message_rate_hz(self, id, rate_hz):
'''set a message rate in Hz; 0 for original, -1 to disable'''
if type(id) == str:
if isinstance(id, str):
id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % id)
if rate_hz == 0 or rate_hz == -1:
set_interval = rate_hz
Expand Down Expand Up @@ -8537,7 +8537,7 @@ def test_set_message_interval_basic(self):
raise ex

def send_poll_message(self, message_id, target_sysid=None, target_compid=None):
if type(message_id) == str:
if isinstance(message_id, str):
message_id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % message_id)
self.send_cmd(mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE,
message_id,
Expand All @@ -8551,7 +8551,7 @@ def send_poll_message(self, message_id, target_sysid=None, target_compid=None):
target_compid=target_compid)

def poll_message(self, message_id, timeout=10):
if type(message_id) == str:
if isinstance(message_id, str):
message_id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % message_id)
self.drain_mav()
tstart = self.get_sim_time() # required for timeout in run_cmd_get_ack to work
Expand Down Expand Up @@ -9439,7 +9439,7 @@ def upload_fences_from_locations(self,
seq = 0
items = []
for locs in list_of_list_of_locs:
if type(locs) == dict:
if isinstance(locs, dict):
# circular fence
if vertex_type == mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION:
v = mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION
Expand Down Expand Up @@ -11599,7 +11599,7 @@ def autotest(self):
"""Autotest used by ArduPilot autotest CI."""
all_tests = []
for test in self.tests():
if type(test) == Test:
if isinstance(test, Test):
all_tests.append(test)
continue
(name, desc, func) = test
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/helicopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -183,7 +183,7 @@ def fly_each_frame(self):
# to carry the path to the JSON.
actual_model = model.split(":")[0]
defaults = self.model_defaults_filepath(actual_model)
if type(defaults) != list:
if not isinstance(defaults, list):
defaults = [defaults]
self.customise_SITL_commandline(
["--defaults", ','.join(defaults), ],
Expand Down
4 changes: 2 additions & 2 deletions Tools/autotest/quadplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -258,15 +258,15 @@ def test_airmode(self):
def test_motor_mask(self):
"""Check operation of output_motor_mask"""
"""copter tailsitters will add condition: or (int(self.get_parameter('Q_TAILSIT_MOTMX')) & 1)"""
if not(int(self.get_parameter('Q_TILT_MASK')) & 1):
if not (int(self.get_parameter('Q_TILT_MASK')) & 1):
self.progress("output_motor_mask not in use")
return
self.progress("Testing output_motor_mask")
self.wait_ready_to_arm()

"""Default channel for Motor1 is 5"""
self.progress('Assert that SERVO5 is Motor1')
assert(33 == self.get_parameter('SERVO5_FUNCTION'))
assert (33 == self.get_parameter('SERVO5_FUNCTION'))

modes = ('MANUAL', 'FBWA', 'QHOVER')
for mode in modes:
Expand Down
2 changes: 1 addition & 1 deletion Tools/gittools/pre-commit.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ def check_file(self, filepath):
def split_git_diff_output(self, output):
'''split output from git-diff into a list of (status, filepath) tuples'''
ret = []
if type(output) == bytes:
if isinstance(output, bytes):
output = output.decode('utf-8')
for line in output.split("\n"):
if len(line) == 0:
Expand Down
2 changes: 1 addition & 1 deletion Tools/scripts/uploader.py
Original file line number Diff line number Diff line change
Expand Up @@ -629,7 +629,7 @@ def erase_extflash(self, label, size):
self.__send(uploader.EXTF_ERASE + size_bytes + uploader.EOC)
self.__getSync()
last_pct = 0
while(True):
while True:
if last_pct < 90:
pct = self.__recv_uint8()
if last_pct != pct:
Expand Down

0 comments on commit e0cd85d

Please sign in to comment.