Tools: sim_vehicle.py: use gps functions from pymavlink rather than MAVProxy

This should solve a problem on Windows where MAVProxy's libraries may
not be generally available (packed into a .exe)
This commit is contained in:
Peter Barker 2019-02-14 08:10:53 +11:00 committed by Peter Barker
parent 5134af2298
commit 90ea847cad

View File

@ -22,7 +22,7 @@ import textwrap
import time import time
import shlex import shlex
from MAVProxy.modules.lib import mp_util from pymavlink import mavextra
from pysim import vehicleinfo from pysim import vehicleinfo
# List of open terminal windows for macosx # List of open terminal windows for macosx
@ -407,10 +407,10 @@ def find_new_spawn(loc, file_path):
(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 = mavextra.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 = mavextra.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