Skip to content
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
50 changes: 50 additions & 0 deletions .github/workflows/python_tests_copter.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
name: Run Python Copter Tests
Comment thread
1Blademaster marked this conversation as resolved.

permissions:
contents: read

on:
push:
branches:
- main
- release-*
paths:
- radio/**
pull_request:
branches:
- main
- release-*
paths:
- radio/**

jobs:
build:
runs-on: ubuntu-latest
services:
service-name-1:
image: kushmakkapati/ardupilot_sitl:latest
env:
VEHICLE: ArduCopter
ports:
- 5760:5760
options: >-
--name ardupilot-copter
steps:
- uses: actions/checkout@v3

- name: Set up Python 3.11
uses: actions/setup-python@v4
with:
python-version: '3.11'

- name: Install dependencies
working-directory: radio
run: |
python -m pip install --upgrade pip
python -m pip install pytest
python -m pip install -r requirements.txt

- name: Test with pytest
working-directory: radio
timeout-minutes: 15
run: pytest -m "not plane_only" --log-cli-level=DEBUG
Comment thread Fixed
Original file line number Diff line number Diff line change
@@ -1,4 +1,7 @@
name: Run Python Tests with simulator
name: Run Python Plane Tests

permissions:
contents: read

on:
push:
Expand All @@ -20,8 +23,12 @@ jobs:
services:
service-name-1:
image: kushmakkapati/ardupilot_sitl:latest
env:
VEHICLE: ArduPlane
ports:
- 5760:5760
options: >-
--name ardupilot-plane
steps:
- uses: actions/checkout@v3

Expand All @@ -40,4 +47,4 @@ jobs:
- name: Test with pytest
working-directory: radio
timeout-minutes: 15
run: pytest --log-cli-level=DEBUG
run: pytest -m "not copter_only" --log-cli-level=DEBUG
31 changes: 31 additions & 0 deletions radio/tests/conftest.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,16 @@
from app.utils import getComPort


def pytest_configure(config):
"""Register custom markers"""
config.addinivalue_line(
"markers", "plane_only: mark test to run only on plane SITL"
)
config.addinivalue_line(
"markers", "copter_only: mark test to run only on copter SITL"
)


def setupDrone(connectionString: str) -> bool:
"""
Setup the drone globally, this is done before running pytest
Expand Down Expand Up @@ -47,3 +57,24 @@ def pytest_sessionstart(session):
if not success:
print("\033[1;31;40mFAILED TO CONNECT TO DRONE, EXITING TESTS\033[0m")
pytest.exit(1)


@pytest.fixture(autouse=True)
def check_aircraft_type(request):
"""Fixture to skip tests based on aircraft type markers"""

markers = [marker.name for marker in request.node.iter_markers()]

if droneStatus.drone is None:
pytest.skip("No drone connected")
return

aircraft_type = droneStatus.drone.aircraft_type

# Skip if marked as plane_only but not a plane
if "plane_only" in markers and aircraft_type != 1:
pytest.skip(f"Test requires plane SITL (current type: {aircraft_type})")

# Skip if marked as copter_only but not a copter
if "copter_only" in markers and aircraft_type != 2:
pytest.skip(f"Test requires copter SITL (current type: {aircraft_type})")
18 changes: 2 additions & 16 deletions radio/tests/helpers.py
Original file line number Diff line number Diff line change
Expand Up @@ -90,20 +90,6 @@ def __exit__(self, type, value, traceback) -> None:
droneStatus.drone.wait_for_message = self.wait_for_message # type: ignore[method-assign]


class SetAircraftType:
def __init__(self, aircraftType: int):
self.aircraftType = aircraftType

def __enter__(self) -> None:
if droneStatus.drone is not None:
self.old_aircraftType = droneStatus.drone.aircraft_type
droneStatus.drone.aircraft_type = self.aircraftType

def __exit__(self, type, value, traceback) -> None:
if droneStatus.drone is not None:
droneStatus.drone.aircraft_type = self.old_aircraftType


def send_and_receive(endpoint: str, args: Optional[Union[dict, str]] = None) -> dict:
"""Sends a request to the socketio test client and returns the response

Expand Down Expand Up @@ -151,7 +137,7 @@ def set_params(params: List[tuple[str, Number, int]]) -> None:

for param in params:
param_name, param_value, param_type = param
max_retries = 5
max_retries = 7
retry_count = 0
param_set_successfully = False

Expand Down Expand Up @@ -212,7 +198,7 @@ def set_params(params: List[tuple[str, Number, int]]) -> None:
# Timeout occurred
retry_count += 1
if retry_count < max_retries:
backoff_delay = 0.1 * (2**retry_count) # Exponential backoff
backoff_delay = 0.2 * (2**retry_count) # Exponential backoff
logger.warning(
f"Timeout setting {param_name}, retrying in {backoff_delay:.1f}s... ({retry_count}/{max_retries})"
)
Expand Down
98 changes: 55 additions & 43 deletions radio/tests/test_FlightModesController.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
from . import falcon_test
from .helpers import (
FakeTCP,
SetAircraftType,
WaitForMessageReturnsNone,
)

Expand Down Expand Up @@ -96,7 +95,7 @@ def test_setCurrentFlightMode(client: SocketIOTestClient, droneStatus):


@falcon_test(pass_drone_status=True)
def test_setFlightMode(client: SocketIOTestClient, droneStatus):
def test_setFlightMode_invalidData(client: SocketIOTestClient, droneStatus):
response = droneStatus.drone.flightModesController.setFlightMode(0, 1)
assert response == {
"success": False,
Expand All @@ -121,57 +120,70 @@ def test_setFlightMode(client: SocketIOTestClient, droneStatus):
"message": "Invalid flight mode number, must be between 1 and 6 inclusive, got 100.",
}

# TODO: Fix imitation of PLANE type while being on COPTER sim, should use a different simulator ideally.
with SetAircraftType(1):
response = droneStatus.drone.flightModesController.setFlightMode(1, -2)
assert response == {
"success": False,
"message": "Invalid plane flight mode, must be between 0 and 24 inclusive, got -2",
}

response = droneStatus.drone.flightModesController.setFlightMode(1, 25)
@pytest.mark.copter_only
@falcon_test(pass_drone_status=True)
def test_setFlightMode_invalidData_copter(client: SocketIOTestClient, droneStatus):
response = droneStatus.drone.flightModesController.setFlightMode(1, -2)
assert response == {
"success": False,
"message": "Invalid copter flight mode, must be between 0 and 27 inclusive, got -2",
}

response = droneStatus.drone.flightModesController.setFlightMode(1, 28)
assert response == {
"success": False,
"message": "Invalid copter flight mode, must be between 0 and 27 inclusive, got 28",
}

with WaitForMessageReturnsNone():
response = droneStatus.drone.flightModesController.setFlightMode(1, 1)
assert response == {
"success": False,
"message": "Invalid plane flight mode, must be between 0 and 24 inclusive, got 25",
"message": "Failed to set flight mode 1 to COPTER_MODE_ACRO",
}

with WaitForMessageReturnsNone():
response = droneStatus.drone.flightModesController.setFlightMode(1, 1)
assert response == {
"success": False,
"message": "Failed to set flight mode 1 to PLANE_MODE_CIRCLE",
}

response = droneStatus.drone.flightModesController.setFlightMode(1, 24)
assert response == {
"success": True,
"message": "Flight mode 1 set to PLANE_MODE_THERMAL",
}
assert droneStatus.drone.flightModesController.flight_modes[0] == 24
@pytest.mark.copter_only
@falcon_test(pass_drone_status=True)
def test_setFlightMode_success_copter(client: SocketIOTestClient, droneStatus):
response = droneStatus.drone.flightModesController.setFlightMode(1, 5)
assert response == {
"success": True,
"message": "Flight mode 1 set to COPTER_MODE_LOITER",
}
assert droneStatus.drone.flightModesController.flight_modes[0] == 5

with SetAircraftType(2):
response = droneStatus.drone.flightModesController.setFlightMode(1, -2)
assert response == {
"success": False,
"message": "Invalid copter flight mode, must be between 0 and 27 inclusive, got -2",
}

response = droneStatus.drone.flightModesController.setFlightMode(1, 28)
@pytest.mark.plane_only
@falcon_test(pass_drone_status=True)
def test_setFlightMode_invalidData_plane(client: SocketIOTestClient, droneStatus):
response = droneStatus.drone.flightModesController.setFlightMode(1, -2)
assert response == {
"success": False,
"message": "Invalid plane flight mode, must be between 0 and 24 inclusive, got -2",
}

response = droneStatus.drone.flightModesController.setFlightMode(1, 25)
assert response == {
"success": False,
"message": "Invalid plane flight mode, must be between 0 and 24 inclusive, got 25",
}

with WaitForMessageReturnsNone():
response = droneStatus.drone.flightModesController.setFlightMode(1, 1)
assert response == {
"success": False,
"message": "Invalid copter flight mode, must be between 0 and 27 inclusive, got 28",
"message": "Failed to set flight mode 1 to PLANE_MODE_CIRCLE",
}

with WaitForMessageReturnsNone():
response = droneStatus.drone.flightModesController.setFlightMode(1, 1)
assert response == {
"success": False,
"message": "Failed to set flight mode 1 to COPTER_MODE_ACRO",
}

response = droneStatus.drone.flightModesController.setFlightMode(1, 27)
assert response == {
"success": True,
"message": "Flight mode 1 set to COPTER_MODE_AUTO_RTL",
}
assert droneStatus.drone.flightModesController.flight_modes[0] == 27
@pytest.mark.plane_only
@falcon_test(pass_drone_status=True)
def test_setFlightMode_success_plane(client: SocketIOTestClient, droneStatus):
response = droneStatus.drone.flightModesController.setFlightMode(1, 5)
assert response == {
"success": True,
"message": "Flight mode 1 set to PLANE_MODE_FLY_BY_WIRE_A",
}
assert droneStatus.drone.flightModesController.flight_modes[0] == 5