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

CX_BIT Autotests #276

Merged
merged 7 commits into from
Dec 29, 2024
Merged
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
2 changes: 1 addition & 1 deletion .github/workflows/test_sitl_blimp.yml
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,7 @@ jobs:
export CXX=clang++
fi
PATH="/github/home/.local/bin:$PATH"
./waf configure --board sitl
./waf configure --board sitl --debug
./waf build --target bin/blimp
ccache -s
ccache -z
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_sitl_copter.yml
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ jobs:
export CXX=clang++
fi
PATH="/github/home/.local/bin:$PATH"
./waf configure --board sitl
./waf configure --board sitl --debug
./waf build --target bin/arducopter
ccache -s
ccache -z
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_sitl_periph.yml
Original file line number Diff line number Diff line change
Expand Up @@ -196,7 +196,7 @@ jobs:
run: |
git config --global --add safe.directory ${GITHUB_WORKSPACE}
PATH="/github/home/.local/bin:$PATH"
./waf configure --board sitl_periph_universal
./waf configure --board sitl_periph_universal --debug
./waf build --target bin/AP_Periph
ccache -s
ccache -z
Expand Down
4 changes: 3 additions & 1 deletion .github/workflows/test_sitl_plane.yml
Original file line number Diff line number Diff line change
Expand Up @@ -203,7 +203,7 @@ jobs:
export CXX=clang++
fi
PATH="/github/home/.local/bin:$PATH"
./waf configure --board sitl
./waf configure --board sitl --debug
./waf build --target bin/arduplane
ccache -s
ccache -z
Expand All @@ -220,6 +220,8 @@ jobs:
config: [
sitltest-plane,
sitltest-quadplane,
sitltest-carbonix-ottano,
sitltest-carbonix-volanti,
]

steps:
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_sitl_rover.yml
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,7 @@ jobs:
export CXX=clang++
fi
PATH="/github/home/.local/bin:$PATH"
./waf configure --board sitl
./waf configure --board sitl --debug --enable-math-check-indexes
./waf build --target bin/ardurover
ccache -s
ccache -z
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_sitl_sub.yml
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,7 @@ jobs:
export CXX=clang++
fi
PATH="/github/home/.local/bin:$PATH"
./waf configure --board sitl
./waf configure --board sitl --debug
./waf build --target bin/ardusub
ccache -s
ccache -z
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_sitl_tracker.yml
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,7 @@ jobs:
export CXX=clang++
fi
PATH="/github/home/.local/bin:$PATH"
./waf configure --board sitl
./waf configure --board sitl --debug
./waf build --target bin/antennatracker
ccache -s
ccache -z
Expand Down
6 changes: 5 additions & 1 deletion Tools/autotest/autotest.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
import ardusub
import antennatracker
import quadplane
import carbonix
import balancebot
import sailboat
import helicopter
Expand Down Expand Up @@ -282,6 +283,7 @@ def should_run_step(step):
"Tracker": "antennatracker",
"Helicopter": "arducopter-heli",
"QuadPlane": "arduplane",
"Carbonix": "arduplane",
"Sub": "ardusub",
"Blimp": "blimp",
"BalanceBot": "ardurover",
Expand Down Expand Up @@ -352,6 +354,7 @@ def find_specific_test_to_run(step):
"test.CopterTests2b": arducopter.AutoTestCopterTests2b, # 8m18s
"test.Plane": arduplane.AutoTestPlane,
"test.QuadPlane": quadplane.AutoTestQuadPlane,
"test.Carbonix": carbonix.AutoTestCarbonix,
"test.Rover": rover.AutoTestRover,
"test.BalanceBot": balancebot.AutoTestBalanceBot,
"test.Sailboat": sailboat.AutoTestSailboat,
Expand Down Expand Up @@ -772,7 +775,7 @@ def run_tests(steps):
return passed


vehicle_list = ['Sub', 'Copter', 'Plane', 'Tracker', 'Rover', 'QuadPlane', 'BalanceBot', 'Helicopter', 'Sailboat', 'Blimp']
vehicle_list = ['Sub', 'Copter', 'Plane', 'Tracker', 'Rover', 'QuadPlane', 'Carbonix', 'BalanceBot', 'Helicopter', 'Sailboat', 'Blimp'] # noqa: E501


def list_subtests():
Expand Down Expand Up @@ -1064,6 +1067,7 @@ def format_epilog(self, formatter):
'build.Plane',
'test.Plane',
'test.QuadPlane',
'test.Carbonix',

'build.Rover',
'test.Rover',
Expand Down
185 changes: 185 additions & 0 deletions Tools/autotest/carbonix.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,185 @@
'''
Fly Carbonix aircraft in SITL

AP_FLAKE8_CLEAN

'''

from quadplane import AutoTestQuadPlane
from pysim import vehicleinfo
from vehicle_test_suite import AutoTestTimeoutException, NotAchievedException
from cx_vehicle_bundle import copy_frame_scripts


class AutoTestCarbonix(AutoTestQuadPlane):
def init(self):
super().init()
self.install_frame_scripts()
self.reboot_sitl()

def default_parameter_list(self):
return super().default_parameter_list() | {
"ARMING_MIS_ITEMS": 0, # disable mission check
"BRD_SAFETY_DEFLT": 0, # disable safety switch
"FENCE_AUTOENABLE": 0, # disable fences
"FENCE_ENABLE": 0,
"FS_GCS_ENABL": 0, # disable GCS failsafe
"TERRAIN_FOLLOW": 0, # disable terrain follow (causes prearm fail; terrain requests require extra steps)
}

def default_frame(self):
return 'ottano-headless'

def log_name(self):
return 'Carbonix'

