mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
autotest: add tests for AVD_F_ALT_MIN
This commit is contained in:
parent
e342ce0da4
commit
66395ce195
@ -7532,6 +7532,46 @@ class AutoTestCopter(AutoTest):
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
def AP_Avoidance(self):
|
||||
self.set_parameters({
|
||||
"AVD_ENABLE": 1,
|
||||
"ADSB_TYPE": 1, # mavlink
|
||||
"AVD_F_ACTION": 2, # climb or descend
|
||||
})
|
||||
self.reboot_sitl()
|
||||
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
here = self.mav.location()
|
||||
|
||||
self.context_push()
|
||||
|
||||
self.start_subtest("F_ALT_MIN zero - disabled, can't arm in face of threat")
|
||||
self.set_parameters({
|
||||
"AVD_F_ALT_MIN": 0,
|
||||
})
|
||||
self.wait_ready_to_arm()
|
||||
self.test_adsb_send_threatening_adsb_message(here)
|
||||
self.delay_sim_time(1)
|
||||
self.try_arm(result=False,
|
||||
expect_msg="ADSB threat detected")
|
||||
|
||||
self.wait_ready_to_arm(timeout=60)
|
||||
|
||||
self.context_pop()
|
||||
|
||||
self.start_subtest("F_ALT_MIN 16m relative - arm in face of threat")
|
||||
self.context_push()
|
||||
self.set_parameters({
|
||||
"AVD_F_ALT_MIN": int(16 + here.alt),
|
||||
})
|
||||
self.wait_ready_to_arm()
|
||||
self.test_adsb_send_threatening_adsb_message(here)
|
||||
# self.delay_sim_time(1)
|
||||
self.arm_vehicle()
|
||||
self.disarm_vehicle()
|
||||
self.context_pop()
|
||||
|
||||
def PAUSE_CONTINUE(self):
|
||||
self.load_mission("copter_mission.txt", strict=False)
|
||||
|
||||
@ -8163,6 +8203,10 @@ class AutoTestCopter(AutoTest):
|
||||
"Check GSF",
|
||||
self.test_gsf),
|
||||
|
||||
Test("AP_Avoidance",
|
||||
"ADSB-based avoidance",
|
||||
self.AP_Avoidance),
|
||||
|
||||
Test("SMART_RTL",
|
||||
"Check SMART_RTL",
|
||||
self.test_SMART_RTL),
|
||||
|
@ -1934,24 +1934,6 @@ class AutoTestPlane(AutoTest):
|
||||
continue
|
||||
last_collision = now
|
||||
|
||||
def test_adsb_send_threatening_adsb_message(self, here):
|
||||
self.progress("Sending ABSD_VEHICLE message")
|
||||
self.mav.mav.adsb_vehicle_send(
|
||||
37, # ICAO address
|
||||
int(here.lat * 1e7),
|
||||
int(here.lng * 1e7),
|
||||
mavutil.mavlink.ADSB_ALTITUDE_TYPE_PRESSURE_QNH,
|
||||
int(here.alt*1000 + 10000), # 10m up
|
||||
0, # heading in cdeg
|
||||
0, # horizontal velocity cm/s
|
||||
0, # vertical velocity cm/s
|
||||
"bob".encode("ascii"), # callsign
|
||||
mavutil.mavlink.ADSB_EMITTER_TYPE_LIGHT,
|
||||
1, # time since last communication
|
||||
65535, # flags
|
||||
17 # squawk
|
||||
)
|
||||
|
||||
def SimADSB(self):
|
||||
'''trivial tests to ensure simulated ADSB sensor continues to
|
||||
function'''
|
||||
|
@ -1995,6 +1995,24 @@ class AutoTest(ABC):
|
||||
htree[n] = p
|
||||
return htree
|
||||
|
||||
def test_adsb_send_threatening_adsb_message(self, here):
|
||||
self.progress("Sending ABSD_VEHICLE message")
|
||||
self.mav.mav.adsb_vehicle_send(
|
||||
37, # ICAO address
|
||||
int(here.lat * 1e7),
|
||||
int(here.lng * 1e7),
|
||||
mavutil.mavlink.ADSB_ALTITUDE_TYPE_PRESSURE_QNH,
|
||||
int(here.alt*1000 + 10000), # 10m up
|
||||
0, # heading in cdeg
|
||||
0, # horizontal velocity cm/s
|
||||
0, # vertical velocity cm/s
|
||||
"bob".encode("ascii"), # callsign
|
||||
mavutil.mavlink.ADSB_EMITTER_TYPE_LIGHT,
|
||||
1, # time since last communication
|
||||
65535, # flags
|
||||
17 # squawk
|
||||
)
|
||||
|
||||
def test_parameter_documentation_get_all_parameters(self):
|
||||
xml_filepath = os.path.join(self.buildlogs_dirpath(), "apm.pdef.xml")
|
||||
param_parse_filepath = os.path.join(self.rootdir(), 'Tools', 'autotest', 'param_metadata', 'param_parse.py')
|
||||
|
Loading…
Reference in New Issue
Block a user