Tools: factorize sitl rangefinder setup

This commit is contained in:
Pierre Kancir 2019-07-10 15:57:46 +02:00 committed by Peter Barker
parent daaf769055
commit 12cb09a3f4
3 changed files with 15 additions and 40 deletions

View File

@ -384,11 +384,7 @@ class AutoTestCopter(AutoTest):
self.fetch_parameters()
self.set_parameter("PLND_TYPE", 4)
self.set_parameter("RNGFND1_TYPE", 1)
self.set_parameter("RNGFND1_MIN_CM", 0)
self.set_parameter("RNGFND1_MAX_CM", 4000)
self.set_parameter("RNGFND1_PIN", 0)
self.set_parameter("RNGFND1_SCALING", 12.12)
self.set_analog_rangefinder_parameters()
self.reboot_sitl()
@ -1214,11 +1210,7 @@ class AutoTestCopter(AutoTest):
self.set_parameter("SIM_FLOW_ENABLE", 1)
self.set_parameter("FLOW_TYPE", 10)
self.set_parameter("RNGFND1_TYPE", 1)
self.set_parameter("RNGFND1_MIN_CM", 0)
self.set_parameter("RNGFND1_MAX_CM", 4000)
self.set_parameter("RNGFND1_PIN", 0)
self.set_parameter("RNGFND1_SCALING", 12.12, epsilon=0.01)
self.set_analog_rangefinder_parameters()
self.set_parameter("SIM_GPS_DISABLE", 1)
self.set_parameter("SIM_TERRAIN", 0)
@ -1620,11 +1612,7 @@ class AutoTestCopter(AutoTest):
raise NotAchievedException("Found unexpected RFND message")
try:
self.set_parameter("RNGFND1_TYPE", 1)
self.set_parameter("RNGFND1_MIN_CM", 0)
self.set_parameter("RNGFND1_MAX_CM", 4000)
self.set_parameter("RNGFND1_PIN", 0)
self.set_parameter("RNGFND1_SCALING", 12.12)
self.set_analog_rangefinder_parameters()
self.set_parameter("RC9_OPTION", 10) # rangefinder
self.set_rc(9, 2000)
@ -1694,11 +1682,7 @@ class AutoTestCopter(AutoTest):
self.context_push()
try:
self.set_parameter("RNGFND1_TYPE", 1)
self.set_parameter("RNGFND1_MIN_CM", 0)
self.set_parameter("RNGFND1_MAX_CM", 4000)
self.set_parameter("RNGFND1_PIN", 0)
self.set_parameter("RNGFND1_SCALING", 12.12)
self.set_analog_rangefinder_parameters()
self.set_parameter("RC9_OPTION", 10) # rangefinder
self.set_rc(9, 2000)
@ -1832,11 +1816,7 @@ class AutoTestCopter(AutoTest):
self.fetch_parameters()
self.set_parameter("PLND_TYPE", 4)
self.set_parameter("RNGFND1_TYPE", 1)
self.set_parameter("RNGFND1_MIN_CM", 0)
self.set_parameter("RNGFND1_MAX_CM", 4000)
self.set_parameter("RNGFND1_PIN", 0)
self.set_parameter("RNGFND1_SCALING", 12)
self.set_analog_rangefinder_parameters()
self.set_parameter("SIM_SONAR_SCALE", 12)
start = self.mav.location()
@ -2531,11 +2511,7 @@ class AutoTestCopter(AutoTest):
ex = None
try:
self.set_parameter("RNGFND1_TYPE", 1)
self.set_parameter("RNGFND1_MIN_CM", 0)
self.set_parameter("RNGFND1_MAX_CM", 4000)
self.set_parameter("RNGFND1_PIN", 0)
self.set_parameter("RNGFND1_SCALING", 12.12)
self.set_analog_rangefinder_parameters()
self.set_parameter("GRIP_ENABLE", 1)
self.set_parameter("GRIP_TYPE", 1)
self.set_parameter("SIM_GRPS_ENABLE", 1)
@ -3104,11 +3080,7 @@ class AutoTestCopter(AutoTest):
# enable companion backend:
self.set_parameter("PLND_TYPE", 1)
self.set_parameter("RNGFND1_TYPE", 1)
self.set_parameter("RNGFND1_MIN_CM", 0)
self.set_parameter("RNGFND1_MAX_CM", 4000)
self.set_parameter("RNGFND1_PIN", 0)
self.set_parameter("RNGFND1_SCALING", 12.12)
self.set_analog_rangefinder_parameters()
# set up a channel switch to enable precision loiter:
self.set_parameter("RC7_OPTION", 39)

View File

@ -1231,11 +1231,7 @@ class AutoTestPlane(AutoTest):
raise NotAchievedException("Received unexpected RANGEFINDER msg")
try:
self.set_parameter("RNGFND1_TYPE", 1)
self.set_parameter("RNGFND1_MIN_CM", 0)
self.set_parameter("RNGFND1_MAX_CM", 4000)
self.set_parameter("RNGFND1_PIN", 0)
self.set_parameter("RNGFND1_SCALING", 12.12)
self.set_analog_rangefinder_parameters()
self.reboot_sitl()

View File

@ -884,6 +884,13 @@ class AutoTest(ABC):
0,
0)
def set_analog_rangefinder_parameters(self):
self.set_parameter("RNGFND1_TYPE", 1)
self.set_parameter("RNGFND1_MIN_CM", 0)
self.set_parameter("RNGFND1_MAX_CM", 4000)
self.set_parameter("RNGFND1_SCALING", 12.12)
self.set_parameter("RNGFND1_PIN", 0)
def arm_vehicle(self, timeout=20):
"""Arm vehicle with mavlink arm message."""
self.progress("Arm motors with MAVLink cmd")