Tools: autotest: sim_vehicle.py flake8 compliance

This commit is contained in:
Peter Barker 2019-01-19 09:33:03 +11:00
parent 9eea14054e
commit 6fc18792e4

View File

@ -157,7 +157,7 @@ def cygwin_pidof(proc_name):
if cmd == proc_name: if cmd == proc_name:
try: try:
pid = int(line_split[0].strip()) pid = int(line_split[0].strip())
except: except Exception as e:
pid = int(line_split[1].strip()) pid = int(line_split[1].strip())
if pid not in pids: if pid not in pids:
pids.append(pid) pids.append(pid)
@ -392,25 +392,26 @@ def get_user_locations_path():
def find_new_spawn(loc, file_path): def find_new_spawn(loc, file_path):
(lat, lon, alt, heading)=loc.split(",") (lat, lon, alt, heading) = loc.split(",")
swarminit_filepath = os.path.join(autotest, "swarminit.txt") swarminit_filepath = os.path.join(find_autotest_dir(), "swarminit.txt")
for path2 in [file_path, swarminit_filepath]: for path2 in [file_path, swarminit_filepath]:
if os.path.isfile(path2): if os.path.isfile(path2):
with open(path2,'r') as swd: with open(path2, 'r') as swd:
next(swd) next(swd)
for lines in swd: for lines in swd:
if len(lines) == 0: if len(lines) == 0:
continue continue
(instance, offset) = lines.split("=") (instance, offset) = lines.split("=")
if ((int)(instance) == (int)(cmd_opts.instance)): if ((int)(instance) == (int)(cmd_opts.instance)):
(x,y,z,head) = offset.split(",") (x, y, z, head) = offset.split(",")
g=mp_util.gps_offset((float)(lat), (float)(lon), (float)(x), (float)(y)) g = mp_util.gps_offset((float)(lat), (float)(lon), (float)(x), (float)(y))
loc=str(g[0])+","+str(g[1])+","+str(alt+z)+","+str(head) loc = str(g[0])+","+str(g[1])+","+str(alt+z)+","+str(head)
return loc return loc
g=mp_util.gps_newpos((float)(lat), (float)(lon), 90, 20*(int)(cmd_opts.instance)) g = mp_util.gps_newpos((float)(lat), (float)(lon), 90, 20*(int)(cmd_opts.instance))
loc=str(g[0])+","+str(g[1])+","+str(alt)+","+str(heading) loc = str(g[0])+","+str(g[1])+","+str(alt)+","+str(heading)
return loc return loc
def find_location_by_name(autotest, locname): def find_location_by_name(autotest, locname):
"""Search locations.txt for locname, return GPS coords""" """Search locations.txt for locname, return GPS coords"""
locations_userpath = os.environ.get('ARDUPILOT_LOCATIONS', locations_userpath = os.environ.get('ARDUPILOT_LOCATIONS',
@ -429,7 +430,7 @@ def find_location_by_name(autotest, locname):
(name, loc) = line.split("=") (name, loc) = line.split("=")
if name == locname: if name == locname:
if cmd_opts.swarm is not None: if cmd_opts.swarm is not None:
loc=find_new_spawn(loc, cmd_opts.swarm) loc = find_new_spawn(loc, cmd_opts.swarm)
return loc return loc
print("Failed to find location (%s)" % cmd_opts.location) print("Failed to find location (%s)" % cmd_opts.location)
@ -902,7 +903,7 @@ group_sim.add_option("", "--no-extra-ports",
dest='no_extra_ports', dest='no_extra_ports',
default=False, default=False,
help="Disable setup of UDP 14550 and 14551 output") help="Disable setup of UDP 14550 and 14551 output")
group_sim.add_option("-Z","--swarm", group_sim.add_option("-Z", "--swarm",
type='string', type='string',
default=None, default=None,
help="Specify path of swarminit.txt for shifting spawn location") help="Specify path of swarminit.txt for shifting spawn location")