Tools: add throttle curve and governor autotest for tradheli

This commit is contained in:
bnsgeyer 2023-05-29 23:38:27 -04:00 committed by Peter Barker
parent a18c818949
commit c8fc238e62
4 changed files with 40 additions and 1 deletions

View File

@ -8339,6 +8339,7 @@ class AutoTestCopter(AutoTest):
'heli-compound': "wrong binary, different takeoff regime", 'heli-compound': "wrong binary, different takeoff regime",
'heli-dual': "wrong binary, different takeoff regime", 'heli-dual': "wrong binary, different takeoff regime",
'heli': "wrong binary, different takeoff regime", 'heli': "wrong binary, different takeoff regime",
'heli-gas': "wrong binary, different takeoff regime",
'heli-blade360': "wrong binary, different takeoff regime", 'heli-blade360': "wrong binary, different takeoff regime",
} }
for frame in sorted(copter_vinfo_options["frames"].keys()): for frame in sorted(copter_vinfo_options["frames"].keys()):

View File

@ -0,0 +1,9 @@
H_RSC_IDLE 14
H_RSC_MODE 3
H_RSC_RAMP_TIME 10
H_RSC_RUNUP_TIME 15
H_RSC_THRCRV_0 27
H_RSC_THRCRV_25 32
H_RSC_THRCRV_50 45
H_RSC_THRCRV_75 75
H_RSC_THRCRV_100 100

View File

@ -152,7 +152,13 @@ class AutoTestHelicopter(AutoTestCopter):
self.progress("Raising rotor speed") self.progress("Raising rotor speed")
self.set_rc(8, 2000) self.set_rc(8, 2000)
self.progress("wait for rotor runup to complete") self.progress("wait for rotor runup to complete")
self.wait_servo_channel_value(8, 1659, timeout=10) if self.get_parameter("H_RSC_MODE") == 4:
self.context_collect('STATUSTEXT')
self.wait_statustext("Governor Engaged", check_context=True)
elif self.get_parameter("H_RSC_MODE") == 3:
self.wait_rpm(1, 1300, 1400)
else:
self.wait_servo_channel_value(8, 1659, timeout=10)
# wait for motor runup # wait for motor runup
self.delay_sim_time(20) self.delay_sim_time(20)
@ -199,6 +205,18 @@ class AutoTestHelicopter(AutoTestCopter):
self.do_RTL() self.do_RTL()
self.set_rc(8, 1000) self.set_rc(8, 1000)
def governortest(self):
'''Test Heli Internal Throttle Curve and Governor'''
self.customise_SITL_commandline(
["--defaults", ','.join(self.model_defaults_filepath('heli-gas')), ],
model="heli-gas",
wipe=True,
)
self.set_parameter("H_RSC_MODE", 4)
self.takeoff(10)
self.do_RTL()
self.set_rc(8, 1000)
def hover(self): def hover(self):
self.progress("Setting hover collective") self.progress("Setting hover collective")
self.set_rc(3, 1500) self.set_rc(3, 1500)
@ -793,6 +811,7 @@ class AutoTestHelicopter(AutoTestCopter):
self.SplineWaypoint, self.SplineWaypoint,
self.AutoRotation, self.AutoRotation,
self.ManAutoRotation, self.ManAutoRotation,
self.governortest,
self.FlyEachFrame, self.FlyEachFrame,
self.AirspeedDrivers, self.AirspeedDrivers,
self.TurbineStart, self.TurbineStart,

View File

@ -149,6 +149,11 @@ class VehicleInfo(object):
"waf_target": "bin/arducopter-heli", "waf_target": "bin/arducopter-heli",
"default_params_filename": "default_params/copter-heli.parm", "default_params_filename": "default_params/copter-heli.parm",
}, },
"heli-gas": {
"waf_target": "bin/arducopter-heli",
"default_params_filename": ["default_params/copter-heli.parm",
"default_params/copter-heli-gas.parm"],
},
"heli-dual": { "heli-dual": {
"waf_target": "bin/arducopter-heli", "waf_target": "bin/arducopter-heli",
"default_params_filename": ["default_params/copter-heli.parm", "default_params_filename": ["default_params/copter-heli.parm",
@ -192,6 +197,11 @@ class VehicleInfo(object):
"waf_target": "bin/arducopter-heli", "waf_target": "bin/arducopter-heli",
"default_params_filename": "default_params/copter-heli.parm", "default_params_filename": "default_params/copter-heli.parm",
}, },
"heli-gas": {
"waf_target": "bin/arducopter-heli",
"default_params_filename": ["default_params/copter-heli.parm",
"default_params/copter-heli-gas.parm"],
},
"heli-dual": { "heli-dual": {
"waf_target": "bin/arducopter-heli", "waf_target": "bin/arducopter-heli",
"default_params_filename": ["default_params/copter-heli.parm", "default_params_filename": ["default_params/copter-heli.parm",