mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
Tools: autotest uses PRX1 parameters
This commit is contained in:
parent
6025b1dcaa
commit
c898261698
@ -6126,7 +6126,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
self.context_push()
|
self.context_push()
|
||||||
self.set_parameters({
|
self.set_parameters({
|
||||||
"SERIAL5_PROTOCOL": 1,
|
"SERIAL5_PROTOCOL": 1,
|
||||||
"PRX_TYPE": 2,
|
"PRX1_TYPE": 2,
|
||||||
"SIM_SPEEDUP": 8, # much GCS interaction
|
"SIM_SPEEDUP": 8, # much GCS interaction
|
||||||
})
|
})
|
||||||
self.reboot_sitl()
|
self.reboot_sitl()
|
||||||
@ -6147,7 +6147,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
self.load_fence("copter-avoidance-fence.txt")
|
self.load_fence("copter-avoidance-fence.txt")
|
||||||
self.set_parameters({
|
self.set_parameters({
|
||||||
"FENCE_ENABLE": 1,
|
"FENCE_ENABLE": 1,
|
||||||
"PRX_TYPE": 10,
|
"PRX1_TYPE": 10,
|
||||||
"PRX_LOG_RAW": 1,
|
"PRX_LOG_RAW": 1,
|
||||||
"RC10_OPTION": 40, # proximity-enable
|
"RC10_OPTION": 40, # proximity-enable
|
||||||
})
|
})
|
||||||
@ -6215,7 +6215,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
home_string = "%s,%s,%s,%s" % (51.8752066, 14.6487840, 54.15, 0)
|
home_string = "%s,%s,%s,%s" % (51.8752066, 14.6487840, 54.15, 0)
|
||||||
for (name, prx_type, expected_distances) in sensors:
|
for (name, prx_type, expected_distances) in sensors:
|
||||||
self.start_subtest("Testing %s" % name)
|
self.start_subtest("Testing %s" % name)
|
||||||
self.set_parameter("PRX_TYPE", prx_type)
|
self.set_parameter("PRX1_TYPE", prx_type)
|
||||||
self.customise_SITL_commandline([
|
self.customise_SITL_commandline([
|
||||||
"--uartF=sim:%s:" % name,
|
"--uartF=sim:%s:" % name,
|
||||||
"--home", home_string,
|
"--home", home_string,
|
||||||
@ -6252,7 +6252,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
ex = None
|
ex = None
|
||||||
try:
|
try:
|
||||||
self.set_parameters({
|
self.set_parameters({
|
||||||
"PRX_TYPE": 2,
|
"PRX1_TYPE": 2,
|
||||||
"AVOID_ALT_MIN": 10,
|
"AVOID_ALT_MIN": 10,
|
||||||
})
|
})
|
||||||
self.set_analog_rangefinder_parameters()
|
self.set_analog_rangefinder_parameters()
|
||||||
@ -6835,7 +6835,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
ex = None
|
ex = None
|
||||||
try:
|
try:
|
||||||
self.set_parameter("SERIAL5_PROTOCOL", 1)
|
self.set_parameter("SERIAL5_PROTOCOL", 1)
|
||||||
self.set_parameter("PRX_TYPE", 2) # mavlink
|
self.set_parameter("PRX1_TYPE", 2) # mavlink
|
||||||
self.reboot_sitl()
|
self.reboot_sitl()
|
||||||
|
|
||||||
self.progress("Should be unhealthy while we don't send messages")
|
self.progress("Should be unhealthy while we don't send messages")
|
||||||
|
@ -571,7 +571,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||||||
self.load_fence("rover-fence-ac-avoid.txt")
|
self.load_fence("rover-fence-ac-avoid.txt")
|
||||||
self.set_parameters({
|
self.set_parameters({
|
||||||
"FENCE_ENABLE": 0,
|
"FENCE_ENABLE": 0,
|
||||||
"PRX_TYPE": 10,
|
"PRX1_TYPE": 10,
|
||||||
"RC10_OPTION": 40, # proximity-enable
|
"RC10_OPTION": 40, # proximity-enable
|
||||||
})
|
})
|
||||||
self.reboot_sitl()
|
self.reboot_sitl()
|
||||||
@ -5335,7 +5335,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||||||
ex = None
|
ex = None
|
||||||
try:
|
try:
|
||||||
self.set_parameters({
|
self.set_parameters({
|
||||||
"PRX_TYPE": 2, # AP_Proximity_MAV
|
"PRX1_TYPE": 2, # AP_Proximity_MAV
|
||||||
"OA_TYPE": 2, # dijkstra
|
"OA_TYPE": 2, # dijkstra
|
||||||
"OA_DB_OUTPUT": 3, # send all items
|
"OA_DB_OUTPUT": 3, # send all items
|
||||||
})
|
})
|
||||||
|
Loading…
Reference in New Issue
Block a user