mirror of https://github.com/ArduPilot/ardupilot
Tools: copter test_rangefinder_switchover config for EKF2/3
This commit is contained in:
parent
bd8b85d1e5
commit
d00194c60a
|
@ -2567,12 +2567,16 @@ class AutoTestCopter(AutoTest):
|
||||||
self.set_analog_rangefinder_parameters()
|
self.set_analog_rangefinder_parameters()
|
||||||
|
|
||||||
self.set_parameters({
|
self.set_parameters({
|
||||||
"RNGFND1_MAX_CM": 1500,
|
"RNGFND1_MAX_CM": 1500
|
||||||
"EK2_RNG_USE_HGT": 70,
|
|
||||||
"EK2_ENABLE": 1,
|
|
||||||
"AHRS_EKF_TYPE": 2,
|
|
||||||
})
|
})
|
||||||
|
|
||||||
|
# configure EKF to use rangefinder for altitude at low altitudes
|
||||||
|
ahrs_ekf_type = self.get_parameter("AHRS_EKF_TYPE")
|
||||||
|
if ahrs_ekf_type == 2:
|
||||||
|
self.set_parameter("EK2_RNG_USE_HGT", 70)
|
||||||
|
if ahrs_ekf_type == 3:
|
||||||
|
self.set_parameter("EK3_RNG_USE_HGT", 70)
|
||||||
|
|
||||||
self.reboot_sitl() # needed for both rangefinder and initial position
|
self.reboot_sitl() # needed for both rangefinder and initial position
|
||||||
self.assert_vehicle_location_is_at_startup_location()
|
self.assert_vehicle_location_is_at_startup_location()
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue