mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tools: add tests for ICE Planes
This commit is contained in:
parent
db59117b83
commit
215842fe82
@ -0,0 +1,7 @@
|
|||||||
|
QGC WPL 110
|
||||||
|
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -27.274439 151.290064 343.089996 1
|
||||||
|
1 0 3 84 0.000000 0.000000 0.000000 0.000000 8.088916 1.817588 50.000000 1
|
||||||
|
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -27.273614 151.284212 100.000000 1
|
||||||
|
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -27.272018 151.285616 100.000000 1
|
||||||
|
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -27.272738 151.290290 100.000000 1
|
||||||
|
5 0 3 85 0.000000 0.000000 0.000000 0.000000 -27.274316 151.288817 0.000000 1
|
@ -5596,6 +5596,32 @@ class AutoTest(ABC):
|
|||||||
pos += 1
|
pos += 1
|
||||||
return None
|
return None
|
||||||
|
|
||||||
|
def get_rpm(self, rpm_sensor):
|
||||||
|
m = self.assert_receive_message('RPM')
|
||||||
|
if rpm_sensor == 1:
|
||||||
|
ret = m.rpm1
|
||||||
|
elif rpm_sensor == 2:
|
||||||
|
ret = m.rpm2
|
||||||
|
else:
|
||||||
|
raise ValueError("Bad sensor id")
|
||||||
|
if ret < 0.000001:
|
||||||
|
# yay filtering!
|
||||||
|
return 0
|
||||||
|
return ret
|
||||||
|
|
||||||
|
def wait_rpm(self, rpm_sensor, rpm_min, rpm_max, **kwargs):
|
||||||
|
'''wait for RPM to be between rpm_min and rpm_max'''
|
||||||
|
def validator(value2, target2=None):
|
||||||
|
return rpm_min <= value2 <= rpm_max
|
||||||
|
self.wait_and_maintain(
|
||||||
|
value_name="RPM%u" % rpm_sensor,
|
||||||
|
target=(rpm_min+rpm_max)/2.0,
|
||||||
|
current_value_getter=lambda: self.get_rpm(rpm_sensor),
|
||||||
|
accuracy=rpm_max-rpm_min,
|
||||||
|
validator=lambda value2, target2: validator(value2, target2),
|
||||||
|
**kwargs
|
||||||
|
)
|
||||||
|
|
||||||
def wait_esc_telem_rpm(self, esc, rpm_min, rpm_max, **kwargs):
|
def wait_esc_telem_rpm(self, esc, rpm_min, rpm_max, **kwargs):
|
||||||
'''wait for ESC to be between rpm_min and rpm_max'''
|
'''wait for ESC to be between rpm_min and rpm_max'''
|
||||||
def validator(value2, target2=None):
|
def validator(value2, target2=None):
|
||||||
@ -5750,6 +5776,8 @@ class AutoTest(ABC):
|
|||||||
count_of_achieved_values = 0
|
count_of_achieved_values = 0
|
||||||
called_function = kwargs.get("called_function", None)
|
called_function = kwargs.get("called_function", None)
|
||||||
minimum_duration = kwargs.get("minimum_duration", 0)
|
minimum_duration = kwargs.get("minimum_duration", 0)
|
||||||
|
if minimum_duration >= timeout:
|
||||||
|
raise ValueError("minimum_duration >= timeout")
|
||||||
if type(target) is Vector3:
|
if type(target) is Vector3:
|
||||||
self.progress("Waiting for %s=(%s) with accuracy %.02f" % (value_name, str(target), accuracy))
|
self.progress("Waiting for %s=(%s) with accuracy %.02f" % (value_name, str(target), accuracy))
|
||||||
else:
|
else:
|
||||||
@ -11300,7 +11328,7 @@ switch value'''
|
|||||||
tstart = self.get_sim_time()
|
tstart = self.get_sim_time()
|
||||||
while True:
|
while True:
|
||||||
t = self.get_sim_time_cached()
|
t = self.get_sim_time_cached()
|
||||||
if t - tstart > 10:
|
if t - tstart > timeout:
|
||||||
raise AutoTestTimeoutException("Failed to do get valid RPM")
|
raise AutoTestTimeoutException("Failed to do get valid RPM")
|
||||||
rpm = self.mav.recv_match(
|
rpm = self.mav.recv_match(
|
||||||
type='RPM',
|
type='RPM',
|
||||||
|
@ -811,6 +811,56 @@ class AutoTestQuadPlane(AutoTest):
|
|||||||
raise NotAchievedException("Changed throttle output on mode change to QHOVER")
|
raise NotAchievedException("Changed throttle output on mode change to QHOVER")
|
||||||
self.disarm_vehicle()
|
self.disarm_vehicle()
|
||||||
|
|
||||||
|
def ICEngine(self):
|
||||||
|
rc_engine_start_chan = 11
|
||||||
|
self.set_parameters({
|
||||||
|
'SERVO13_FUNCTION': 67, # ignition
|
||||||
|
'SERVO14_FUNCTION': 69, # starter
|
||||||
|
'ICE_ENABLE': 1,
|
||||||
|
'ICE_START_CHAN': rc_engine_start_chan,
|
||||||
|
'ICE_RPM_CHAN': 1,
|
||||||
|
'RPM1_TYPE': 10,
|
||||||
|
})
|
||||||
|
self.reboot_sitl()
|
||||||
|
self.wait_ready_to_arm()
|
||||||
|
self.wait_rpm(1, 0, 0, minimum_duration=1)
|
||||||
|
self.arm_vehicle()
|
||||||
|
self.wait_rpm(1, 0, 0, minimum_duration=1)
|
||||||
|
self.context_collect("STATUSTEXT")
|
||||||
|
self.progress("Setting engine-start RC switch to HIGH")
|
||||||
|
self.set_rc(rc_engine_start_chan, 2000)
|
||||||
|
self.wait_statustext("Starting engine", check_context=True)
|
||||||
|
self.wait_rpm(1, 300, 400, minimum_duration=1)
|
||||||
|
self.progress("Setting engine-start RC switch to MID")
|
||||||
|
self.set_rc(rc_engine_start_chan, 1500)
|
||||||
|
self.progress("Setting full throttle")
|
||||||
|
self.set_rc(3, 2000)
|
||||||
|
self.wait_rpm(1, 6500, 7500, minimum_duration=30, timeout=40)
|
||||||
|
self.progress("Setting min-throttle")
|
||||||
|
self.set_rc(3, 1000)
|
||||||
|
self.wait_rpm(1, 300, 400, minimum_duration=1)
|
||||||
|
self.progress("Setting engine-start RC switch to LOW")
|
||||||
|
self.set_rc(rc_engine_start_chan, 1000)
|
||||||
|
self.wait_rpm(1, 0, 0, minimum_duration=1)
|
||||||
|
self.disarm_vehicle()
|
||||||
|
|
||||||
|
def ICEngineMission(self):
|
||||||
|
rc_engine_start_chan = 11
|
||||||
|
self.set_parameters({
|
||||||
|
'SERVO13_FUNCTION': 67, # ignition
|
||||||
|
'SERVO14_FUNCTION': 69, # starter
|
||||||
|
'ICE_ENABLE': 1,
|
||||||
|
'ICE_START_CHAN': rc_engine_start_chan,
|
||||||
|
'ICE_RPM_CHAN': 1,
|
||||||
|
'RPM1_TYPE': 10,
|
||||||
|
})
|
||||||
|
self.load_mission("mission.txt")
|
||||||
|
self.wait_ready_to_arm()
|
||||||
|
self.set_rc(rc_engine_start_chan, 2000)
|
||||||
|
self.arm_vehicle()
|
||||||
|
self.change_mode('AUTO')
|
||||||
|
self.wait_disarmed(timeout=300)
|
||||||
|
|
||||||
def tests(self):
|
def tests(self):
|
||||||
'''return list of all tests'''
|
'''return list of all tests'''
|
||||||
|
|
||||||
@ -854,6 +904,13 @@ class AutoTestQuadPlane(AutoTest):
|
|||||||
"Test tailsitter support",
|
"Test tailsitter support",
|
||||||
self.tailsitter),
|
self.tailsitter),
|
||||||
|
|
||||||
|
("ICEngine",
|
||||||
|
"Test ICE Engine support",
|
||||||
|
self.ICEngine),
|
||||||
|
|
||||||
|
("ICEngineMission",
|
||||||
|
"Test ICE Engine Mission support",
|
||||||
|
self.ICEngineMission),
|
||||||
|
|
||||||
("LogUpload",
|
("LogUpload",
|
||||||
"Log upload",
|
"Log upload",
|
||||||
|
Loading…
Reference in New Issue
Block a user