def vehicleinfo_key(self):
return 'Carbonix'

def install_frame_scripts(self):
'''installs all scripts specified for the frame in vehicleinfo'''
options = vehicleinfo.VehicleInfo().options[self.vehicleinfo_key()]
frame_bits = options['frames'][self.frame]
script_patterns = frame_bits.get('scripts', [])
scripts_root = self.installed_script_path('')
copy_frame_scripts(self.frame, scripts_root, script_patterns)

def assert_no_text(self, *args, **kwargs):
'''Assert that a text message does not come in within a timeout'''
try:
text = self.wait_text(*args, **kwargs)
except AutoTestTimeoutException:
return
raise AssertionError(f"Text '{text}' appeared")

def CX_BIT(self):
'''Test Carbonix's Built-in-Test (BIT) script'''

def TestESCTelemetry(index):
'''Test a single ESC'''
index = int(index)
self.context_push()
self.context_collect('STATUSTEXT')
self.wait_ready_to_arm()

# Confirm no error messages are present, with one exception:
# "Servo Out nil" is not uncommon when running with simulation
# speedups. There is a race condition that can occur because
# SRV_Channels::function_mask gets periodically cleared and
# re-calculated.
# TODO: CX_BIT needs to switch to checking channel number instead
# of checking by function assignment, but that will take some work
# and will require a new binding.
self.assert_no_text('^CX_BIT:.*(?!Servo Out nil).*', regex=True, check_context=True)

# Fail the ESC telemetry for the specified index
self.progress(f'Failing ESC telemetry for ESC {index}')
self.set_parameter('SIM_ESC_TLM_FAIL', 1 << index)

# Wait for the prearm failure and the error message
self.wait_not_ready_to_arm()
lost_text = f'CX_BIT: ESC {index + 1} Telemetry Lost'
self.wait_text(lost_text, check_context=True)
self.progress("'" + lost_text + "':" + ' Success!')

# Clear the failure
self.progress(f'Clearing ESC telemetry failure for ESC {index}')
self.context_clear_collection('STATUSTEXT')
self.set_parameter('SIM_ESC_TLM_FAIL', 0)
recovered_text = f'CX_BIT: ESC {index + 1} Telemetry Recovered'
self.wait_text(recovered_text, check_context=True)
# Confirm we didn't get lost/recovered/lost/recovered during that time
self.assert_no_text(lost_text, timeout=1, regex=True, check_context=True)

# And one more time, confirm no error messages are present
self.context_clear_collection('STATUSTEXT')
# TODO: clean this line up too when Servo Out nil is fixed
self.assert_no_text('^CX_BIT:.*(?!Servo Out nil).*', regex=True, check_context=True)
self.context_pop()

def TestMotorFail(esc_index, servo_index, is_pusher=False):
'''Test a single VTOL motor failure'''
esc_index = int(esc_index)
servo_index = int(servo_index)
self.context_push()
self.context_collect('STATUSTEXT')
self.wait_ready_to_arm()

self.arm_vehicle()
if is_pusher:
self.change_mode('MANUAL')
self.set_rc(3, 1500)
else:
self.change_mode('QSTABILIZE')

# Confirm no error messages are present
self.assert_no_text('CX_BIT.*', regex=True, check_context=True)

# Fail the ESC telemetry for the specified index
self.progress(f'Failing Motor {esc_index}')
self.set_parameter('SIM_ENGINE_FAIL', 1 << servo_index)

# Wait for the error message
lost_text = f'CX_BIT: ESC {esc_index + 1} RPM Drop'
self.wait_text(lost_text, check_context=True)
self.progress("'" + lost_text + "':" + ' Success!')

# Clear the failure
self.progress(f'Fixing Motor {esc_index}')
self.context_clear_collection('STATUSTEXT')
self.set_parameter('SIM_ENGINE_FAIL', 0)
recovered_text = f'CX_BIT: ESC {esc_index + 1} RPM Recovered'
self.wait_text(recovered_text, check_context=True)
# Confirm we didn't get lost/recovered/lost/recovered during that time
self.assert_no_text(lost_text, timeout=1, regex=True, check_context=True)

# And one more time, confirm no error messages are present
self.context_clear_collection('STATUSTEXT')
self.assert_no_text('CX_BIT.*', regex=True, check_context=True)
self.disarm_vehicle()
self.context_pop()

# Count the number of ESCs
frame_class = self.get_parameter('Q_FRAME_CLASS')
if frame_class == 1: # Quad
num_vtols = 4
elif frame_class == 4: # OctaQuad
num_vtols = 8
else:
raise ValueError(f'Unsupported frame class {frame_class}')
has_engine = self.get_parameter('ICE_ENABLE')

# Find the servo assignments for the ESCs
vtol_servos = {}
pusher_servo = None
for i in range(1, 32):
try:
assignment = self.get_parameter(f'SERVO{i}_FUNCTION')
if 33 <= assignment <= 40:
vtol_servos[assignment - 33] = i - 1
elif assignment == 70:
pusher_servo = i - 1
except NotAchievedException:
break
assert len(vtol_servos) == num_vtols
assert pusher_servo is not None

self.start_subtest('Test ESC telemetry warnings')
for i in range(num_vtols):
TestESCTelemetry(i)
if not has_engine:
TestESCTelemetry(num_vtols) # Test the pusher

self.start_subtest('Test VTOL motor failures')
for i in range(num_vtols):
TestMotorFail(i, vtol_servos[i])
if not has_engine:
TestMotorFail(num_vtols, pusher_servo, is_pusher=True)

def disabled_tests(self):
return dict()

def tests(self):
return [
self.CX_BIT,
]
Loading
Loading