mirror of https://github.com/ArduPilot/ardupilot
autotest: add test for FETtecESC
This commit is contained in:
parent
97057a1350
commit
3bc4cf710f
|
@ -0,0 +1,14 @@
|
||||||
|
QGC WPL 110
|
||||||
|
0 1 0 16 0.000000 0.000000 0.000000 0.000000 -35.362881 149.165222 582.000000 1
|
||||||
|
1 0 3 22 0.000000 0.000000 0.000000 0.000000 -35.362881 149.165222 20.000000 1
|
||||||
|
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364652 149.163501 0.000000 1
|
||||||
|
3 0 3 115 640.000000 20.000000 1.000000 1.000000 0.000000 0.000000 0.000000 1
|
||||||
|
4 0 3 19 5.000000 0.000000 0.000000 1.000000 0.000000 0.000000 20.000000 1
|
||||||
|
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365361 149.163501 0.000000 1
|
||||||
|
6 0 3 16 1.000000 0.000000 0.000000 0.000000 -35.365361 149.163995 40.000000 1
|
||||||
|
7 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365361 149.164563 20.000000 1
|
||||||
|
8 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364652 149.164531 20.000000 1
|
||||||
|
9 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364652 149.163995 20.000000 1
|
||||||
|
10 0 3 177 8.000000 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||||
|
11 0 3 16 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||||
|
12 0 3 20 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
|
@ -2139,6 +2139,12 @@ class AutoTestCopter(AutoTest):
|
||||||
if not num_wp:
|
if not num_wp:
|
||||||
raise NotAchievedException("load copter_mission failed")
|
raise NotAchievedException("load copter_mission failed")
|
||||||
|
|
||||||
|
self.fly_loaded_mission(num_wp)
|
||||||
|
|
||||||
|
self.progress("Auto mission completed: passed!")
|
||||||
|
|
||||||
|
def fly_loaded_mission(self, num_wp):
|
||||||
|
'''fly mission loaded on vehicle. FIXME: get num_wp from vehicle'''
|
||||||
self.progress("test: Fly a mission from 1 to %u" % num_wp)
|
self.progress("test: Fly a mission from 1 to %u" % num_wp)
|
||||||
self.set_current_waypoint(1)
|
self.set_current_waypoint(1)
|
||||||
|
|
||||||
|
@ -2160,8 +2166,6 @@ class AutoTestCopter(AutoTest):
|
||||||
self.wait_disarmed()
|
self.wait_disarmed()
|
||||||
self.progress("MOTORS DISARMED OK")
|
self.progress("MOTORS DISARMED OK")
|
||||||
|
|
||||||
self.progress("Auto mission completed: passed!")
|
|
||||||
|
|
||||||
# fly_auto_test using CAN GPS - fly mission which tests normal operation alongside CAN GPS
|
# fly_auto_test using CAN GPS - fly mission which tests normal operation alongside CAN GPS
|
||||||
def fly_auto_test_using_can_gps(self):
|
def fly_auto_test_using_can_gps(self):
|
||||||
self.set_parameter("CAN_P1_DRIVER", 1)
|
self.set_parameter("CAN_P1_DRIVER", 1)
|
||||||
|
@ -7196,6 +7200,57 @@ class AutoTestCopter(AutoTest):
|
||||||
ret.extend(self.tests1e())
|
ret.extend(self.tests1e())
|
||||||
return ret
|
return ret
|
||||||
|
|
||||||
|
def FETtecESC_flight(self):
|
||||||
|
'''fly with servo outputs from FETtec ESC'''
|
||||||
|
self.start_subtest("FETtec EC flight")
|
||||||
|
num_wp = self.load_mission("copter_mission.txt", strict=False)
|
||||||
|
self.fly_loaded_mission(num_wp)
|
||||||
|
|
||||||
|
def fettec_assert_bad_mask(self, mask):
|
||||||
|
'''assert the mask is bad for fettec driver'''
|
||||||
|
self.start_subsubtest("Checking mask (%s) is bad" % (mask,))
|
||||||
|
self.context_push()
|
||||||
|
self.set_parameter("SERVO_FTW_MASK", mask)
|
||||||
|
self.reboot_sitl()
|
||||||
|
tstart = self.get_sim_time()
|
||||||
|
while True:
|
||||||
|
if self.get_sim_time_cached() - tstart > 20:
|
||||||
|
raise NotAchievedException("Expected mask to be only problem within 20 seconds")
|
||||||
|
try:
|
||||||
|
self.assert_prearm_failure("Invalid motor mask; need consecuti")
|
||||||
|
break
|
||||||
|
except NotAchievedException:
|
||||||
|
self.delay_sim_time(1)
|
||||||
|
self.context_pop()
|
||||||
|
self.reboot_sitl()
|
||||||
|
|
||||||
|
def fettec_assert_good_mask(self, mask):
|
||||||
|
'''assert the mask is bad for fettec driver'''
|
||||||
|
self.start_subsubtest("Checking mask (%s) is good" % (mask,))
|
||||||
|
self.context_push()
|
||||||
|
self.set_parameter("SERVO_FTW_MASK", mask)
|
||||||
|
self.reboot_sitl()
|
||||||
|
self.wait_ready_to_arm()
|
||||||
|
self.context_pop()
|
||||||
|
self.reboot_sitl()
|
||||||
|
|
||||||
|
def FETtecESC_preflight_checks(self):
|
||||||
|
'''ensure prearm checks work as expected'''
|
||||||
|
for bad_mask in [0b101, 0b1010]:
|
||||||
|
self.fettec_assert_bad_mask(bad_mask)
|
||||||
|
for good_mask in [0b00001, 0b000011]:
|
||||||
|
self.fettec_assert_good_mask(good_mask)
|
||||||
|
|
||||||
|
def FETtecESC(self):
|
||||||
|
self.set_parameters({
|
||||||
|
"SERIAL5_PROTOCOL": 38,
|
||||||
|
"SERVO_FTW_MASK": 15,
|
||||||
|
"SIM_FTOWESC_ENA": 1,
|
||||||
|
})
|
||||||
|
self.customise_SITL_commandline(["--uartF=sim:fetteconewireesc"])
|
||||||
|
self.FETtecESC_preflight_checks()
|
||||||
|
self.FETtecESC_flight()
|
||||||
|
|
||||||
def tests1a(self):
|
def tests1a(self):
|
||||||
'''return list of all tests'''
|
'''return list of all tests'''
|
||||||
ret = super(AutoTestCopter, self).tests() # about 5 mins and ~20 initial tests from autotest/common.py
|
ret = super(AutoTestCopter, self).tests() # about 5 mins and ~20 initial tests from autotest/common.py
|
||||||
|
@ -7655,6 +7710,10 @@ class AutoTestCopter(AutoTest):
|
||||||
"Test Replay",
|
"Test Replay",
|
||||||
self.test_replay),
|
self.test_replay),
|
||||||
|
|
||||||
|
Test("FETtecESC",
|
||||||
|
"Test FETtecESC",
|
||||||
|
self.FETtecESC),
|
||||||
|
|
||||||
Test("GroundEffectCompensation_touchDownExpected",
|
Test("GroundEffectCompensation_touchDownExpected",
|
||||||
"Test EKF's handling of touchdown-expected",
|
"Test EKF's handling of touchdown-expected",
|
||||||
self.GroundEffectCompensation_touchDownExpected),
|
self.GroundEffectCompensation_touchDownExpected),
|
||||||
|
|
Loading…
Reference in New Issue