Tools: added --can-gps option to sim_vehicle.py

allows for easy DroneCAN testing
This commit is contained in:
Andrew Tridgell 2022-08-22 07:20:39 +10:00
parent 8014f96235
commit 3127af1af6
2 changed files with 31 additions and 1 deletions

View File

@ -392,6 +392,14 @@ class VehicleInfo(object):
},
},
},
"sitl_periph_gps": {
"frames": {
"gps": {
"configure_target": "sitl_periph_gps",
"waf_target": "bin/AP_Periph",
},
}
},
}

View File

@ -319,7 +319,9 @@ def do_build(opts, frame_options):
waf_light = os.path.join(root_dir, "modules/waf/waf-light")
cmd_configure = [waf_light, "configure", "--board", "sitl"]
configure_target = frame_options.get('configure_target', 'sitl')
cmd_configure = [waf_light, "configure", "--board", configure_target]
if opts.debug:
cmd_configure.append("--debug")
@ -382,6 +384,7 @@ def do_build(opts, frame_options):
if opts.clean:
run_cmd_blocking("Building clean", [waf_light, "clean"])
print(frame_options)
cmd_build = [waf_light, "build", "--target", frame_options["waf_target"]]
if opts.jobs is not None:
cmd_build += ['-j', str(opts.jobs)]
@ -623,6 +626,18 @@ def start_antenna_tracker(opts):
os.chdir(oldpwd)
def start_CAN_GPS(opts):
"""Compile and run the sitl_periph_gps"""
global can_uarta
progress("Preparing sitl_periph_gps")
options = vinfo.options["sitl_periph_gps"]['frames']['gps']
do_build(opts, options)
exe = os.path.join(root_dir, 'build/sitl_periph_gps', 'bin/AP_Periph')
run_in_terminal_window("sitl_periph_gps",
["nice", exe])
def start_vehicle(binary, opts, stuff, spawns=None):
"""Run the ArduPilot binary"""
@ -1036,6 +1051,10 @@ group_sim.add_option("-T", "--tracker",
group_sim.add_option("", "--enable-onvif",
action="store_true",
help="enable onvif camera control sim using AntennaTracker")
group_sim.add_option("", "--can-gps",
action='store_true',
default=False,
help="start a DroneCAN GPS instance (use Tools/scripts/CAN/can_sitl_nodev.sh first)")
group_sim.add_option("-A", "--sitl-instance-args",
type='string',
default=None,
@ -1378,6 +1397,9 @@ if cmd_opts.instance == 0:
if cmd_opts.tracker:
start_antenna_tracker(cmd_opts)
if cmd_opts.can_gps:
start_CAN_GPS(cmd_opts)
if cmd_opts.custom_location:
location = [(float)(x) for x in cmd_opts.custom_location.split(",")]
progress("Starting up at %s" % (location,))