diff --git a/Tools/autotest/default_params/quadplane-copter_tailsitter.parm b/Tools/autotest/default_params/quadplane-copter_tailsitter.parm index acd8243d109cc7..a936774c6ce33b 100644 --- a/Tools/autotest/default_params/quadplane-copter_tailsitter.parm +++ b/Tools/autotest/default_params/quadplane-copter_tailsitter.parm @@ -31,3 +31,17 @@ Q_A_RAT_YAW_I 0.039192 Q_A_RAT_YAW_IMAX 0.500000 Q_A_RAT_YAW_P 0.391919 Q_TRANS_DECEL 8 + +# setup rangefinder for tailsitter +SIM_SONAR_ROT 4 +SIM_SONAR_SCALE 10 +RNGFND1_TYPE 100 +RNGFND1_PIN 0 +RNGFND1_SCALING 10 +RNGFND1_MIN_CM 10 +RNGFND1_MAX_CM 5000 +RNGFND1_ORIENT 12 +RNGFND_LANDING 1 +RNGFND_LND_ORNT 12 + + diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index 1282f9213c0625..f73a7918906bb5 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -1049,6 +1049,24 @@ def Tailsitter(self): raise NotAchievedException("Changed throttle output on mode change to QHOVER") self.disarm_vehicle() + def CopterTailsitter(self): + '''copter tailsitter test''' + self.customise_SITL_commandline( + [], + defaults_filepath=self.model_defaults_filepath('quadplane-copter_tailsitter'), + model="quadplane-copter_tailsitter", + wipe=True, + ) + + self.reboot_sitl() + self.wait_ready_to_arm() + self.takeoff(60, mode='GUIDED') + self.context_collect("STATUSTEXT") + self.progress("Starting QLAND") + self.change_mode("QLAND") + self.wait_statustext("Rangefinder engaged") + self.wait_disarmed(timeout=100) + def setup_ICEngine_vehicle(self): '''restarts SITL with an IC Engine setup''' model = "quadplane-ice" @@ -1812,6 +1830,7 @@ def tests(self): self.QAssist, self.GyroFFT, self.Tailsitter, + self.CopterTailsitter, self.ICEngine, self.ICEngineMission, self.MAV_CMD_DO_ENGINE_CONTROL,