Skip to content

Commit ef73e05

Browse files
committed
autotest: update source set and optical flow tests to take into account relative position in loiter
1 parent e8058eb commit ef73e05

File tree

1 file changed

+22
-7
lines changed

1 file changed

+22
-7
lines changed

Tools/autotest/arducopter.py

Lines changed: 22 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -3048,9 +3048,10 @@ def configure_EKFs_to_use_optical_flow_instead_of_GPS(self):
30483048
"EK3_SRC1_VELXY": 5,
30493049
"EK3_SRC1_VELZ": 0,
30503050
})
3051+
self.set_analog_rangefinder_parameters() # optical flow cannot be used for position without a rangefinder
30513052

30523053
def OpticalFlowLocation(self):
3053-
'''test optical flow does supply location'''
3054+
'''test optical flow *does* supply location'''
30543055

30553056
self.context_push()
30563057

@@ -3060,20 +3061,22 @@ def OpticalFlowLocation(self):
30603061
"AHRS_EKF_TYPE": 3,
30613062
"SIM_FLOW_ENABLE": 1,
30623063
"FLOW_TYPE": 10,
3064+
"GPS1_TYPE": 0,
30633065
"AHRS_ORIGIN_LAT": -35.362938,
30643066
"AHRS_ORIGIN_LNG": 149.165085,
30653067
"AHRS_ORIGIN_ALT": 584.0805053710938
30663068
})
30673069

30683070
self.configure_EKFs_to_use_optical_flow_instead_of_GPS()
3069-
30703071
self.reboot_sitl()
30713072

30723073
self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW, True, True, True, verbose=True)
30733074

30743075
self.change_mode('LOITER')
30753076
self.delay_sim_time(5)
30763077
self.wait_ready_to_arm(require_absolute=False, timeout=300)
3078+
self.arm_vehicle() # check we can arm
3079+
self.disarm_vehicle(force=True)
30773080

30783081
self.context_pop()
30793082

@@ -3149,8 +3152,6 @@ def OpticalFlowLimits(self):
31493152

31503153
self.configure_EKFs_to_use_optical_flow_instead_of_GPS()
31513154

3152-
self.set_analog_rangefinder_parameters()
3153-
31543155
self.reboot_sitl()
31553156

31563157
# we can't takeoff in loiter as we need flow healthy
@@ -13593,15 +13594,29 @@ def _MAV_CMD_SET_EKF_SOURCE_SET(self, run_cmd):
1359313594
want_result=mavutil.mavlink.MAV_RESULT_DENIED,
1359413595
)
1359513596

13597+
self.set_parameters({
13598+
"AHRS_EKF_TYPE": 3,
13599+
"SIM_FLOW_ENABLE": 1,
13600+
"FLOW_TYPE": 10,
13601+
"GPS1_TYPE": 0,
13602+
})
13603+
self.configure_EKFs_to_use_optical_flow_instead_of_GPS()
13604+
self.reboot_sitl()
13605+
13606+
# the problem is that with a GPS enabled we will always have a position estimate
13607+
# as far as the EKF is concerned, but turning it off will not let us be ready to arm
13608+
# in loiter. To get around this we configure loiter for relative positioning
13609+
# which means we can check the source set behaviour without being affected by the
13610+
# absence of the GPS
1359613611
self.change_mode('LOITER')
13597-
self.wait_ready_to_arm()
13612+
self.wait_ready_to_arm(require_absolute=False)
1359813613

1359913614
run_cmd(mavutil.mavlink.MAV_CMD_SET_EKF_SOURCE_SET, 2)
1360013615

13601-
self.assert_prearm_failure('Need Position Estimate')
13616+
self.assert_prearm_failure('AHRS: waiting for home')
1360213617
run_cmd(mavutil.mavlink.MAV_CMD_SET_EKF_SOURCE_SET, 1)
1360313618

13604-
self.wait_ready_to_arm()
13619+
self.wait_ready_to_arm(require_absolute=False)
1360513620

1360613621
def MAV_CMD_SET_EKF_SOURCE_SET(self):
1360713622
'''test setting of source sets using mavlink command'''

0 commit comments

Comments
 (0)