Skip to content

Commit 4d5b110

Browse files
authored
Update states tests, reset message listeners on state change (#870)
1 parent 1d3bb2d commit 4d5b110

3 files changed

Lines changed: 53 additions & 14 deletions

File tree

radio/app/drone.py

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -522,6 +522,10 @@ def removeMessageListener(self, message_id: str) -> bool:
522522
return True
523523
return False
524524

525+
def clearAllMessageListeners(self) -> None:
526+
"""Clears all message listeners."""
527+
self.message_listeners.clear()
528+
525529
def reserve_message_type(self, message_type: str, controller_id: str) -> bool:
526530
"""Reserve a message type for exclusive controller use.
527531
@@ -1173,8 +1177,7 @@ def stopForwarding(self) -> Response:
11731177
def close(self) -> None:
11741178
"""Close the connection to the drone."""
11751179
self.logger.info(f"Cleaning up resources for drone at {self}")
1176-
for message_id in copy.deepcopy(self.message_listeners):
1177-
self.removeMessageListener(message_id)
1180+
self.clearAllMessageListeners()
11781181

11791182
self.is_active.clear()
11801183

radio/app/endpoints/states.py

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -64,6 +64,9 @@ def set_state(data: SetStateType) -> None:
6464
# Reset all data streams
6565
droneStatus.drone.stopAllDataStreams()
6666

67+
# Remove all existing message listeners
68+
droneStatus.drone.clearAllMessageListeners()
69+
6770
# Always setup position stream to get GLOBAL_POSITION_INT messages
6871
droneStatus.drone.setupSingleDataStream(mavutil.mavlink.MAV_DATA_STREAM_POSITION)
6972

radio/tests/test_states.py

Lines changed: 45 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -5,48 +5,81 @@
55

66

77
@falcon_test(pass_drone_status=True)
8-
def test_setState(socketio_client: SocketIOTestClient, droneStatus) -> None:
9-
# Failure on no drone connection
8+
def test_setState_no_drone_connection(
9+
socketio_client: SocketIOTestClient, droneStatus
10+
) -> None:
11+
"""Test that setState fails when no drone is connected"""
1012
with NoDrone():
1113
assert send_and_receive("set_state", "dashboard") == {
1214
"message": "Must be connected to the drone to set the drone state."
1315
}
1416

15-
# Failure on no state sent
17+
18+
@falcon_test(pass_drone_status=True)
19+
def test_setState_missing_state_parameter(
20+
socketio_client: SocketIOTestClient, droneStatus
21+
) -> None:
22+
"""Test that setState fails when state parameter is missing"""
1623
assert send_and_receive("set_state", {}) == {
1724
"message": "Request to endpoint set_state missing value for parameter: state."
1825
}
1926

20-
# TODO: These values don't seem right to me, they don't include the STATUSTEXT listener?
2127

22-
# Success on changing state to dashboard
28+
@falcon_test(pass_drone_status=True)
29+
def test_setState_dashboard_state(
30+
socketio_client: SocketIOTestClient, droneStatus
31+
) -> None:
32+
"""Test setting state to dashboard"""
2333
socketio_client.emit("set_state", {"state": "dashboard"})
2434
assert len(socketio_client.get_received()) == 0
35+
# TODO: These values don't seem right to me, they don't include the STATUSTEXT listener?
2536
assert len(droneStatus.drone.message_listeners) == 15
2637

38+
39+
@falcon_test(pass_drone_status=True)
40+
def test_setState_graphs_state(
41+
socketio_client: SocketIOTestClient, droneStatus
42+
) -> None:
43+
"""Test setting state to graphs"""
2744
droneStatus.drone.message_listeners = {}
2845

2946
socketio_client.emit("set_state", {"state": "graphs"})
3047
assert len(socketio_client.get_received()) == 0
3148
assert len(droneStatus.drone.message_listeners) == 6
3249

50+
51+
@falcon_test(pass_drone_status=True)
52+
def test_setState_config_flight_modes_state(
53+
socketio_client: SocketIOTestClient, droneStatus
54+
) -> None:
55+
"""Test setting state to config.flight_modes"""
3356
droneStatus.drone.message_listeners = {}
3457

3558
socketio_client.emit("set_state", {"state": "config.flight_modes"})
3659
assert len(socketio_client.get_received()) == 0
3760
assert len(droneStatus.drone.message_listeners) == 4
3861

62+
63+
@falcon_test(pass_drone_status=True)
64+
def test_setState_config_rc_state(
65+
socketio_client: SocketIOTestClient, droneStatus
66+
) -> None:
67+
"""Test setting state to config.rc"""
3968
droneStatus.drone.message_listeners = {}
4069

4170
socketio_client.emit("set_state", {"state": "config.rc"})
4271
assert len(socketio_client.get_received()) == 0
4372
assert len(droneStatus.drone.message_listeners) == 4
4473

45-
droneStatus.drone.message_listeners = {}
4674

47-
# TODO: Sort this out
48-
# pytest.skip(reason="Issues with parameterController to be fixed in alpha 0.1.8")
49-
# socketio_client.emit("set_state", {"state": "params"})
50-
# time.sleep(15)
51-
# assert len(socketio_client.get_received()[-1]["args"][0]) == 1400
52-
# assert len(droneStatus.drone.message_listeners) == 1
75+
# TODO: Sort this out
76+
# @falcon_test(pass_drone_status=True)
77+
# def test_setState_params_state(socketio_client: SocketIOTestClient, droneStatus) -> None:
78+
# """Test setting state to params"""
79+
# # pytest.skip(reason="Issues with parameterController to be fixed in alpha 0.1.8")
80+
# droneStatus.drone.message_listeners = {}
81+
#
82+
# socketio_client.emit("set_state", {"state": "params"})
83+
# time.sleep(15)
84+
# assert len(socketio_client.get_received()[-1]["args"][0]) == 1400
85+
# assert len(droneStatus.drone.message_listeners) == 1

0 commit comments

Comments
 (0)