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
4 changes: 2 additions & 2 deletions gcs/src/params.jsx
Original file line number Diff line number Diff line change
Expand Up @@ -81,10 +81,10 @@ export default function Params() {

return (
<Layout currentPage="params">
<AutopilotRebootModal />

{connected ? (
<>
<AutopilotRebootModal />

{fetchingVars && (
<Progress
radius="xs"
Expand Down
6 changes: 5 additions & 1 deletion gcs/src/redux/middleware/emitters.js
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ import {
emitGetLoiterRadius,
emitIsConnectedToDrone,
emitSetState,
setState,
} from "../slices/droneConnectionSlice"
import {
emitExportMissionToFile,
Expand Down Expand Up @@ -47,7 +48,10 @@ export function handleEmitters(socket, store, action) {
},
{
emitter: emitSetState,
callback: () => socket.socket.emit("set_state", action.payload),
callback: () => {
store.dispatch(setState(action.payload))
socket.socket.emit("set_state", action.payload)
},
},
{
emitter: emitGetHomePosition,
Expand Down
17 changes: 13 additions & 4 deletions gcs/src/redux/middleware/socketMiddleware.js
Original file line number Diff line number Diff line change
Expand Up @@ -261,11 +261,18 @@ const socketMiddleware = (store) => {
store.dispatch(setConnecting(false))
store.dispatch(setConnectionModal(false))

store.dispatch(emitSetState({ state: "dashboard" }))
store.dispatch(emitGetHomePosition()) // use actual home position
if (msg.aircraft_type === 1) {
store.dispatch(emitGetLoiterRadius())
const currentState = store.getState().droneConnection
store.dispatch(emitSetState(currentState))

if (["dashboard", "missions"].includes(currentState.state)) {
store.dispatch(emitGetHomePosition()) // fetch the actual home position of the drone
if (msg.aircraft_type === 1) {
store.dispatch(emitGetLoiterRadius())
}
}

store.dispatch(setRebootData({}))
store.dispatch(setAutoPilotRebootModalOpen(false))
})

// Link stats
Expand Down Expand Up @@ -321,6 +328,8 @@ const socketMiddleware = (store) => {
store.dispatch(setRebootData(msg))
if (msg.success) {
store.dispatch(setAutoPilotRebootModalOpen(false))
store.dispatch(queueSuccessNotification(msg.message))
store.dispatch(setRebootData({}))
}
})

Expand Down
10 changes: 10 additions & 0 deletions gcs/src/redux/slices/droneConnectionSlice.js
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,8 @@ const initialState = {
network_type: "tcp", // local
ip: "127.0.0.1", // local
port: "5760", // local

state: "dashboard",
}

const droneConnectionSlice = createSlice({
Expand Down Expand Up @@ -101,6 +103,11 @@ const droneConnectionSlice = createSlice({
state.wireless = action.payload
}
},
setState: (state, action) => {
if (action.payload !== state.state) {
state.state = action.payload
}
},

// Emits
emitIsConnectedToDrone: () => {},
Expand Down Expand Up @@ -128,6 +135,7 @@ const droneConnectionSlice = createSlice({
selectConnectionModal: (state) => state.connection_modal,
selectConnectionStatus: (state) => state.connection_status,
selectWireless: (state) => state.wireless,
selectState: (state) => state.state,
},
})

Expand All @@ -146,6 +154,7 @@ export const {
setConnectionModal,
setConnectionStatus,
setWireless,
setState,

// Emitters
emitIsConnectedToDrone,
Expand All @@ -171,6 +180,7 @@ export const {
selectConnectionModal,
selectConnectionStatus,
selectWireless,
selectState,
} = droneConnectionSlice.selectors

export default droneConnectionSlice
4 changes: 2 additions & 2 deletions radio/app.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,8 @@
import os
from pathlib import Path

import app.droneStatus as droneStatus
from app import create_app, socketio
from pathlib import Path
from dotenv import load_dotenv

app = create_app(debug=True)
Expand All @@ -20,7 +21,6 @@
host = "127.0.0.1"

print("Starting backend.")
print(host)
socketio.run(app, allow_unsafe_werkzeug=True, host=host, port=port)
if droneStatus.drone:
droneStatus.drone.close()
Expand Down
25 changes: 18 additions & 7 deletions radio/app/controllers/paramsController.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ def __init__(self, drone: Drone) -> None:
self.getAllParamsThread: Optional[Thread] = None

@sendingCommandLock
def getSingleParam(self, param_name: str, timeout: Optional[float] = 5) -> Response:
def getSingleParam(self, param_name: str, timeout: float = 3) -> Response:
Comment thread
1Blademaster marked this conversation as resolved.
"""
Gets a specific parameter value.

Expand All @@ -53,18 +53,29 @@ def getSingleParam(self, param_name: str, timeout: Optional[float] = 5) -> Respo
)

try:
response = self.drone.master.recv_match(
type="PARAM_VALUE", blocking=True, timeout=timeout
)
start_time = time.time()
response = None
while time.time() - start_time < timeout:
# timeout of 0.2 to recv_match to allow checking the overall timeout and not block forever
msg = self.drone.master.recv_match(
type="PARAM_VALUE", blocking=True, timeout=0.2
)

if msg is None:
continue

if response and response.param_id == param_name:
self.drone.is_listening = True
if msg.param_id == param_name:
response = msg
break

self.drone.is_listening = True
if response:
return {
"success": True,
"data": response,
}
else:
self.drone.is_listening = True
self.drone.logger.error(f"Did not receive {param_name} within timeout")
Comment thread
1Blademaster marked this conversation as resolved.
return {
"success": False,
"message": f"{failure_message}, timed out",
Expand Down
2 changes: 1 addition & 1 deletion radio/app/drone.py
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ def __init__(

self.connectionError: Optional[str] = None

self.logger.debug("Trying to setup master")
self.logger.debug(f"Trying to setup master with port {port} and baud {baud}")

if not Drone.checkBaudrateValid(baud):
self.connectionError = (
Expand Down
22 changes: 18 additions & 4 deletions radio/app/endpoints/autopilot.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,10 @@
@socketio.on("reboot_autopilot")
def rebootAutopilot() -> None:
"""
Attempt to reboot the autopilot, this will try to reconnect to the drone 3 times before stopping. This will also stop if the port
is not open for 10 seconds.
Attempt to reboot the autopilot, this will try to reconnect to the drone 3 times before stopping.

Note: If SITL is running and you are connected via TCP 5763 then rebooting does not work as expected.
Use TCP 5760 instead.
"""
if not droneStatus.drone:
return
Expand All @@ -20,12 +22,20 @@ def rebootAutopilot() -> None:
droneErrorCb = droneStatus.drone.droneErrorCb
droneDisconnectCb = droneStatus.drone.droneDisconnectCb
droneConnectStatusCb = droneStatus.drone.droneConnectStatusCb
linkDebugStatsCb = droneStatus.drone.linkDebugStatsCb

socketio.emit("disconnected_from_drone")

droneStatus.drone.rebootAutopilot()

while droneStatus.drone is not None and droneStatus.drone.is_active.is_set():
while droneStatus.drone.is_active.is_set():
Comment thread
1Blademaster marked this conversation as resolved.
print("Waiting for drone to disconnect...")
time.sleep(0.05)

droneStatus.drone = None

time.sleep(1.5) # Wait for the port to be released and let the autopilot reboot

tries = 0
while tries < 3:
droneStatus.drone = Drone(
Expand All @@ -35,13 +45,15 @@ def rebootAutopilot() -> None:
droneErrorCb=droneErrorCb,
droneDisconnectCb=droneDisconnectCb,
droneConnectStatusCb=droneConnectStatusCb,
linkDebugStatsCb=linkDebugStatsCb,
)
if droneStatus.drone.connectionError:
tries += 1
time.sleep(2)
else:
break
else:
droneStatus.drone = None
logger.error("Could not reconnect to drone after 3 attempts.")
socketio.emit(
"reboot_autopilot",
Expand All @@ -53,7 +65,9 @@ def rebootAutopilot() -> None:
return

time.sleep(1)
socketio.emit("connected_to_drone")
socketio.emit(
"connected_to_drone", {"aircraft_type": droneStatus.drone.aircraft_type}
)
logger.info("Rebooted autopilot successfully.")
socketio.emit(
"reboot_autopilot",
Expand Down
19 changes: 11 additions & 8 deletions radio/tests/helpers.py
Original file line number Diff line number Diff line change
@@ -1,8 +1,9 @@
import pytest
from typing import Optional, Union
from serial.serialutil import SerialException

import pytest
from app import droneStatus, logger
from serial.serialutil import SerialException

from . import socketio_client


Expand Down Expand Up @@ -121,17 +122,17 @@ def __exit__(self, type, value, traceback) -> None:
droneStatus.drone.master.recv_match = self.old_recv


class RecvMsgReturnsFalse:
class RecvMsgReturnsNone:
@staticmethod
def recv_match_false(
condition=None, type=None, blocking=False, timeout=None
) -> bool:
return False
) -> None:
return None

def __enter__(self) -> None:
if droneStatus.drone is not None:
self.old_recv = droneStatus.drone.master.recv_match
droneStatus.drone.master.recv_match = RecvMsgReturnsFalse.recv_match_false
droneStatus.drone.master.recv_match = RecvMsgReturnsNone.recv_match_false

def __exit__(self, type, value, traceback) -> None:
if droneStatus.drone is not None:
Expand Down Expand Up @@ -167,8 +168,10 @@ def send_and_recieve(endpoint: str, args: Optional[Union[dict, str]] = None) ->
dict
The data recieved from the client
"""
socketio_client.emit(endpoint, args) if args is not None else socketio_client.emit(
endpoint
(
socketio_client.emit(endpoint, args)
if args is not None
else socketio_client.emit(endpoint)
)
return socketio_client.get_received()[0]["args"][0]

Expand Down
8 changes: 4 additions & 4 deletions radio/tests/test_FlightModesController.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
from flask_socketio.test_client import SocketIOTestClient

from . import falcon_test
from .helpers import FakeTCP, ParamSetTimeout, RecvMsgReturnsFalse, SetAircraftType
from .helpers import FakeTCP, ParamSetTimeout, RecvMsgReturnsNone, SetAircraftType


@pytest.fixture(scope="module", autouse=True)
Expand Down Expand Up @@ -41,7 +41,7 @@ def test_getFlightModes_success(client: SocketIOTestClient, droneStatus):

@falcon_test(pass_drone_status=True)
def test_getFlightModes_failure(client: SocketIOTestClient, droneStatus):
with RecvMsgReturnsFalse():
with RecvMsgReturnsNone():
droneStatus.drone.flightModesController.getFlightModes()
assert len(droneStatus.drone.flightModesController.flight_modes) == 6
for items in droneStatus.drone.flightModesController.flight_modes:
Expand All @@ -50,7 +50,7 @@ def test_getFlightModes_failure(client: SocketIOTestClient, droneStatus):

@falcon_test(pass_drone_status=True)
def test_getFlightModeChannel_failure(client: SocketIOTestClient, droneStatus):
with RecvMsgReturnsFalse():
with RecvMsgReturnsNone():
droneStatus.drone.flightModesController.getFlightModeChannel()
assert droneStatus.drone.flightModesController.flight_mode_channel == "UNKNOWN"

Expand All @@ -68,7 +68,7 @@ def test_setCurrentFlightMode(client: SocketIOTestClient, droneStatus):
assert response.get("success") is False
assert response.get("message") == "Could not set flight mode, serial exception"

with RecvMsgReturnsFalse():
with RecvMsgReturnsNone():
response = droneStatus.drone.flightModesController.setCurrentFlightMode(1)
assert response.get("success") is False
assert response.get("message") == "Could not set flight mode"
Expand Down
1 change: 0 additions & 1 deletion radio/tests/test_autopilot.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
from . import falcon_test


# @pytest.mark.skip(reason="Test fails due to reboot_autopilot not functional")
@falcon_test()
def test_reboot_success(socketio_client: SocketIOTestClient):
"""
Expand Down
Loading