From 9b60072a04638cd82842df3482b139f3b7cc6b15 Mon Sep 17 00:00:00 2001 From: Bill Geyer Date: Fri, 10 Feb 2023 23:37:27 -0500 Subject: [PATCH] Tools:Autotest: tradheli improvements set servo8 min-max for heli default params improve heli-dual default params modified dual heli default params for new sitl model allow spool up time for heli takeoff --- Tools/autotest/default_params/copter-heli-dual.parm | 13 ++++++++++++- Tools/autotest/default_params/copter-heli.parm | 3 +++ Tools/autotest/helicopter.py | 11 +++++++---- 3 files changed, 22 insertions(+), 5 deletions(-) diff --git a/Tools/autotest/default_params/copter-heli-dual.parm b/Tools/autotest/default_params/copter-heli-dual.parm index 17fb19337f..d12d6725f6 100644 --- a/Tools/autotest/default_params/copter-heli-dual.parm +++ b/Tools/autotest/default_params/copter-heli-dual.parm @@ -1,2 +1,13 @@ FRAME_CLASS 11 -ATC_PIRO_COMP 0 # should this line be removed? +ATC_ANG_PIT_P 4.5 +ATC_ANG_YAW_P 4.5 +ATC_RAT_PIT_D 0.0012 +ATC_RAT_PIT_P 0.001 +ATC_RAT_PIT_FF 0.17 +ATC_RAT_YAW_D 0.0015 +ATC_RAT_YAW_P 0.14685 +ATC_HOVR_ROL_TRM 0 +H_COL2_MAX 1740 +H_COL2_MIN 1460 +PILOT_Y_RATE_TC 0.08 +PILOT_Y_RATE 120 diff --git a/Tools/autotest/default_params/copter-heli.parm b/Tools/autotest/default_params/copter-heli.parm index 641b7b90c0..08a836dd01 100644 --- a/Tools/autotest/default_params/copter-heli.parm +++ b/Tools/autotest/default_params/copter-heli.parm @@ -73,6 +73,7 @@ H_COL_MIN 1460 H_COL_ANG_MAX 10 H_COL_ANG_MIN -2 H_RSC_MODE 2 +H_RSC_SETPOINT 66 RC1_MAX 2000.000000 RC1_MIN 1000.000000 RC1_TRIM 1500.000000 @@ -100,3 +101,5 @@ RC8_TRIM 1500.000000 RPM1_TYPE 10 IM_ACRO_COL_EXP 0.2 PSC_VELXY_D 0.5 +SERVO8_MIN 1000.000000 +SERVO8_MAX 2000.000000 diff --git a/Tools/autotest/helicopter.py b/Tools/autotest/helicopter.py index b2f1edddf1..be0028d81e 100644 --- a/Tools/autotest/helicopter.py +++ b/Tools/autotest/helicopter.py @@ -150,7 +150,10 @@ class AutoTestHelicopter(AutoTestCopter): self.progress("Raising rotor speed") self.set_rc(8, 2000) self.progress("wait for rotor runup to complete") - self.wait_servo_channel_value(8, 1660, timeout=10) + self.wait_servo_channel_value(8, 1659, timeout=10) + + # wait for motor runup + self.delay_sim_time(20) if mode == 'GUIDED': self.user_takeoff(alt_min=alt_min) @@ -214,7 +217,7 @@ class AutoTestHelicopter(AutoTestCopter): self.progress("Raising rotor speed") self.set_rc(8, 2000) self.progress("wait for rotor runup to complete") - self.wait_servo_channel_value(8, 1660, timeout=10) + self.wait_servo_channel_value(8, 1659, timeout=10) self.delay_sim_time(20) # check we are still on the ground... m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True) @@ -273,7 +276,7 @@ class AutoTestHelicopter(AutoTestCopter): self.arm_vehicle() self.set_rc(8, 2000) self.progress("wait for rotor runup to complete") - self.wait_servo_channel_value(8, 1660, timeout=10) + self.wait_servo_channel_value(8, 1659, timeout=10) self.delay_sim_time(20) # check we are still on the ground... m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True) @@ -331,7 +334,7 @@ class AutoTestHelicopter(AutoTestCopter): self.arm_vehicle() self.set_rc(8, 2000) self.progress("wait for rotor runup to complete") - self.wait_servo_channel_value(8, 1660, timeout=10) + self.wait_servo_channel_value(8, 1659, timeout=10) self.delay_sim_time(20) self.set_rc(3, 2000) self.wait_altitude(start_alt - 1,