mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
autotest: specify baudrate for NMEA GPS for testing
This commit is contained in:
parent
0717c3409b
commit
bd364b6169
@ -7338,7 +7338,7 @@ class AutoTestCopter(AutoTest):
|
||||
("USD1_v1", 11),
|
||||
("leddarone", 12),
|
||||
("maxsonarseriallv", 13),
|
||||
("nmea", 17),
|
||||
("nmea", 17, {"baud": 9600}),
|
||||
("wasp", 18),
|
||||
("benewake_tf02", 19),
|
||||
("blping", 23),
|
||||
@ -7357,14 +7357,20 @@ class AutoTestCopter(AutoTest):
|
||||
(1, '--uartF', 5),
|
||||
(2, '--uartG', 6)]:
|
||||
if len(do_drivers) > offs:
|
||||
if len(do_drivers[offs]) > 2:
|
||||
(sim_name, rngfnd_param_value, kwargs) = do_drivers[offs]
|
||||
else:
|
||||
(sim_name, rngfnd_param_value) = do_drivers[offs]
|
||||
kwargs = {}
|
||||
command_line_args.append("%s=sim:%s" %
|
||||
(cmdline_argument, sim_name))
|
||||
serial_param_name = "SERIAL%u_PROTOCOL" % serial_num
|
||||
self.set_parameters({
|
||||
serial_param_name: 9, # rangefinder
|
||||
sets = {
|
||||
"SERIAL%u_PROTOCOL" % serial_num: 9, # rangefinder
|
||||
"RNGFND%u_TYPE" % (offs+1): rngfnd_param_value,
|
||||
})
|
||||
}
|
||||
if "baud" in kwargs:
|
||||
sets["SERIAL%u_BAUD" % serial_num] = kwargs["baud"]
|
||||
self.set_parameters(sets)
|
||||
self.customise_SITL_commandline(command_line_args)
|
||||
self.fly_rangefinder_drivers_fly([x[0] for x in do_drivers])
|
||||
self.context_pop()
|
||||
|
@ -5932,6 +5932,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
||||
"RNGFND1_TYPE" : 17, # NMEA must attach uart to SITL
|
||||
"RNGFND1_ORIENT" : 25, # Set to downward facing
|
||||
"SERIAL7_PROTOCOL" : 9, # Rangefinder on uartH
|
||||
"SERIAL7_BAUD" : 9600, # Rangefinder specific baudrate
|
||||
|
||||
"RNGFND3_TYPE" : 2, # MaxbotixI2C
|
||||
"RNGFND3_ADDR" : 112, # 0x70 address from SIM_I2C.cpp
|
||||
|
Loading…
Reference in New Issue
Block a user