Skip to content

Commit

Permalink
Tools: update autotest to work with heli SITL model changes
Browse files Browse the repository at this point in the history
  • Loading branch information
bnsgeyer committed Dec 15, 2023
1 parent 5c593f3 commit 2b458fb
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 8 deletions.
6 changes: 3 additions & 3 deletions Tools/autotest/default_params/copter-heli-dual.parm
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
FRAME_CLASS 11
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_PIT_D 0.0005
ATC_RAT_PIT_P 0.02
ATC_RAT_PIT_FF 0.0
ATC_RAT_YAW_D 0.0015
ATC_RAT_YAW_P 0.14685
ATC_HOVR_ROL_TRM 0
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/default_params/copter-heli.parm
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ ATC_ACCEL_Y_MAX 60000
ATC_HOVR_ROL_TRM 320
H_COL_MAX 1740
H_COL_MIN 1460
H_COL_ANG_MAX 10
H_COL_ANG_MAX 12
H_COL_ANG_MIN -2
H_RSC_MODE 2
H_RSC_SETPOINT 66
Expand Down
15 changes: 11 additions & 4 deletions Tools/autotest/helicopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -303,7 +303,7 @@ def StabilizeTakeOff(self):
if abs(m.relative_alt) > 100:
raise NotAchievedException("Took off prematurely")
self.progress("Pushing throttle past half-way")
self.set_rc(3, 1600)
self.set_rc(3, 1650)

self.progress("Monitoring takeoff")
self.wait_altitude(6.9, 8, relative=True)
Expand Down Expand Up @@ -401,20 +401,27 @@ def ManAutoRotation(self, timeout=600):
self.context_collect('STATUSTEXT')
self.change_mode('STABILIZE')
self.progress("Triggering manual autorotation by disabling interlock")
self.set_rc(3, 1300)
self.set_rc(3, 1000)
self.set_rc(8, 1000)
self.wait_servo_channel_value(8, 1200, timeout=3)
self.progress("channel 8 set to autorotation window")

# wait to establish autorotation
self.delay_sim_time(2)

self.set_rc(8, 2000)
self.wait_servo_channel_value(8, 1659, timeout=AROT_RAMP_TIME * 1.1)

# give time for engine to power up
self.set_rc(3, 1400)
self.delay_sim_time(2)

self.progress("in-flight power recovery")
self.set_rc(3, 1700)
self.set_rc(3, 1500)
self.delay_sim_time(5)

# initiate autorotation again
self.set_rc(3, 1200)
self.set_rc(3, 1000)
self.set_rc(8, 1000)

self.wait_statustext(r"SIM Hit ground at ([0-9.]+) m/s",
Expand Down

0 comments on commit 2b458fb

Please sign in to comment.