diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index b6a358c3ee..6a788cb5bf 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -670,8 +670,28 @@ def start_CAN_GPS(opts): 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]) + cmd = ["nice"] + cmd_name = "sitl_periph_gps" + if opts.valgrind: + cmd_name += " (valgrind)" + cmd.append("valgrind") + # adding this option allows valgrind to cope with the overload + # of operator new + cmd.append("--soname-synonyms=somalloc=nouserintercepts") + cmd.append("--track-origins=yes") + if opts.gdb or opts.gdb_stopped: + cmd_name += " (gdb)" + cmd.append("gdb") + gdb_commands_file = tempfile.NamedTemporaryFile(mode='w', delete=False) + atexit.register(os.unlink, gdb_commands_file.name) + gdb_commands_file.write("set pagination off\n") + if not opts.gdb_stopped: + gdb_commands_file.write("r\n") + gdb_commands_file.close() + cmd.extend(["-x", gdb_commands_file.name]) + cmd.append("--args") + cmd.append(exe) + run_in_terminal_window(cmd_name, cmd) def start_vehicle(binary, opts, stuff, spawns=None):