Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

autotest: Added Copter Smart RTL repeat detection test #28920

Merged
merged 1 commit into from
Dec 21, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 11 additions & 0 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -6158,7 +6158,7 @@

# double-notch should do better, but check for within 5%
if peakdb2 * 1.05 > peakdb1:
raise NotAchievedException(

Check failure on line 6161 in Tools/autotest/arducopter.py

View workflow job for this annotation

GitHub Actions / autotest (sitltest-copter-tests2b)

vehicle_test_suite.NotAchievedException: Double-notch peak was higher than single-notch peak -24.627624dB > -26.166195dB
"Double-notch peak was higher than single-notch peak %fdB > %fdB" %
(peakdb2, peakdb1))

Expand All @@ -6182,7 +6182,7 @@
self.context_pop()

if ex is not None:
raise ex

Check failure on line 6185 in Tools/autotest/arducopter.py

View workflow job for this annotation

GitHub Actions / autotest (sitltest-copter-tests2b)

File "/__w/ardupilot/ardupilot/Tools/autotest/arducopter.py", line 6161, in DynamicNotches

def DynamicRpmNotches(self):
"""Use dynamic harmonic notch to control motor noise via ESC telemetry."""
Expand Down Expand Up @@ -9976,6 +9976,15 @@
self.change_mode('ALT_HOLD')
self.change_mode('SMART_RTL')

def SMART_RTL_Repeat(self):
'''Test whether Smart RTL catches the repeat'''
self.takeoff(alt_min=10, mode='GUIDED')
self.set_rc(3, 1500)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
self.set_rc(3, 1500)
self.hover()

... that could be useful if you're running a frame other than the default, boring one.

We don't do this in many places yet, and it doesnt' actually do anything but set it to 1500... but aspirationally...

self.change_mode("CIRCLE")
self.delay_sim_time(1300)
self.change_mode("SMART_RTL")
self.wait_disarmed()

def GPSForYawCompassLearn(self):
'''Moving baseline GPS yaw - with compass learning'''
self.context_push()
Expand Down Expand Up @@ -12299,6 +12308,7 @@
self.AP_Avoidance,
self.SMART_RTL,
self.SMART_RTL_EnterLeave,
self.SMART_RTL_Repeat,
self.RTL_TO_RALLY,
self.FlyEachFrame,
self.GPSBlending,
Expand Down Expand Up @@ -12461,6 +12471,7 @@
"GPSForYawCompassLearn": "Vehicle currently crashed in spectacular fashion",
"CompassMot": "Cuases an arithmetic exception in the EKF",
"SMART_RTL_EnterLeave": "Causes a panic",
"SMART_RTL_Repeat": "Currently fails due to issue with loop detection",
}


Expand Down
Loading