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
10 changes: 8 additions & 2 deletions gcs/src/components/navbar.jsx
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ import { useDispatch, useSelector } from "react-redux"
import {
ConnectionType,
emitConnectToDrone,
emitDisconnectFromDrone,
emitGetComPorts,
emitStartForwarding,
emitStopForwarding,
Expand Down Expand Up @@ -169,6 +170,9 @@ export default function Navbar() {
<Modal
opened={openedModal}
onClose={() => {
if (connecting) {
dispatch(emitDisconnectFromDrone())
}
dispatch(setConnectionModal(false))
dispatch(setConnecting(false))
}}
Expand Down Expand Up @@ -297,12 +301,14 @@ export default function Navbar() {
variant="filled"
color={"red"}
onClick={() => {
if (connecting) {
dispatch(emitDisconnectFromDrone())
}
dispatch(setConnectionModal(false))
dispatch(setConnecting(false))
}}
disabled={connecting}
>
Close
{connecting ? "Cancel" : "Close"}
</Button>
<Button
variant="filled"
Expand Down
12 changes: 11 additions & 1 deletion gcs/src/redux/middleware/emitters.js
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,17 @@ export function handleEmitters(socket, store, action) {
},
{
emitter: emitDisconnectFromDrone,
callback: () => socket.socket.emit("disconnect_from_drone"),
callback: () => {
const storeState = store.getState()
const isConnecting = storeState.droneConnection.connecting

if (isConnecting) {
socket.socket.emit("cancel_connect_to_drone")
return
}

socket.socket.emit("disconnect_from_drone")
},
},
{
emitter: emitConnectToDrone,
Expand Down
14 changes: 14 additions & 0 deletions radio/app/controllers/paramsController.py
Original file line number Diff line number Diff line change
Expand Up @@ -77,10 +77,17 @@ def fetchAllParamsBlocking(
self,
timeout_secs: int = 120,
progress_update_callback: Optional[Callable[[dict], None]] = None,
should_cancel_callback: Optional[Callable[[], bool]] = None,
) -> Response:
"""
Fetches all parameters from the drone in a blocking manner.
"""
if should_cancel_callback and should_cancel_callback():
return {
"success": False,
"message": "Connection cancelled by user.",
}

start_response = self._startFetchAll()
if not start_response.get("success"):
return start_response
Expand All @@ -89,6 +96,13 @@ def fetchAllParamsBlocking(

try:
while self.is_requesting_params:
if should_cancel_callback and should_cancel_callback():
self.drone.logger.info("Parameter fetch cancelled by user")
return {
"success": False,
"message": "Connection cancelled by user.",
}

if time.time() > timeout:
self.drone.logger.error(
f"Fetching all parameters timed out after {timeout_secs} seconds"
Expand Down
53 changes: 50 additions & 3 deletions radio/app/drone.py
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,7 @@ def __init__(
droneConnectStatusCb: Optional[Callable] = None,
linkDebugStatsCb: Optional[Callable] = None,
fetchingParameterCb: Optional[Callable] = None,
connectionCancelEvent: Optional[Event] = None,
) -> None:
"""
The drone class interfaces with the UAS via MavLink.
Expand All @@ -95,6 +96,9 @@ def __init__(
droneErrorCb (Optional[Callable], optional): Callback function for drone errors. Defaults to None.
droneDisconnectCb (Optional[Callable], optional): Callback function for drone disconnection. Defaults to None.
droneConnectStatusCb (Optional[Callable], optional): Callback function for drone connection providing an update as the drone connects. Defaults to None.
linkDebugStatsCb (Optional[Callable], optional): Callback function for link debug stats. Defaults to None.
fetchingParameterCb (Optional[Callable], optional): Callback function for when parameters are being fetched. Defaults to None.
connectionCancelEvent (Optional[Event], optional): Event to signal if the connection process should be cancelled. Defaults to None.
"""
self.port = port
self.baud = baud
Expand All @@ -104,6 +108,7 @@ def __init__(
self.droneConnectStatusCb = droneConnectStatusCb
self.linkDebugStatsCb = linkDebugStatsCb
self.fetchingParameterCb = fetchingParameterCb
self.connection_cancel_event: Event = connectionCancelEvent or Event()

self.connectionError: Optional[str] = None
self._last_connect_progress: float = 0.0
Expand Down Expand Up @@ -148,12 +153,20 @@ def __init__(
self.connectionError = str(e)
return

if self._isConnectionCancelRequested():
self._setCancelledConnectionErrorAndCloseMaster()
return

try:
initial_heartbeat = None
heartbeat_timeout_secs = 5.0
deadline = time.monotonic() + heartbeat_timeout_secs

while True:
if self._isConnectionCancelRequested():
self._setCancelledConnectionErrorAndCloseMaster()
return

now = time.monotonic()
if now >= deadline:
break
Expand Down Expand Up @@ -249,6 +262,12 @@ def __init__(

self.addMessageListener("STATUSTEXT", sendMessage)

if self._isConnectionCancelRequested():
self._setCancelledConnectionErrorAndCloseMaster()
self.is_active.clear()
self.stopAllThreads()
return

self.getAutopilotVersion()

if self.flight_sw_version is None:
Expand Down Expand Up @@ -289,6 +308,7 @@ def __init__(
fetch_all_params_result = self.paramsController.fetchAllParamsBlocking(
timeout_secs=120,
progress_update_callback=self.sendParamFetchConnectionStatusUpdate,
should_cancel_callback=self._isConnectionCancelRequested,
)

if not fetch_all_params_result.get("success"):
Expand All @@ -311,6 +331,24 @@ def __init__(
mavutil.mavlink.MAV_SEVERITY_INFO, "FGCS connected to aircraft"
)

def _isConnectionCancelRequested(self) -> bool:
return self.connection_cancel_event.is_set()

def requestConnectionCancel(self) -> None:
self.connection_cancel_event.set()
if getattr(self, "paramsController", None) is not None:
self.paramsController.is_requesting_params = False

def _setCancelledConnectionErrorAndCloseMaster(self) -> None:
self.logger.info("Connection cancelled by user")
self.connectionError = "Connection cancelled by user."
if getattr(self, "master", None) is not None:
try:
self.master.close()
except Exception:
self.logger.exception("Failed to close connection during cancellation")
self.master = None

def __getNextLogFilePath(self, line: str) -> str:
return line.split("==NEXT_FILE==")[-1].split("==END==")[0]

Expand Down Expand Up @@ -931,8 +969,13 @@ def sendHeartbeatMessage(self) -> None:
if sleep_time > 0:
time.sleep(sleep_time)

master = getattr(self, "master", None)
if master is None:
# Connection teardown can clear master while this thread is winding down.
break

try:
self.master.mav.heartbeat_send(
master.mav.heartbeat_send(
mavutil.mavlink.MAV_TYPE_GCS,
mavutil.mavlink.MAV_AUTOPILOT_INVALID,
0,
Expand Down Expand Up @@ -1228,10 +1271,14 @@ def close(self) -> None:

self.is_active.clear()

self.stopAllDataStreams()
if getattr(self, "master", None) is not None:
self.stopAllDataStreams()
self.stopForwarding()
self.stopAllThreads()
self.master.close()

if getattr(self, "master", None) is not None:
self.master.close()
self.master = None

if len(self.log_file_names) == 0:
self.logger.debug("No logs to save")
Expand Down
5 changes: 4 additions & 1 deletion radio/app/droneStatus.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,11 +3,14 @@
imports this and access it, it can update the values and every other file will also have the update due to passing by reference (probably).
"""

from threading import Event, Lock
from typing import List, Optional


from app.drone import Drone

correct_ports: List[str] = []
drone: Optional[Drone] = None
state: Optional[str] = None
connection_state_lock: Lock = Lock()
connection_in_progress: bool = False
connect_cancel_event: Optional[Event] = None
125 changes: 87 additions & 38 deletions radio/app/endpoints/comPorts.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
import sys
import time
from threading import Event
from typing import Optional

from serial.tools import list_ports
Expand All @@ -11,9 +12,9 @@
from app.utils import (
droneConnectStatusCb,
droneErrorCb,
fetchingParameterCb,
getComPortNames,
getFlightSwVersionString,
fetchingParameterCb,
)


Expand Down Expand Up @@ -78,13 +79,6 @@ def connectToDrone(data: ConnectionDataType) -> None:
Args:
data: The message passed in from the client containing the form sent (select com port, baud rate)
"""
if droneStatus.drone:
droneStatus.drone.logger.warning(
"Attempting a connection to drone when connection is already established."
)
droneStatus.drone.close()
droneStatus.drone = None

connectionType = data.get("connectionType")

if connectionType not in ["serial", "network"]:
Expand Down Expand Up @@ -133,45 +127,100 @@ def connectToDrone(data: ConnectionDataType) -> None:
droneStatus.drone = None
return

drone = Drone(
port,
baud=baud,
forwarding_address=forwarding_address,
droneErrorCb=droneErrorCb,
droneDisconnectCb=disconnectFromDrone,
droneConnectStatusCb=droneConnectStatusCb,
linkDebugStatsCb=sendLinkDebugStats,
fetchingParameterCb=fetchingParameterCb,
)

if drone.connectionError is not None:
socketio.emit("connection_error", {"message": drone.connectionError})
droneStatus.drone = None
return
old_drone = None
with droneStatus.connection_state_lock:
if droneStatus.connection_in_progress:
socketio.emit(
"connection_error",
{"message": "A drone connection is already in progress."},
)
return

# Set droneStatus drone to local drone
droneStatus.drone = drone
if droneStatus.drone:
old_drone = droneStatus.drone
droneStatus.drone = 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,
"flight_sw_version": getFlightSwVersionString(drone.flight_sw_version),
},
)
cancel_event = Event()
droneStatus.connect_cancel_event = cancel_event
droneStatus.connection_in_progress = True

if old_drone is not None:
old_drone.logger.warning(
"Attempting a connection to drone when connection is already established."
)
old_drone.close()

try:
drone = Drone(
port,
baud=baud,
forwarding_address=forwarding_address,
droneErrorCb=droneErrorCb,
droneDisconnectCb=disconnectFromDrone,
droneConnectStatusCb=droneConnectStatusCb,
linkDebugStatsCb=sendLinkDebugStats,
fetchingParameterCb=fetchingParameterCb,
connectionCancelEvent=cancel_event,
)

if drone.connectionError is not None:
socketio.emit("connection_error", {"message": drone.connectionError})
droneStatus.drone = None
return

# Set droneStatus drone to local drone
droneStatus.drone = drone

# 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,
"flight_sw_version": getFlightSwVersionString(drone.flight_sw_version),
},
)
finally:
with droneStatus.connection_state_lock:
droneStatus.connection_in_progress = False
droneStatus.connect_cancel_event = None


@socketio.on("cancel_connect_to_drone")
def cancelConnectToDrone() -> None:
"""Cancel an in-progress drone connection attempt."""
with droneStatus.connection_state_lock:
if droneStatus.connection_in_progress and droneStatus.connect_cancel_event:
logger.info("Connection cancel requested by user")
droneStatus.connect_cancel_event.set()
else:
logger.debug(
"Connection cancel requested, but no connection is in progress"
)


@socketio.on("disconnect_from_drone")
def disconnectFromDrone() -> None:
"""
Disconnect from drone and reset all global variables, send a message to client disconnecting as well
"""
if droneStatus.drone:
droneStatus.drone.close()
droneStatus.drone = None
with droneStatus.connection_state_lock:
if droneStatus.drone:
drone = droneStatus.drone
droneStatus.drone = None
else:
drone = None

if (
drone is None
and droneStatus.connection_in_progress
and droneStatus.connect_cancel_event
):
droneStatus.connect_cancel_event.set()

if drone is not None:
drone.close()

droneStatus.state = None
socketio.emit("disconnected_from_drone")
Loading
Loading