diff --git a/Tools/autotest/helicopter.py b/Tools/autotest/helicopter.py index 3c7a464ed2013e..257a2b835a5b0f 100644 --- a/Tools/autotest/helicopter.py +++ b/Tools/autotest/helicopter.py @@ -872,7 +872,7 @@ def AutoTune(self): self.wait_statustext('AutoTune: Success', timeout=1000) now = self.get_sim_time() self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) - self.land_and_disarm() + self.autotune_land_and_save_gains() # test pitch rate P and Rate D tuning self.set_parameters({ @@ -891,7 +891,7 @@ def AutoTune(self): self.wait_statustext('AutoTune: Success', timeout=1000) now = self.get_sim_time() self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) - self.land_and_disarm() + self.autotune_land_and_save_gains() # test Roll rate P and Rate D tuning self.set_parameters({ @@ -910,7 +910,7 @@ def AutoTune(self): self.wait_statustext('AutoTune: Success', timeout=1000) now = self.get_sim_time() self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) - self.land_and_disarm() + self.autotune_land_and_save_gains() # test Roll and pitch angle P tuning self.set_parameters({ @@ -931,7 +931,7 @@ def AutoTune(self): self.wait_statustext('AutoTune: Success', timeout=1000) now = self.get_sim_time() self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) - self.land_and_disarm() + self.autotune_land_and_save_gains() # test yaw FF and rate P and Rate D self.set_parameters({ @@ -952,8 +952,7 @@ def AutoTune(self): self.wait_statustext('AutoTune: Success', timeout=1000) now = self.get_sim_time() self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) - self.land_and_disarm() - self.set_rc(8, 1000) + self.autotune_land_and_save_gains() # test yaw angle P tuning self.set_parameters({ @@ -970,12 +969,41 @@ def AutoTune(self): # hold position in loiter self.change_mode('AUTOTUNE') + tstart = self.get_sim_time() + self.wait_statustext('AutoTune: Success', timeout=1000) + now = self.get_sim_time() + self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) + self.autotune_land_and_save_gains() + + # tune check + self.set_parameters({ + "AUTOTUNE_AXES": 7, + "AUTOTUNE_SEQ": 16, + "AUTOTUNE_FRQ_MIN": 10, + "AUTOTUNE_FRQ_MAX": 80, + }) + + # Conduct testing from althold + self.takeoff(10, mode="ALT_HOLD") + + # hold position in loiter + self.change_mode('AUTOTUNE') + tstart = self.get_sim_time() self.wait_statustext('AutoTune: Success', timeout=1000) now = self.get_sim_time() self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) self.land_and_disarm() + def autotune_land_and_save_gains(self): + self.set_rc(3, 1000) + self.context_collect('STATUSTEXT') + self.wait_statustext(r"SIM Hit ground at ([0-9.]+) m/s", + check_context=True, + regex=True) + self.set_rc(8, 1000) + self.wait_disarmed() + def land_and_disarm(self, **kwargs): super(AutoTestHelicopter, self).land_and_disarm(**kwargs) self.progress("Killing rotor speed")