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

Add test for scripting flip mode #28927

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
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
31 changes: 31 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 -25.302853dB > -28.409931dB
"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 @@ -12281,6 +12281,36 @@
# restart GPS driver
self.reboot_sitl()

def ScriptingFlipMode(self):
'''test adding custom mode from scripting'''
# Really it would be nice to check for the AVAILABLE_MODES message, but pymavlink does not understand them yet.

# enable scripting and install flip script
self.set_parameters({
"SCR_ENABLE": 1,
})
self.install_example_script_context('Flip_Mode.lua')
self.reboot_sitl()

# Takeoff in loiter
self.takeoff(10, mode="LOITER")

# Try and switch to flip, should not be posible from loiter
try:
self.change_mode(100, timeout=10)
except AutoTestTimeoutException:
self.progress("PASS not able to enter from loiter")

# Should be alowd to enter from alt hold
self.change_mode("ALT_HOLD")
self.change_mode(100)

# Should return to previous mode after flipping
self.wait_mode("ALT_HOLD")

# Test done
self.land_and_disarm()

def tests2b(self): # this block currently around 9.5mins here
'''return list of all tests'''
ret = ([
Expand Down Expand Up @@ -12389,6 +12419,7 @@
self.ScriptingAHRSSource,
self.CommonOrigin,
self.TestTetherStuck,
self.ScriptingFlipMode,
])
return ret

Expand Down
8 changes: 3 additions & 5 deletions libraries/AP_Scripting/examples/Flip_Mode.lua
Original file line number Diff line number Diff line change
Expand Up @@ -217,13 +217,11 @@ local function exit()
end

local function update()
local mode = vehicle:get_mode()

-- Only allow entry into flip mode if armed and flying
local armed = arming:is_armed()
local flying = vehicle:get_likely_flying()
FLIP_MODE_STATE:allow_entry(armed and flying)
-- Update entry state
FLIP_MODE_STATE:allow_entry(allow_enter(mode))

local mode = vehicle:get_mode()
if mode == MODE_NUMBER then
if last_mode_number ~= MODE_NUMBER then
-- Fist call after entering
Expand Down
Loading