autotest: a gap in the beginning of the SERVO_FTW_MASK is now allowed, test it

make sure the SERVO_FWT_MASK is valid:
  - it can have bit gaps between active channels, but channels higher than 12 are not allowed (AP_EST_TELEM limitation)
  - Explain that the FETtec ESC IDs inside the FETtec Firmware need to be contiguous and start at 1.
add tests for ESC power outages
add test that safety switch zeroes PWM for FETtec ESC
This commit is contained in:
Peter Barker 2021-07-07 15:07:28 +02:00 committed by Peter Barker
parent 1b7b705856
commit e263063600
2 changed files with 119 additions and 6 deletions

View File

@ -7202,10 +7202,40 @@ class AutoTestCopter(AutoTest):
def FETtecESC_flight(self):
'''fly with servo outputs from FETtec ESC'''
self.start_subtest("FETtec EC flight")
self.start_subtest("FETtec ESC flight")
num_wp = self.load_mission("copter_mission.txt", strict=False)
self.fly_loaded_mission(num_wp)
def FETtecESC_esc_power_checks(self):
'''Make sure state machine copes with ESCs rebooting'''
self.start_subtest("FETtec ESC reboot")
self.wait_ready_to_arm()
self.context_collect('STATUSTEXT')
self.progress("Turning off an ESC off ")
mask = int(self.get_parameter("SIM_FTOWESC_POW"))
for mot_id_to_kill in 1, 2:
self.progress("Turning ESC=%u off" % mot_id_to_kill)
self.set_parameter("SIM_FTOWESC_POW", mask & ~(1 << mot_id_to_kill))
self.assert_prearm_failure("are not sending tel")
self.progress("Turning it back on")
self.set_parameter("SIM_FTOWESC_POW", mask)
self.wait_ready_to_arm()
self.progress("Turning ESC=%u off (again)" % mot_id_to_kill)
self.set_parameter("SIM_FTOWESC_POW", mask & ~(1 << mot_id_to_kill))
self.assert_prearm_failure("are not sending tel")
self.progress("Turning it back on")
self.set_parameter("SIM_FTOWESC_POW", mask)
self.wait_ready_to_arm()
self.progress("Turning all ESCs off")
self.set_parameter("SIM_FTOWESC_POW", 0)
self.assert_prearm_failure("are not sending tel")
self.progress("Turning them back on")
self.set_parameter("SIM_FTOWESC_POW", mask)
self.wait_ready_to_arm()
def fettec_assert_bad_mask(self, mask):
'''assert the mask is bad for fettec driver'''
self.start_subsubtest("Checking mask (%s) is bad" % (mask,))
@ -7234,21 +7264,60 @@ class AutoTestCopter(AutoTest):
self.context_pop()
self.reboot_sitl()
def FETtecESC_preflight_checks(self):
def FETtecESC_safety_switch(self):
mot = self.find_first_set_bit(int(self.get_parameter("SERVO_FTW_MASK"))) + 1
self.wait_esc_telem_rpm(mot, 0, 0)
self.wait_ready_to_arm()
self.context_push()
self.set_parameter("DISARM_DELAY", 0)
self.arm_vehicle()
# we have to wait for a while for the arming tone to go out
# before the motors will spin:
self.wait_esc_telem_rpm(
esc=mot,
rpm_min=17640,
rpm_max=17640,
minimum_duration=2,
timeout=5,
)
self.set_safetyswitch_on()
self.wait_esc_telem_rpm(mot, 0, 0)
self.set_safetyswitch_off()
self.wait_esc_telem_rpm(
esc=mot,
rpm_min=17640,
rpm_max=17640,
minimum_duration=2,
timeout=5,
)
self.context_pop()
self.wait_disarmed()
def FETtecESC_btw_mask_checks(self):
'''ensure prearm checks work as expected'''
for bad_mask in [0b101, 0b1010]:
for bad_mask in [0b1000000000000, 0b10100000000000]:
self.fettec_assert_bad_mask(bad_mask)
for good_mask in [0b00001, 0b000011]:
for good_mask in [0b00001, 0b00101, 0b110000000000]:
self.fettec_assert_good_mask(good_mask)
def FETtecESC(self):
self.set_parameters({
"SERIAL5_PROTOCOL": 38,
"SERVO_FTW_MASK": 15,
"SERVO_FTW_MASK": 0b11101000,
"SIM_FTOWESC_ENA": 1,
"SERVO1_FUNCTION": 0,
"SERVO2_FUNCTION": 0,
"SERVO3_FUNCTION": 0,
"SERVO4_FUNCTION": 33,
"SERVO5_FUNCTION": 0,
"SERVO6_FUNCTION": 34,
"SERVO7_FUNCTION": 35,
"SERVO8_FUNCTION": 36,
})
self.customise_SITL_commandline(["--uartF=sim:fetteconewireesc"])
self.FETtecESC_preflight_checks()
self.FETtecESC_safety_switch()
self.FETtecESC_esc_power_checks()
self.FETtecESC_btw_mask_checks()
self.FETtecESC_flight()
def tests1a(self):

View File

@ -3692,6 +3692,18 @@ class AutoTest(ABC):
else:
return None
def set_safetyswitch_on(self):
self.set_safetyswitch(1)
def set_safetyswitch_off(self):
self.set_safetyswitch(0)
def set_safetyswitch(self, value, target_system=1, target_component=1):
self.mav.mav.set_mode_send(
target_system,
mavutil.mavlink.MAV_MODE_FLAG_DECODE_POSITION_SAFETY,
value)
def armed(self):
"""Return true if vehicle is armed and safetyoff"""
return self.mav.motors_armed()
@ -4872,6 +4884,38 @@ class AutoTest(ABC):
return msg.relative_alt / 1000.0 # mm -> m
return msg.alt / 1000.0 # mm -> m
def get_esc_rpm(self, esc):
if esc > 4:
raise ValueError("Only does 1-4")
m = self.mav.recv_match(type='ESC_TELEMETRY_1_TO_4', blocking=True, timeout=1)
if m is None:
raise NotAchievedException("Did not get ESC_TELEMETRY_1_TO_4")
self.progress("%s" % str(m))
return m.rpm[esc-1]
def find_first_set_bit(self, mask):
'''returns offset of first-set-bit (counting from right) in mask. Returns None if no bits set'''
pos = 0
while mask != 0:
if mask & 0x1:
return pos
mask = mask >> 1
pos += 1
return None
def wait_esc_telem_rpm(self, esc, rpm_min, rpm_max, **kwargs):
'''wait for ESC 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="ESC %u RPM" % esc,
target=(rpm_min+rpm_max)/2.0,
current_value_getter=lambda: self.get_esc_rpm(esc),
accuracy=rpm_max-rpm_min,
validator=lambda value2, target2: validator(value2, target2),
**kwargs
)
def wait_altitude(self, altitude_min, altitude_max, relative=False, timeout=30, **kwargs):
"""Wait for a given altitude range."""
assert altitude_min <= altitude_max, "Minimum altitude should be less than maximum altitude."