autotest: make and declare sim_vehicle.py flake8-clean

This commit is contained in:
Peter Barker 2021-02-21 19:48:07 +11:00 committed by Peter Barker
parent 98451e499a
commit adf44f3b2b

View File

@ -5,10 +5,14 @@ Framework to start a simulated vehicle and connect it to MAVProxy.
Peter Barker, April 2016
based on sim_vehicle.sh by Andrew Tridgell, October 2011
AP_FLAKE8_CLEAN
"""
from __future__ import print_function
import atexit
import datetime
import errno
import optparse
import os
@ -26,8 +30,6 @@ import binascii
from pymavlink import mavextra
from pysim import vehicleinfo
import time
import datetime
# List of open terminal windows for macosx
windowID = []
@ -37,6 +39,7 @@ root_dir = os.path.realpath(os.path.join(autotest_dir, '../..'))
os.environ["SIM_VEHICLE_SESSION"] = binascii.hexlify(os.urandom(8)).decode()
class CompatError(Exception):
"""A custom exception class to hold state if we encounter the parse
error we are looking for"""
@ -165,7 +168,7 @@ def cygwin_pidof(proc_name):
if cmd == proc_name:
try:
pid = int(line_split[0].strip())
except Exception as e:
except Exception:
pid = int(line_split[1].strip())
if pid not in pids:
pids.append(pid)
@ -300,7 +303,7 @@ def do_build(opts, frame_options):
if opts.OSDMSP:
cmd_configure.append("--osd")
if opts.rgbled:
cmd_configure.append("--enable-sfml")
cmd_configure.append("--sitl-rgbled")
@ -319,7 +322,7 @@ def do_build(opts, frame_options):
if opts.disable_ekf3:
cmd_configure.append("--disable-ekf3")
pieces = [shlex.split(x) for x in opts.waf_configure_args]
for piece in pieces:
cmd_configure.extend(piece)
@ -387,7 +390,7 @@ def get_user_locations_path():
def find_offsets(instances, file_path):
offsets = {}
swarminit_filepath = os.path.join(autotest_dir, "swarminit.txt")
comment_regex = re.compile("\s*#.*")
comment_regex = re.compile(r"\s*#.*")
for path in [file_path, swarminit_filepath]:
if os.path.isfile(path):
with open(path, 'r') as fd:
@ -399,7 +402,7 @@ def find_offsets(instances, file_path):
(instance, offset) = line.split("=")
instance = (int)(instance)
if (instance not in offsets) and (instance in instances):
offsets[instance] = [ (float)(x) for x in offset.split(",") ]
offsets[instance] = [(float)(x) for x in offset.split(",")]
continue
if len(offsets) == len(instances):
return offsets
@ -416,7 +419,7 @@ def find_location_by_name(locname):
locations_userpath = os.environ.get('ARDUPILOT_LOCATIONS',
get_user_locations_path())
locations_filepath = os.path.join(autotest_dir, "locations.txt")
comment_regex = re.compile("\s*#.*")
comment_regex = re.compile(r"\s*#.*")
for path in [locations_userpath, locations_filepath]:
if not os.path.isfile(path):
continue
@ -428,7 +431,7 @@ def find_location_by_name(locname):
continue
(name, loc) = line.split("=")
if name == locname:
return [ (float)(x) for x in loc.split(",") ]
return [(float)(x) for x in loc.split(",")]
print("Failed to find location (%s)" % cmd_opts.location)
sys.exit(1)
@ -634,7 +637,7 @@ def start_vehicle(binary, opts, stuff, spawns=None):
# Parse start_time into a double precision number specifying seconds since 1900.
try:
start_time_UTC = time.mktime(datetime.datetime.strptime(cmd_opts.start_time, '%Y-%m-%d-%H:%M').timetuple())
except:
except Exception:
print("Incorrect start time format - require YYYY-MM-DD-HH:MM (given %s)" % cmd_opts.start_time)
sys.exit(1)
@ -1218,7 +1221,7 @@ if cmd_opts.tracker:
start_antenna_tracker(cmd_opts)
if cmd_opts.custom_location:
location = [ (float)(x) for x in cmd_opts.custom_location.split(",") ]
location = [(float)(x) for x in cmd_opts.custom_location.split(",")]
progress("Starting up at %s" % (location,))
elif cmd_opts.location is not None:
location = find_location_by_name(cmd_opts.location)
@ -1229,7 +1232,7 @@ else:
if cmd_opts.swarm is not None:
offsets = find_offsets(instances, cmd_opts.swarm)
else:
offsets = { x: [0.0, 0.0, 0.0, None] for x in instances }
offsets = {x: [0.0, 0.0, 0.0, None] for x in instances}
if location is not None:
spawns = find_spawns(location, offsets)
else: