diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 973a67c77a..59f4fce8a8 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -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 @@ -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), ], diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index a4af9874b2..35b8de926c 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -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), ], diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index 5e45c0eff8..5c10d0e5b2 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -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, 'PASSED', diff --git a/Tools/autotest/bisect-helper.py b/Tools/autotest/bisect-helper.py index f8655964ea..10b174ab22 100755 --- a/Tools/autotest/bisect-helper.py +++ b/Tools/autotest/bisect-helper.py @@ -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() diff --git a/Tools/autotest/check_autotest_speedup.py b/Tools/autotest/check_autotest_speedup.py index a601dcc5e9..9c8daa7de8 100755 --- a/Tools/autotest/check_autotest_speedup.py +++ b/Tools/autotest/check_autotest_speedup.py @@ -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() diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index d60e89268d..126f31ffc5 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -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: @@ -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): @@ -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): @@ -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 @@ -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, @@ -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: @@ -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 @@ -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, @@ -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 @@ -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 @@ -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 diff --git a/Tools/autotest/helicopter.py b/Tools/autotest/helicopter.py index 6f5a9a0d4d..56561523b7 100644 --- a/Tools/autotest/helicopter.py +++ b/Tools/autotest/helicopter.py @@ -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), ], diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index 4f8ff76b5e..95f0e88ee5 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -258,7 +258,7 @@ 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") @@ -266,7 +266,7 @@ def test_motor_mask(self): """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: diff --git a/Tools/gittools/pre-commit.py b/Tools/gittools/pre-commit.py index adb59f5b77..fc8c69e594 100755 --- a/Tools/gittools/pre-commit.py +++ b/Tools/gittools/pre-commit.py @@ -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: diff --git a/Tools/scripts/uploader.py b/Tools/scripts/uploader.py index c7abdd4d27..750eb6a189 100755 --- a/Tools/scripts/uploader.py +++ b/Tools/scripts/uploader.py @@ -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: