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
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,9 @@ export default function ActionTabsSection({
<NoConnectionMsg message="No actions are available right now. Connect a drone to begin" />
) : (
<div className="flex flex-col gap-y-2">
{/** Loiter Radius */}
<LoiterRadiusAction currentLoiterRadius={currentLoiterRadius} />
{aircraftType === 1 && (
<LoiterRadiusAction currentLoiterRadius={currentLoiterRadius} />
)}
{/** Flight Mode */}
<FlightModeAction
aircraftType={aircraftType}
Expand Down
8 changes: 7 additions & 1 deletion gcs/src/components/layout.jsx
Original file line number Diff line number Diff line change
Expand Up @@ -20,10 +20,12 @@ import { socket } from "../helpers/socket"
import { useDispatch, useSelector } from "react-redux"
import {
emitGetCurrentMissionAll,
emitGetHomePosition,
emitGetLoiterRadius,
emitSetState,
selectConnectedToDrone,
} from "../redux/slices/droneConnectionSlice"
import { selectAircraftTypeString } from "../redux/slices/droneInfoSlice"
import {
notificationShown,
selectNotificationQueue,
Expand All @@ -33,6 +35,7 @@ export default function Layout({ children, currentPage }) {
const dispatch = useDispatch()
const connectedToDrone = useSelector(selectConnectedToDrone)
const notificationQueue = useSelector(selectNotificationQueue)
const aircraftTypeString = useSelector(selectAircraftTypeString)

// Change current page, there's a single comma because javascript has weird syntax
// we don't care about the first variable.
Expand Down Expand Up @@ -71,7 +74,10 @@ export default function Layout({ children, currentPage }) {
dispatch(emitSetState({ state: currentPage }))
if (currentPage.toLowerCase() == "dashboard") {
dispatch(emitGetCurrentMissionAll())
dispatch(emitGetLoiterRadius())
dispatch(emitGetHomePosition())
if (aircraftTypeString === "Plane") {
dispatch(emitGetLoiterRadius())
}
}
}, [currentPage, connectedToDrone])

Expand Down
6 changes: 4 additions & 2 deletions gcs/src/redux/middleware/socketMiddleware.js
Original file line number Diff line number Diff line change
Expand Up @@ -228,7 +228,7 @@ const socketMiddleware = (store) => {
// Flags that the drone is connected
socket.socket.on("connected_to_drone", (msg) => {
store.dispatch(setDroneAircraftType(msg.aircraft_type)) // There are two aircraftTypes, make sure to not use FLA one haha :D
if (msg.aircraft_type != 1 && msg.aircraft_type != 2) {
if (msg.aircraft_type !== 1 && msg.aircraft_type !== 2) {
store.dispatch(
queueErrorNotification(
"Aircraft not of type quadcopter or plane",
Expand All @@ -241,7 +241,9 @@ const socketMiddleware = (store) => {

store.dispatch(emitSetState({ state: "dashboard" }))
store.dispatch(emitGetHomePosition())
store.dispatch(emitGetLoiterRadius())
if (msg.aircraft_type === 1) {
store.dispatch(emitGetLoiterRadius())
}
})

// Link stats
Expand Down
4 changes: 3 additions & 1 deletion radio/app/controllers/armController.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
from typing import TYPE_CHECKING

from app.customTypes import Response
from app.utils import commandAccepted
from app.utils import commandAccepted, sendingCommandLock
from pymavlink import mavutil

if TYPE_CHECKING:
Expand All @@ -21,6 +21,7 @@ def __init__(self, drone: Drone) -> None:
"""
self.drone = drone

@sendingCommandLock
def arm(self, force: bool = False) -> Response:
"""
Arm the drone.
Expand Down Expand Up @@ -63,6 +64,7 @@ def arm(self, force: bool = False) -> Response:
return {"success": False, "message": "Could not arm, serial exception"}
return {"success": False, "message": "Could not arm, command not accepted"}

@sendingCommandLock
def disarm(self, force: bool = False) -> Response:
"""
Disarm the drone.
Expand Down
3 changes: 2 additions & 1 deletion radio/app/controllers/flightModesController.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

import serial
from app.customTypes import Response
from app.utils import commandAccepted
from app.utils import commandAccepted, sendingCommandLock
from pymavlink import mavutil

if TYPE_CHECKING:
Expand Down Expand Up @@ -126,6 +126,7 @@ def setFlightMode(self, mode_number: int, flight_mode: int) -> Response:
"message": f"Failed to set flight mode {mode_number} to {mode_name}",
}

@sendingCommandLock
def setCurrentFlightMode(self, flightMode: int) -> Response:
"""
Sends a Mavlink message to the drone for setting its current flight mode
Expand Down
3 changes: 3 additions & 0 deletions radio/app/controllers/gripperController.py
Original file line number Diff line number Diff line change
Expand Up @@ -103,6 +103,7 @@ def setGripper(self, action: str) -> Response:
}

self.drone.is_listening = False
self.drone.sending_command_lock.acquire()

self.drone.sendCommand(
mavutil.mavlink.MAV_CMD_DO_GRIPPER,
Expand All @@ -119,6 +120,7 @@ def setGripper(self, action: str) -> Response:
response = self.drone.master.recv_match(type="COMMAND_ACK", blocking=True)

self.drone.is_listening = True
self.drone.sending_command_lock.release()

if commandAccepted(response, mavutil.mavlink.MAV_CMD_DO_GRIPPER):
return {
Expand All @@ -132,6 +134,7 @@ def setGripper(self, action: str) -> Response:
}
except serial.serialutil.SerialException:
self.drone.is_listening = True
self.drone.sending_command_lock.release()
return {
"success": False,
"message": "Setting gripper failed, serial exception",
Expand Down
16 changes: 14 additions & 2 deletions radio/app/controllers/missionController.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

import serial
from app.customTypes import Number, Response
from app.utils import commandAccepted
from app.utils import commandAccepted, sendingCommandLock
from pymavlink import mavutil, mavwp

if TYPE_CHECKING:
Expand Down Expand Up @@ -161,6 +161,7 @@ def getCurrentMissionAll(self) -> Response:
},
}

@sendingCommandLock
def getMissionItems(
self,
mission_type: int,
Expand Down Expand Up @@ -282,7 +283,6 @@ def getMissionItems(
"success": False,
"message": failure_message,
}

except serial.serialutil.SerialException:
self.drone.is_listening = True
return {
Expand Down Expand Up @@ -311,6 +311,7 @@ def getItemDetails(
failure_message = f"Failed to get mission item {item_number + 1}/{mission_count} for mission type {mission_type}"

self.drone.is_listening = False
# The sending_command_lock is held by the caller function getMissionItems

self.drone.master.mav.mission_request_int_send(
self.drone.target_system,
Expand Down Expand Up @@ -356,6 +357,7 @@ def getItemDetails(
"message": f"{failure_message}, serial exception",
}

@sendingCommandLock
def startMission(self) -> Response:
"""
Start the mission on the drone.
Expand Down Expand Up @@ -391,6 +393,7 @@ def startMission(self) -> Response:
"message": "Failed to start mission, serial exception",
}

@sendingCommandLock
def restartMission(self) -> Response:
"""
Restarts the mission on the drone.
Expand Down Expand Up @@ -426,6 +429,7 @@ def restartMission(self) -> Response:
"message": "Failed to restart mission, serial exception",
}

@sendingCommandLock
def clearMission(self, mission_type: int) -> Response:
"""
Clears the specified mission type from the drone.
Expand All @@ -438,6 +442,7 @@ def clearMission(self, mission_type: int) -> Response:
return mission_type_check

self.drone.is_listening = False

self.drone.master.mav.mission_clear_all_send(
self.drone.target_system,
self.drone.target_component,
Expand Down Expand Up @@ -575,6 +580,7 @@ def uploadMission(
}

self.drone.is_listening = False
self.drone.sending_command_lock.acquire()
Comment thread
1Blademaster marked this conversation as resolved.

self.drone.master.mav.mission_count_send(
self.drone.target_system,
Expand All @@ -592,6 +598,7 @@ def uploadMission(
)
if not response:
self.drone.is_listening = True
self.drone.sending_command_lock.release()

return {
"success": False,
Expand All @@ -601,6 +608,8 @@ def uploadMission(
self.drone.logger.error(
f"Error uploading mission, mission ack response: {response.type}"
)
self.drone.is_listening = True
self.drone.sending_command_lock.release()
return {
"success": False,
"message": "Could not upload mission, received mission acknowledgement error",
Expand Down Expand Up @@ -628,6 +637,7 @@ def uploadMission(
timeout=2,
)
self.drone.is_listening = True
self.drone.sending_command_lock.release()

if (
mission_ack_response
Expand All @@ -641,6 +651,7 @@ def uploadMission(
self.fenceLoader = new_loader
else:
self.rallyLoader = new_loader

return {
"success": True,
"message": "Mission uploaded successfully",
Expand All @@ -655,6 +666,7 @@ def uploadMission(
}
except serial.serialutil.SerialException:
self.drone.is_listening = True
self.drone.sending_command_lock.release()
return {
"success": False,
"message": "Could not upload mission, serial exception",
Expand Down
5 changes: 4 additions & 1 deletion radio/app/controllers/motorTestController.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
MotorTestThrottleDurationAndNumber,
Response,
)
from app.utils import commandAccepted
from app.utils import commandAccepted, sendingCommandLock
from pymavlink import mavutil

if TYPE_CHECKING:
Expand Down Expand Up @@ -55,6 +55,7 @@ def checkMotorTestValues(

return throttle, duration, None

@sendingCommandLock
def testOneMotor(self, data: MotorTestAllValues) -> Response:
"""
Test a single motor.
Expand Down Expand Up @@ -121,6 +122,7 @@ def testOneMotor(self, data: MotorTestAllValues) -> Response:
"message": f"Motor test for motor {motor_letter} not started, serial exception",
}

@sendingCommandLock
def testMotorSequence(self, data: MotorTestThrottleDurationAndNumber) -> Response:
"""
Test a sequence of motors.
Expand Down Expand Up @@ -174,6 +176,7 @@ def testMotorSequence(self, data: MotorTestThrottleDurationAndNumber) -> Respons
"message": "Motor sequence test not started, serial exception",
}

@sendingCommandLock
def testAllMotors(self, data: MotorTestThrottleDurationAndNumber) -> Response:
"""
Test all motors.
Expand Down
47 changes: 26 additions & 21 deletions radio/app/controllers/navController.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

import serial
from app.customTypes import Response
from app.utils import commandAccepted
from app.utils import commandAccepted, sendingCommandLock
from pymavlink import mavutil

if TYPE_CHECKING:
Expand All @@ -24,6 +24,7 @@ def __init__(self, drone: Drone) -> None:
self.loiter_radius_param_type = mavutil.mavlink.MAV_PARAM_TYPE_INT16
self.loiter_radius = 80.0 # Default loiter radius

@sendingCommandLock
def getHomePosition(self) -> Response:
"""
Request the current home position from the drone.
Expand All @@ -41,7 +42,7 @@ def getHomePosition(self) -> Response:
self.drone.is_listening = True

if response:
self.drone.logger.info(f"Home position received, {response}")
self.drone.logger.info("Home position received")

home_position = {
"lat": response.latitude,
Expand All @@ -68,6 +69,7 @@ def getHomePosition(self) -> Response:
"message": "Could not get home position, serial exception",
}

@sendingCommandLock
def setHomePosition(self, lat: float, lon: float, alt: float) -> Response:
"""
Set the home point of the drone.
Expand Down Expand Up @@ -133,12 +135,14 @@ def takeoff(self, alt: float) -> Response:
return guidedModeSetResult

self.drone.is_listening = False
self.drone.sending_command_lock.acquire()
Comment thread
1Blademaster marked this conversation as resolved.

self.drone.sendCommand(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, param7=alt)

try:
response = self.drone.master.recv_match(type="COMMAND_ACK", blocking=True)
self.drone.is_listening = True
self.drone.sending_command_lock.release()

if commandAccepted(response, mavutil.mavlink.MAV_CMD_NAV_TAKEOFF):
self.drone.is_listening = True
Expand All @@ -157,6 +161,7 @@ def takeoff(self, alt: float) -> Response:
"message": "Could not takeoff, serial exception",
}

@sendingCommandLock
def land(self) -> Response:
"""
Tells the drone to land.
Expand Down Expand Up @@ -205,24 +210,25 @@ def reposition(self, lat: float, lon: float, alt: float) -> Response:

self.drone.is_listening = False

self.drone.master.mav.set_position_target_global_int_send(
0,
self.drone.target_system,
self.drone.target_component,
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
65016, # Bitmask to ignore all values except for x, y and z
int(lat * 1e7),
int(lon * 1e7),
alt,
0,
0,
0,
0,
0,
0,
0,
0,
)
with self.drone.sending_command_lock:
Comment thread
1Blademaster marked this conversation as resolved.
self.drone.master.mav.set_position_target_global_int_send(
0,
self.drone.target_system,
self.drone.target_component,
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
65016, # Bitmask to ignore all values except for x, y and z
int(lat * 1e7),
int(lon * 1e7),
alt,
0,
0,
0,
0,
0,
0,
0,
0,
)

self.drone.logger.info(f"Reposition command sent to {lat}, {lon}, {alt}m")

Expand Down Expand Up @@ -250,7 +256,6 @@ def getLoiterRadius(self) -> Response:
"""
Get the loiter radius of the drone.
"""

loiter_radius_data = self.drone.paramsController.getSingleParam(
"WP_LOITER_RAD", timeout=1.5
)
Expand Down
Loading
Loading