diff --git a/.github/workflows/python_tests.yml b/.github/workflows/python_tests.yml
index fd73e0357..7df579b46 100644
--- a/.github/workflows/python_tests.yml
+++ b/.github/workflows/python_tests.yml
@@ -28,7 +28,7 @@ jobs:
- name: Set up Python 3.11
uses: actions/setup-python@v4
with:
- python-version: "3.11"
+ python-version: '3.11'
- name: Install dependencies
working-directory: radio
@@ -39,4 +39,5 @@ jobs:
- name: Test with pytest
working-directory: radio
+ timeout-minutes: 25
run: pytest --log-cli-level=DEBUG
diff --git a/gcs/src/components/dashboard/statusMessages.jsx b/gcs/src/components/dashboard/statusMessages.jsx
index d6655e9e5..89df73d8e 100644
--- a/gcs/src/components/dashboard/statusMessages.jsx
+++ b/gcs/src/components/dashboard/statusMessages.jsx
@@ -68,9 +68,11 @@ export default function StatusMessages(props) {
key={index}
className={getMessageOutsideVisibilityClassNames()}
>
-
- {moment.unix(message.timestamp).format("HH:mm:ss")}
-
+ {message.timestamp !== null && (
+
+ {moment.unix(message.timestamp).format("HH:mm:ss")}
+
+ )}
{message.text}
diff --git a/gcs/src/dashboard.jsx b/gcs/src/dashboard.jsx
index fdc080a95..68dc2bc44 100644
--- a/gcs/src/dashboard.jsx
+++ b/gcs/src/dashboard.jsx
@@ -236,45 +236,45 @@ export default function Dashboard() {
{/* Video Widget for RTSP streams */}
- {connectedToDrone && (
-
-
(
-
- )}
- handleSize={[32, 32]}
- onResize={(_, { size }) => {
- setMessagesPanelSize({ width: size.width, height: size.height })
- }}
- >
- <>
- {/* Show a "Waiting for message area" */}
- {statustextMessages.length == 0 && (
-
- )}
- {/* Show real messages */}
+
+ (
+
+ )}
+ handleSize={[32, 32]}
+ onResize={(_, { size }) => {
+ setMessagesPanelSize({ width: size.width, height: size.height })
+ }}
+ >
+ <>
+ {/* Show a "Waiting for message area" */}
+ {statustextMessages.length == 0 && (
- >
-
-
- )}
+ )}
+ {/* Show real messages */}
+
+ >
+
+
)
diff --git a/gcs/src/redux/middleware/socketMiddleware.js b/gcs/src/redux/middleware/socketMiddleware.js
index 0d07608d7..666b43be1 100644
--- a/gcs/src/redux/middleware/socketMiddleware.js
+++ b/gcs/src/redux/middleware/socketMiddleware.js
@@ -55,6 +55,7 @@ import {
setDroneAircraftType,
setEkfStatusReportData,
setExtraData,
+ setFlightSwVersion,
setGpsData,
setGpsRawIntData,
setGuidedModePinData,
@@ -97,7 +98,7 @@ import {
setShownParams,
updateParamValue,
} from "../slices/paramsSlice.js"
-import { pushMessage } from "../slices/statusTextSlice.js"
+import { pushMessage, resetMessages } from "../slices/statusTextSlice.js"
import { handleEmitters } from "./emitters.js"
const SocketEvents = Object.freeze({
@@ -341,6 +342,8 @@ const socketMiddleware = (store) => {
if (msg.aircraft_type !== 1 && msg.aircraft_type !== 2) {
showErrorNotification("Aircraft not of type quadcopter or plane")
}
+
+ store.dispatch(setFlightSwVersion(msg.flight_sw_version))
store.dispatch(setConnected(true))
store.dispatch(setConnecting(false))
store.dispatch(setConnectionModal(false))
@@ -351,6 +354,7 @@ const socketMiddleware = (store) => {
store.dispatch(setAutoPilotRebootModalOpen(false))
store.dispatch(setShouldFetchAllMissionsOnDashboard(true))
store.dispatch(setShowMotorTestWarningModal(true))
+ store.dispatch(resetMessages())
})
// Link stats
diff --git a/gcs/src/redux/slices/droneInfoSlice.js b/gcs/src/redux/slices/droneInfoSlice.js
index bb7b8bcfe..859f13814 100644
--- a/gcs/src/redux/slices/droneInfoSlice.js
+++ b/gcs/src/redux/slices/droneInfoSlice.js
@@ -9,6 +9,7 @@ import {
const droneInfoSlice = createSlice({
name: "droneInfo",
initialState: {
+ flightSwVersion: "",
attitudeData: {
roll: 0.0,
pitch: 0.0,
@@ -85,6 +86,9 @@ const droneInfoSlice = createSlice({
},
},
reducers: {
+ setFlightSwVersion: (state, action) => {
+ state.flightSwVersion = action.payload
+ },
setHeartbeatData: (state, action) => {
if (
action.payload.base_mode & 128 &&
@@ -225,6 +229,8 @@ const droneInfoSlice = createSlice({
},
},
selectors: {
+ selectFlightSwVersion: (state) => state.flightSwVersion,
+
selectAttitude: (state) => state.attitudeData,
selectTelemetry: (state) => state.telemetryData,
@@ -263,6 +269,7 @@ const droneInfoSlice = createSlice({
})
export const {
+ setFlightSwVersion,
setHeartbeatData,
soundPlayed,
changeExtraData,
@@ -335,6 +342,7 @@ export const selectFlightModeString = createSelector(
)
export const {
+ selectFlightSwVersion,
selectAttitude,
selectTelemetry,
selectGPS,
diff --git a/gcs/src/redux/slices/statusTextSlice.js b/gcs/src/redux/slices/statusTextSlice.js
index d916906b8..917e217d7 100644
--- a/gcs/src/redux/slices/statusTextSlice.js
+++ b/gcs/src/redux/slices/statusTextSlice.js
@@ -7,6 +7,9 @@ const statusTextSlice = createSlice({
pushMessage: (state, action) => {
state.messages.unshift(action.payload)
},
+ resetMessages: (state) => {
+ state.messages = []
+ },
},
selectors: {
selectMessages: (state) => {
@@ -15,7 +18,7 @@ const statusTextSlice = createSlice({
},
})
-export const { pushMessage } = statusTextSlice.actions
+export const { pushMessage, resetMessages } = statusTextSlice.actions
export const { selectMessages } = statusTextSlice.selectors
export default statusTextSlice
diff --git a/radio/app/drone.py b/radio/app/drone.py
index e13af736b..f64936f92 100644
--- a/radio/app/drone.py
+++ b/radio/app/drone.py
@@ -24,7 +24,13 @@
from app.controllers.paramsController import ParamsController
from app.controllers.rcController import RcController
from app.customTypes import Number, Response, VehicleType
-from app.utils import commandAccepted, getVehicleType, sendingCommandLock
+from app.utils import (
+ commandAccepted,
+ decodeFlightSwVersion,
+ getFlightSwVersionString,
+ getVehicleType,
+ sendingCommandLock,
+)
# Constants
@@ -127,7 +133,13 @@ def __init__(
try:
self.sendConnectionStatusUpdate(0)
- self.master: mavutil.mavserial = mavutil.mavlink_connection(port, baud=baud)
+ # Source system and component set to GCS values
+ self.master: mavutil.mavserial = mavutil.mavlink_connection(
+ port,
+ baud=baud,
+ source_system=255,
+ source_component=mavutil.mavlink.MAV_COMP_ID_MISSIONPLANNER,
+ )
except Exception as e:
self.logger.exception(traceback.format_exc())
self.master = None
@@ -175,6 +187,7 @@ def __init__(
self.message_listeners: Dict[str, Callable] = {}
self.message_queue: Queue = Queue()
self.log_message_queue: Queue = Queue()
+
self.log_directory = Path.home().joinpath("FGCS", "logs")
self.log_directory.mkdir(parents=True, exist_ok=True)
self.current_log_file: Optional[Path] = None
@@ -183,12 +196,43 @@ def __init__(
self.sendConnectionStatusUpdate(2)
- self.is_active = Event()
- self.is_active.set()
- self.is_listening = False
+ # To ensure that only one command is sent at a time and we wait for a
+ # response before sending another command, a thread-safe lock is used
+ self.sending_command_lock = Lock()
self.forwarding_address: Optional[str] = None
self.forwarding_connection: Optional[mavutil.mavlink_connection] = None
+
+ self.is_active = Event()
+ self.is_active.set()
+ self.is_listening: bool = False
+
+ self.armed = False
+ self.capabilities: Optional[list[str]] = None
+ self.flight_sw_version: Optional[tuple[int, int, int, int]] = None
+
+ self.getAutopilotVersion()
+
+ if self.flight_sw_version is None:
+ self.logger.error("Could not determine flight software version")
+ self.master.close()
+ self.master = None
+ self.connectionError = "Could not determine flight software version"
+ return
+
+ self.logger.info(
+ f"Flight software version: {getFlightSwVersionString(self.flight_sw_version)}"
+ )
+
+ if self.flight_sw_version[0] != 4:
+ self.logger.error("Unsupported flight software version")
+ self.master.close()
+ self.master = None
+ self.connectionError = f"Unsupported flight software version {getFlightSwVersionString(self.flight_sw_version)}. Only version 4.x.x is supported."
+ return
+
+ self.stopAllDataStreams()
+
if forwarding_address is not None:
try:
start_forwarding_result = self.startForwardingToAddress(
@@ -201,12 +245,25 @@ def __init__(
except Exception as e:
self.logger.error(f"Failed to start forwarding: {e}", exc_info=True)
- # To ensure that only one command is sent at a time and we wait for a
- # response before sending another command, a thread-safe lock is used
- self.sending_command_lock = Lock()
+ self.setupControllers()
- self.armed = False
+ self.is_listening = True
+
+ self.startThread()
+
+ self.sendConnectionStatusUpdate(12)
+
+ self.sendStatusTextMessage(
+ mavutil.mavlink.MAV_SEVERITY_INFO, "FGCS connected to aircraft"
+ )
+
+ def __getNextLogFilePath(self, line: str) -> str:
+ return line.split("==NEXT_FILE==")[-1].split("==END==")[0]
+ def __getCurrentDateTimeStr(self) -> str:
+ return time.strftime("%Y-%m-%d_%H-%M-%S", time.localtime())
+
+ def setupControllers(self) -> None:
self.sendConnectionStatusUpdate(3)
self.paramsController = ParamsController(self)
@@ -234,20 +291,6 @@ def __init__(
self.sendConnectionStatusUpdate(11)
self.navController = NavController(self)
- self.stopAllDataStreams()
-
- self.is_listening = True
-
- self.startThread()
-
- self.sendConnectionStatusUpdate(12)
-
- def __getNextLogFilePath(self, line: str) -> str:
- return line.split("==NEXT_FILE==")[-1].split("==END==")[0]
-
- def __getCurrentDateTimeStr(self) -> str:
- return time.strftime("%Y-%m-%d_%H-%M-%S", time.localtime())
-
def sendConnectionStatusUpdate(self, msg_index):
total_msgs = len(self.connection_phases)
if msg_index < 0 or msg_index >= total_msgs:
@@ -698,7 +741,7 @@ def sendHeartbeatMessage(self) -> None:
mavutil.mavlink.MAV_AUTOPILOT_INVALID,
0,
0,
- 0,
+ mavutil.mavlink.MAV_STATE_ACTIVE,
)
except Exception as e:
self.logger.error(f"Failed to send heartbeat: {e}", exc_info=True)
@@ -741,6 +784,47 @@ def stopAllThreads(self) -> None:
if thread is not None and thread.is_alive() and thread is not this_thread:
thread.join(timeout=3)
+ @sendingCommandLock
+ def getAutopilotVersion(self) -> None:
+ """Get the autopilot version."""
+ was_listening = self.is_listening
+ self.is_listening = False
+
+ self.sendCommand(
+ mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE,
+ param1=mavutil.mavlink.MAVLINK_MSG_ID_AUTOPILOT_VERSION,
+ )
+
+ try:
+ response = self.master.recv_match(
+ type="AUTOPILOT_VERSION", blocking=True, timeout=5
+ )
+ if was_listening:
+ self.is_listening = True
+
+ if response is None:
+ self.logger.error("Failed to get autopilot version: Timeout")
+ return
+
+ capabilities = getattr(response, "capabilities", None)
+ if capabilities is not None:
+ # Decode capabilities bitmask into list of capability names
+ capabilities_map = mavutil.mavlink.enums["MAV_PROTOCOL_CAPABILITY"]
+ self.capabilities = []
+ for capability_value, capability_enum in capabilities_map.items():
+ if capabilities & capability_value:
+ self.capabilities.append(capability_enum.name)
+
+ flight_sw_version = getattr(response, "flight_sw_version", None)
+ if flight_sw_version is not None:
+ self.flight_sw_version = decodeFlightSwVersion(flight_sw_version)
+
+ except serial.serialutil.SerialException:
+ if was_listening:
+ self.is_listening = True
+
+ self.logger.error("Failed to get autopilot version due to serial exception")
+
def rebootAutopilot(self) -> None:
"""Reboot the autopilot."""
self.is_listening = False
@@ -909,6 +993,18 @@ def sendCommandInt(
z,
)
+ def sendStatusTextMessage(self, severity: int, text: str) -> None:
+ """Send a status text message to the drone.
+
+ Args:
+ severity (int): The severity of the message
+ text (str): The text of the message
+ """
+ max_len = 50
+ for i in range(0, len(text), max_len):
+ chunk = text[i : i + max_len]
+ self.master.mav.statustext_send(severity, chunk.encode("utf-8"))
+
def startForwardingToAddress(self, address: str) -> Response:
"""Start forwarding MAVLink messages to a specific address.
diff --git a/radio/app/endpoints/comPorts.py b/radio/app/endpoints/comPorts.py
index 2ac7a97d7..e0c054416 100644
--- a/radio/app/endpoints/comPorts.py
+++ b/radio/app/endpoints/comPorts.py
@@ -8,7 +8,12 @@
import app.droneStatus as droneStatus
from app import logger, socketio
from app.drone import Drone
-from app.utils import droneConnectStatusCb, droneErrorCb, getComPortNames
+from app.utils import (
+ droneConnectStatusCb,
+ droneErrorCb,
+ getComPortNames,
+ getFlightSwVersionString,
+)
class ConnectionDataType(TypedDict):
@@ -150,7 +155,13 @@ def connectToDrone(data: ConnectionDataType) -> None:
# Sleeping for buffer time, if errors occur try changing back to 1 second
time.sleep(0.2)
logger.debug("Created drone instance")
- socketio.emit("connected_to_drone", {"aircraft_type": drone.aircraft_type})
+ socketio.emit(
+ "connected_to_drone",
+ {
+ "aircraft_type": drone.aircraft_type,
+ "flight_sw_version": getFlightSwVersionString(drone.flight_sw_version),
+ },
+ )
@socketio.on("disconnect_from_drone")
diff --git a/radio/app/endpoints/states.py b/radio/app/endpoints/states.py
index 22268647f..77a535940 100644
--- a/radio/app/endpoints/states.py
+++ b/radio/app/endpoints/states.py
@@ -40,7 +40,6 @@ def set_state(data: SetStateType) -> None:
"ALTITUDE",
"NAV_CONTROLLER_OUTPUT",
"HEARTBEAT",
- "STATUSTEXT",
"SYS_STATUS",
"GPS_RAW_INT",
"RC_CHANNELS",
@@ -57,6 +56,9 @@ def set_state(data: SetStateType) -> None:
droneStatus.drone.logger.info(f"Changing state to {droneStatus.state}")
+ # Always send STATUSTEXT messages
+ droneStatus.drone.addMessageListener("STATUSTEXT", sendMessage)
+
if droneStatus.state == "dashboard":
droneStatus.drone.setupDataStreams()
for message in message_listeners["dashboard"]:
diff --git a/radio/app/utils.py b/radio/app/utils.py
index 428f67aea..49c42a071 100644
--- a/radio/app/utils.py
+++ b/radio/app/utils.py
@@ -1,5 +1,5 @@
import sys
-from typing import Any, List
+from typing import Any, List, Optional
from pymavlink import mavutil
from serial.tools import list_ports
@@ -235,3 +235,36 @@ def wrapper(self, *args, **kwargs):
lock.release()
return wrapper
+
+
+def decodeFlightSwVersion(v: Optional[int]) -> Optional[tuple[int, int, int, int]]:
+ """
+ Decode a packed uint32 flight_sw_version into major.minor.patch and extra byte.
+ Format (conventional MAVLink): [major:8][minor:8][patch:8][extra:8]
+ Returns:
+ A tuple of (major, minor, patch, extra) or None if input is None
+ """
+ if v is None:
+ return None
+ v &= 0xFFFFFFFF
+ major = (v >> 24) & 0xFF
+ minor = (v >> 16) & 0xFF
+ patch = (v >> 8) & 0xFF
+ extra = v & 0xFF
+
+ return (major, minor, patch, extra)
+
+
+def getFlightSwVersionString(v: Optional[tuple[int, int, int, int]]) -> str:
+ """
+ Convert flight_sw_version tuple into a human-readable string.
+ """
+ if v is None:
+ return ""
+
+ major, minor, patch, extra = v
+
+ if extra != 0:
+ return f"{major}.{minor}.{patch} ({extra:02x})"
+ else:
+ return f"{major}.{minor}.{patch}"
diff --git a/radio/tests/__init__.py b/radio/tests/__init__.py
index 7067fb000..9842c6ce7 100644
--- a/radio/tests/__init__.py
+++ b/radio/tests/__init__.py
@@ -9,6 +9,19 @@
app = create_app(debug=True)
socketio = socketio
+
+@socketio.on("incoming_msg")
+def ignore_incoming_msg(data):
+ """Silently ignore telemetry incoming_msg events during testing"""
+ pass
+
+
+@socketio.on("link_debug_stats")
+def ignore_link_debug_stats(data):
+ """Silently ignore link_debug_stats events during testing"""
+ pass
+
+
# Create flask/socketio clients to be used in tests
flask_client: FlaskClient = app.test_client()
socketio_client: SocketIOTestClient = socketio.test_client(
diff --git a/radio/tests/mission_test_files/test_getCurrentMission_correctFence_result.json b/radio/tests/mission_test_files/test_getCurrentMission_correctFence_result.json
index 519cba6d4..725291dd2 100644
--- a/radio/tests/mission_test_files/test_getCurrentMission_correctFence_result.json
+++ b/radio/tests/mission_test_files/test_getCurrentMission_correctFence_result.json
@@ -14,7 +14,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 0,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527814618,
"y": -7105708,
@@ -32,7 +32,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 1,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527810530,
"y": -7102918,
@@ -50,7 +50,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 2,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527800342,
"y": -7108390,
@@ -68,7 +68,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 3,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527818512,
"y": -7035434,
@@ -86,7 +86,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 4,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527830582,
"y": -7060110,
@@ -104,7 +104,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 5,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527825456,
"y": -7081568,
@@ -122,7 +122,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 6,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527796578,
"y": -7092163,
@@ -140,7 +140,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 7,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527801900,
"y": -7044017,
@@ -158,7 +158,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 8,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527828246,
"y": -7061076,
@@ -176,7 +176,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 9,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527818707,
"y": -7041549,
@@ -194,7 +194,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 10,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527814489,
"y": -7058179,
@@ -212,7 +212,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 11,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527821887,
"y": -7058072,
@@ -230,7 +230,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 12,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527826364,
"y": -7068908,
diff --git a/radio/tests/mission_test_files/test_getCurrentMission_correctMission_result.json b/radio/tests/mission_test_files/test_getCurrentMission_correctMission_result.json
index 0e860cbab..017a018a1 100644
--- a/radio/tests/mission_test_files/test_getCurrentMission_correctMission_result.json
+++ b/radio/tests/mission_test_files/test_getCurrentMission_correctMission_result.json
@@ -14,7 +14,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 0,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527805690,
"y": -7079236,
@@ -23,7 +23,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 1,
"frame": 3,
"command": 22,
@@ -41,7 +41,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 2,
"frame": 3,
"command": 16,
@@ -59,7 +59,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 3,
"frame": 3,
"command": 16,
@@ -77,7 +77,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 4,
"frame": 3,
"command": 16,
@@ -95,7 +95,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 5,
"frame": 3,
"command": 16,
@@ -113,7 +113,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 6,
"frame": 3,
"command": 16,
@@ -131,7 +131,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 7,
"frame": 3,
"command": 21,
diff --git a/radio/tests/mission_test_files/test_getCurrentMission_correctRally_result.json b/radio/tests/mission_test_files/test_getCurrentMission_correctRally_result.json
index 0fcfa133a..a0dede69e 100644
--- a/radio/tests/mission_test_files/test_getCurrentMission_correctRally_result.json
+++ b/radio/tests/mission_test_files/test_getCurrentMission_correctRally_result.json
@@ -14,7 +14,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 0,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527810011,
"y": -7094872,
@@ -32,7 +32,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 1,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527821108,
"y": -7056785,
diff --git a/radio/tests/mission_test_files/test_getCurrentMission_correctState_result.json b/radio/tests/mission_test_files/test_getCurrentMission_correctState_result.json
index d0ef6a991..1bff5b12f 100644
--- a/radio/tests/mission_test_files/test_getCurrentMission_correctState_result.json
+++ b/radio/tests/mission_test_files/test_getCurrentMission_correctState_result.json
@@ -13,7 +13,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 0,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527805690,
"y": -7079236,
@@ -22,7 +22,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 1,
"frame": 3,
"command": 22,
@@ -40,7 +40,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 2,
"frame": 3,
"command": 16,
@@ -58,7 +58,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 3,
"frame": 3,
"command": 16,
@@ -76,7 +76,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 4,
"frame": 3,
"command": 16,
@@ -94,7 +94,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 5,
"frame": 3,
"command": 16,
@@ -112,7 +112,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 6,
"frame": 3,
"command": 16,
@@ -130,7 +130,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 7,
"frame": 3,
"command": 21,
@@ -159,7 +159,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 0,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527814618,
"y": -7105708,
@@ -177,7 +177,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 1,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527810530,
"y": -7102918,
@@ -195,7 +195,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 2,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527800342,
"y": -7108390,
@@ -213,7 +213,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 3,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527818512,
"y": -7035434,
@@ -231,7 +231,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 4,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527830582,
"y": -7060110,
@@ -249,7 +249,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 5,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527825456,
"y": -7081568,
@@ -267,7 +267,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 6,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527796578,
"y": -7092163,
@@ -285,7 +285,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 7,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527801900,
"y": -7044017,
@@ -303,7 +303,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 8,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527828246,
"y": -7061076,
@@ -321,7 +321,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 9,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527818707,
"y": -7041549,
@@ -339,7 +339,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 10,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527814489,
"y": -7058179,
@@ -357,7 +357,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 11,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527821887,
"y": -7058072,
@@ -375,7 +375,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 12,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527826364,
"y": -7068908,
@@ -395,7 +395,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 0,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527810011,
"y": -7094872,
@@ -413,7 +413,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 1,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527821108,
"y": -7056785,
diff --git a/radio/tests/mission_test_files/test_writeCurrentMission_uploadFenceSuccess_data.json b/radio/tests/mission_test_files/test_writeCurrentMission_uploadFenceSuccess_data.json
index 460a0305f..21d225173 100644
--- a/radio/tests/mission_test_files/test_writeCurrentMission_uploadFenceSuccess_data.json
+++ b/radio/tests/mission_test_files/test_writeCurrentMission_uploadFenceSuccess_data.json
@@ -13,7 +13,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 0,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527814618,
"y": -7105708,
@@ -31,7 +31,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 1,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527810530,
"y": -7102918,
@@ -49,7 +49,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 2,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527800342,
"y": -7108390,
@@ -67,7 +67,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 3,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527818512,
"y": -7035434,
@@ -85,7 +85,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 4,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527830582,
"y": -7060110,
@@ -103,7 +103,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 5,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527825456,
"y": -7081568,
@@ -121,7 +121,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 6,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527796578,
"y": -7092163,
@@ -139,7 +139,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 7,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527801900,
"y": -7044017,
@@ -157,7 +157,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 8,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527828246,
"y": -7061076,
@@ -175,7 +175,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 9,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527818707,
"y": -7041549,
@@ -193,7 +193,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 10,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527814489,
"y": -7058179,
@@ -211,7 +211,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 11,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527821887,
"y": -7058072,
@@ -229,7 +229,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 12,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527826364,
"y": -7068908,
diff --git a/radio/tests/mission_test_files/test_writeCurrentMission_uploadMissionSuccess_data.json b/radio/tests/mission_test_files/test_writeCurrentMission_uploadMissionSuccess_data.json
index 1070d0f12..8e91611c9 100644
--- a/radio/tests/mission_test_files/test_writeCurrentMission_uploadMissionSuccess_data.json
+++ b/radio/tests/mission_test_files/test_writeCurrentMission_uploadMissionSuccess_data.json
@@ -13,7 +13,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 0,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527805690,
"y": -7079236,
@@ -22,7 +22,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 1,
"frame": 3,
"command": 22,
@@ -40,7 +40,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 2,
"frame": 3,
"command": 16,
@@ -58,7 +58,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 3,
"frame": 3,
"command": 16,
@@ -76,7 +76,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 4,
"frame": 3,
"command": 16,
@@ -94,7 +94,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 5,
"frame": 3,
"command": 16,
@@ -112,7 +112,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 6,
"frame": 3,
"command": 16,
@@ -130,7 +130,7 @@
{
"mavpackettype": "MISSION_ITEM_INT",
"target_system": 255,
- "target_component": 0,
+ "target_component": 190,
"seq": 7,
"frame": 3,
"command": 21,
diff --git a/radio/tests/mission_test_files/test_writeCurrentMission_uploadRallySuccess_data.json b/radio/tests/mission_test_files/test_writeCurrentMission_uploadRallySuccess_data.json
index 53f2143b8..2ebc37df3 100644
--- a/radio/tests/mission_test_files/test_writeCurrentMission_uploadRallySuccess_data.json
+++ b/radio/tests/mission_test_files/test_writeCurrentMission_uploadRallySuccess_data.json
@@ -13,7 +13,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 0,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527810011,
"y": -7094872,
@@ -31,7 +31,7 @@
"param3": 0.0,
"param4": 0.0,
"seq": 1,
- "target_component": 0,
+ "target_component": 190,
"target_system": 255,
"x": 527821108,
"y": -7056785,
diff --git a/radio/tests/test_comPorts.py b/radio/tests/test_comPorts.py
index aacfec510..3f27f0243 100644
--- a/radio/tests/test_comPorts.py
+++ b/radio/tests/test_comPorts.py
@@ -109,7 +109,10 @@ def test_connectToDrone_validConnection() -> None:
socketio_client.emit(
"connect_to_drone", {"connectionType": connectionType, "port": VALID_DRONE_PORT}
)
- assert socketio_client.get_received()[-1]["args"][0] == {"aircraft_type": 2}
+ assert socketio_client.get_received()[-1]["args"][0] == {
+ "flight_sw_version": "4.7.0",
+ "aircraft_type": 2,
+ }
assert droneStatus.drone is not None
assert droneStatus.drone.port == VALID_DRONE_PORT
assert droneStatus.drone.baud == 57600
@@ -119,7 +122,10 @@ def test_connectToDrone_validConnection() -> None:
"connect_to_drone",
{"connectionType": connectionType, "port": VALID_DRONE_PORT, "baud": 9600},
)
- assert socketio_client.get_received()[-1]["args"][0] == {"aircraft_type": 2}
+ assert socketio_client.get_received()[-1]["args"][0] == {
+ "flight_sw_version": "4.7.0",
+ "aircraft_type": 2,
+ }
assert droneStatus.drone is not None
assert droneStatus.drone.baud == 9600
@@ -170,7 +176,10 @@ def test_disconnectFromDrone() -> None:
"connect_to_drone",
{"connectionType": connectionType, "port": VALID_DRONE_PORT, "baud": 9600},
)
- assert socketio_client.get_received()[-1]["args"][0] == {"aircraft_type": 2}
+ assert socketio_client.get_received()[-1]["args"][0] == {
+ "flight_sw_version": "4.7.0",
+ "aircraft_type": 2,
+ }
socketio_client.emit("disconnect_from_drone")
assert socketio_client.get_received()[0]["name"] == "disconnected_from_drone"
diff --git a/radio/tests/test_states.py b/radio/tests/test_states.py
index c539a241c..878983804 100644
--- a/radio/tests/test_states.py
+++ b/radio/tests/test_states.py
@@ -1,17 +1,9 @@
-import time
-
-import pytest
from flask_socketio import SocketIOTestClient
from . import falcon_test
from .helpers import NoDrone, send_and_recieve
-def stream_is_active(msg):
- # TODO: THIS DOESNT WORK YAYYYYYYYYYYYYY
- return True
-
-
@falcon_test(pass_drone_status=True)
def test_setState(socketio_client: SocketIOTestClient, droneStatus) -> None:
# Failure on no drone connection
@@ -25,6 +17,8 @@ def test_setState(socketio_client: SocketIOTestClient, droneStatus) -> None:
"message": "Request to endpoint set_state missing value for parameter: state."
}
+ # TODO: These values don't seem right to me, they don't include the STATUSTEXT listener?
+
# Success on changing state to dashboard
socketio_client.emit("set_state", {"state": "dashboard"})
assert len(socketio_client.get_received()) == 0
@@ -34,24 +28,25 @@ def test_setState(socketio_client: SocketIOTestClient, droneStatus) -> None:
socketio_client.emit("set_state", {"state": "graphs"})
assert len(socketio_client.get_received()) == 0
- assert len(droneStatus.drone.message_listeners) == 3
+ assert len(droneStatus.drone.message_listeners) == 4
droneStatus.drone.message_listeners = {}
socketio_client.emit("set_state", {"state": "config.flight_modes"})
assert len(socketio_client.get_received()) == 0
- assert len(droneStatus.drone.message_listeners) == 2
+ assert len(droneStatus.drone.message_listeners) == 3
droneStatus.drone.message_listeners = {}
socketio_client.emit("set_state", {"state": "config.rc"})
assert len(socketio_client.get_received()) == 0
- assert len(droneStatus.drone.message_listeners) == 2
+ assert len(droneStatus.drone.message_listeners) == 3
droneStatus.drone.message_listeners = {}
- pytest.skip(reason="Issues with parameterController to be fixed in alpha 0.1.8")
- socketio_client.emit("set_state", {"state": "params"})
- time.sleep(15)
- assert len(socketio_client.get_received()[-1]["args"][0]) == 1400
- assert len(droneStatus.drone.message_listeners) == 0
+ # TODO: Sort this out
+ # pytest.skip(reason="Issues with parameterController to be fixed in alpha 0.1.8")
+ # socketio_client.emit("set_state", {"state": "params"})
+ # time.sleep(15)
+ # assert len(socketio_client.get_received()[-1]["args"][0]) == 1400
+ # assert len(droneStatus.drone.message_listeners) == 1