Skip to content

Commit 9ff87d6

Browse files
Alpha 0.1.10/569 write missions to drone (#589)
* alpha-0.1.9/hf/583-fix-camera-not-working-on-electron Fixed electron build camera issues (#584) * Add mission write functionality * Add change to waypoints parsing function to allow for rally and fence types * Add tests for missions * Add improvements from copilot review --------- Co-authored-by: Joe <joantpat@gmail.com>
1 parent 9306b43 commit 9ff87d6

7 files changed

Lines changed: 395 additions & 50 deletions

File tree

.vscode/launch.json

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
{
2+
"configurations": [
3+
{
4+
"name": "Python Debugger: Backend",
5+
"type": "debugpy",
6+
"request": "launch",
7+
"program": "${workspaceFolder}/radio/app.py",
8+
"console": "integratedTerminal"
9+
}
10+
]
11+
}

gcs/electron/main.ts

Lines changed: 23 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -112,11 +112,28 @@ type ResizeCallback = (event: Event, arg1: Rectangle) => void;
112112

113113
let currentResizeHandler: ResizeCallback | null = null
114114

115+
/**
116+
* If id and name are provided, passes the id and name to the webcam popout so that the given
117+
* video stream is rendered. If id or name are not provided, prevents any video streams from
118+
* being rendered on the window so that the webcam is not showing in the background
119+
* @param id The device stream ID
120+
* @param name The name of the device
121+
*/
122+
function loadWebcam(id: string = "", name: string = ""){
123+
124+
const params: string = id && name ? "/webcam?deviceId=" + id + "&deviceName=" + name : "/webcam";
125+
126+
if (VITE_DEV_SERVER_URL)
127+
webcamPopoutWin?.loadURL(VITE_DEV_SERVER_URL + "#" + params)
128+
else
129+
webcamPopoutWin?.loadFile(path.join(process.env.DIST, 'index.html'), {hash: params})
130+
}
131+
115132
function openWebcamPopout(videoStreamId: string, name: string, aspect: number){
116133

117134
if (webcamPopoutWin === null) return;
135+
loadWebcam(videoStreamId, name);
118136

119-
webcamPopoutWin.loadURL("http://localhost:5173/#/webcam?deviceId=" + videoStreamId + "&deviceName=" + name);
120137
webcamPopoutWin.setTitle(name);
121138

122139
// Remove previous resize handler
@@ -150,7 +167,7 @@ function openWebcamPopout(videoStreamId: string, name: string, aspect: number){
150167

151168
function closeWebcamPopout(){
152169
webcamPopoutWin?.hide()
153-
webcamPopoutWin?.loadURL("http://localhost:5173/#/webcam")
170+
loadWebcam();
154171
win?.webContents.send("webcam-closed");
155172
}
156173

@@ -210,7 +227,10 @@ function createWindow() {
210227
fullscreen: false,
211228
fullscreenable: false,
212229
});
213-
webcamPopoutWin.loadURL("http://localhost:5173/#/webcam")
230+
231+
232+
// We load the webcam route here to prevent having to load the page on popout
233+
loadWebcam();
214234

215235
// Open links in browser, not within the electron window.
216236
// Note, links must have target="_blank"

gcs/src/missions.jsx

Lines changed: 19 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -135,10 +135,19 @@ export default function Missions() {
135135
showSuccessNotification(`${data.mission_type} read successfully`)
136136
})
137137

138+
socket.on("write_mission_result", (data) => {
139+
if (data.success) {
140+
showSuccessNotification(data.message)
141+
} else {
142+
showErrorNotification(data.message)
143+
}
144+
})
145+
138146
return () => {
139147
socket.off("incoming_msg")
140148
socket.off("home_position_result")
141149
socket.off("current_mission")
150+
socket.off("write_mission_result")
142151
}
143152
}, [connected])
144153

@@ -183,7 +192,16 @@ export default function Missions() {
183192
}
184193

185194
function writeMissionToDrone() {
186-
return
195+
if (activeTab === "mission") {
196+
socket.emit("write_current_mission", {
197+
type: "mission",
198+
items: missionItems,
199+
})
200+
} else if (activeTab === "fence") {
201+
socket.emit("write_current_mission", { type: "fence", items: fenceItems })
202+
} else if (activeTab === "rally") {
203+
socket.emit("write_current_mission", { type: "rally", items: rallyItems })
204+
}
187205
}
188206

189207
function importMissionFromFile() {

radio/app/controllers/missionController.py

Lines changed: 73 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55

66
import serial
77
from app.customTypes import Response
8-
from app.utils import commandAccepted, wpToMissionItemInt
8+
from app.utils import commandAccepted
99
from pymavlink import mavutil, mavwp
1010

1111
if TYPE_CHECKING:
@@ -238,7 +238,7 @@ def getItemDetails(
238238
if not mission_type_check.get("success"):
239239
return mission_type_check
240240

241-
failure_message = f"Failed to get mission item {item_number}/{mission_count} for mission type {mission_type}"
241+
failure_message = f"Failed to get mission item {item_number}/{mission_count - 1} for mission type {mission_type}"
242242

243243
self.drone.is_listening = False
244244

@@ -260,7 +260,7 @@ def getItemDetails(
260260

261261
if response:
262262
self.drone.logger.debug(
263-
f"Got response for mission item {item_number}/{mission_count} for mission type {mission_type}"
263+
f"Got response for mission item {item_number}/{mission_count - 1} for mission type {mission_type}"
264264
)
265265
return {
266266
"success": True,
@@ -269,7 +269,7 @@ def getItemDetails(
269269

270270
else:
271271
self.drone.logger.error(
272-
f"Got no response for mission item {item_number}/{mission_count} for mission type {mission_type}"
272+
f"Got no response for mission item {item_number}/{mission_count - 1} for mission type {mission_type}"
273273
)
274274
return {
275275
"success": False,
@@ -279,7 +279,7 @@ def getItemDetails(
279279
except serial.serialutil.SerialException:
280280
self.drone.is_listening = True
281281
self.drone.logger.error(
282-
f"Got no response for mission item {item_number}/{mission_count}, serial exception"
282+
f"Got no response for mission item {item_number}/{mission_count - 1}, serial exception"
283283
)
284284
return {
285285
"success": False,
@@ -454,9 +454,63 @@ def loadWaypointFile(self, file_path: str, mission_type: int) -> Response:
454454
"message": f"Waypoint file loaded {loader.count()} points successfully",
455455
}
456456

457-
def uploadMission(self, mission_type: int) -> Response:
457+
def _parseWaypointsListIntoLoader(
458+
self, waypoints: List[dict], mission_type: int
459+
) -> mavwp.MAVWPLoader:
458460
"""
459-
Uploads the current mission to the drone.
461+
Parses a list of waypoints into a MAVWPLoader object.
462+
"""
463+
464+
if mission_type == TYPE_MISSION:
465+
loader = mavwp.MAVWPLoader(
466+
target_system=self.drone.target_system,
467+
target_component=self.drone.target_component,
468+
)
469+
elif mission_type == TYPE_FENCE:
470+
loader = mavwp.MissionItemProtocol_Fence(
471+
target_system=self.drone.target_system,
472+
target_component=self.drone.target_component,
473+
)
474+
elif mission_type == TYPE_RALLY:
475+
loader = mavwp.MissionItemProtocol_Rally(
476+
target_system=self.drone.target_system,
477+
target_component=self.drone.target_component,
478+
)
479+
480+
for wp in waypoints:
481+
if isinstance(wp, mavutil.mavlink.MAVLink_mission_item_int_message):
482+
loader.add(wp)
483+
elif isinstance(wp, dict):
484+
# Convert dict to MAVLink mission item int message
485+
p = mavutil.mavlink.MAVLink_mission_item_int_message(
486+
self.drone.target_system,
487+
self.drone.target_component,
488+
wp["seq"],
489+
wp["frame"],
490+
wp["command"],
491+
wp["current"],
492+
wp["autocontinue"],
493+
wp["param1"],
494+
wp["param2"],
495+
wp["param3"],
496+
wp["param4"],
497+
int(wp["x"]),
498+
int(wp["y"]),
499+
wp["z"],
500+
wp["mission_type"],
501+
)
502+
loader.add(p)
503+
else:
504+
self.drone.logger.error(
505+
f"Invalid waypoint type {type(wp)} in waypoints list"
506+
)
507+
raise ValueError(f"Invalid waypoint type {type(wp)} in waypoints list")
508+
509+
return loader
510+
511+
def uploadMission(self, mission_type: int, waypoints: List[dict]) -> Response:
512+
"""
513+
Uploads the current mission to the drone. This method overwrites the current loader if the upload is successful.
460514
461515
Args:
462516
mission_type (int): The type of mission to upload. 0=Mission,1=Fence,2=Rally.
@@ -465,14 +519,9 @@ def uploadMission(self, mission_type: int) -> Response:
465519
if not mission_type_check.get("success"):
466520
return mission_type_check
467521

468-
if mission_type == TYPE_MISSION:
469-
loader = self.missionLoader
470-
elif mission_type == TYPE_FENCE:
471-
loader = self.fenceLoader
472-
else:
473-
loader = self.rallyLoader
522+
new_loader = self._parseWaypointsListIntoLoader(waypoints, mission_type)
474523

475-
if loader.count() == 0:
524+
if new_loader.count() == 0:
476525
return {
477526
"success": False,
478527
"message": f"No waypoints loaded for the mission type of {mission_type}",
@@ -487,7 +536,7 @@ def uploadMission(self, mission_type: int) -> Response:
487536
self.drone.master.mav.mission_count_send(
488537
self.drone.target_system,
489538
self.drone.target_component,
490-
loader.count(),
539+
new_loader.count(),
491540
mission_type=mission_type,
492541
)
493542

@@ -515,13 +564,11 @@ def uploadMission(self, mission_type: int) -> Response:
515564
}
516565
elif response.mission_type == mission_type:
517566
self.drone.logger.debug(
518-
f"Sending mission item {response.seq} out of {loader.count()}"
519-
)
520-
self.drone.master.mav.send(
521-
wpToMissionItemInt(loader.item(response.seq))
567+
f"Sending mission item {response.seq} out of {new_loader.count()-1}"
522568
)
569+
self.drone.master.mav.send(new_loader.item(response.seq))
523570

524-
if response.seq == loader.count() - 1:
571+
if response.seq == new_loader.count() - 1:
525572
mission_ack_response = self.drone.master.recv_match(
526573
type=[
527574
"MISSION_ACK",
@@ -537,6 +584,12 @@ def uploadMission(self, mission_type: int) -> Response:
537584
and mission_ack_response.mission_type == mission_type
538585
):
539586
self.drone.logger.info("Uploaded mission successfully")
587+
if mission_type == TYPE_MISSION:
588+
self.missionLoader = new_loader
589+
elif mission_type == TYPE_FENCE:
590+
self.fenceLoader = new_loader
591+
else:
592+
self.rallyLoader = new_loader
540593
return {
541594
"success": True,
542595
"message": "Mission uploaded successfully",

radio/app/endpoints/mission.py

Lines changed: 50 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,11 @@ class CurrentMissionType(TypedDict):
99
type: str
1010

1111

12+
class WriteCurrentMissionType(TypedDict):
13+
type: str
14+
items: list[dict]
15+
16+
1217
class ControlMissionType(TypedDict):
1318
action: str
1419

@@ -90,6 +95,51 @@ def getCurrentMissionAll() -> None:
9095
)
9196

9297

98+
@socketio.on("write_current_mission")
99+
def writeCurrentMission(data: WriteCurrentMissionType) -> None:
100+
"""
101+
Writes the current mission to the drone, only works if missions screen is loaded.
102+
"""
103+
if droneStatus.state != "missions":
104+
socketio.emit(
105+
"params_error",
106+
{
107+
"message": "You must be on the missions screen to write the current mission."
108+
},
109+
)
110+
logger.debug(f"Current state: {droneStatus.state}")
111+
return
112+
113+
if not droneStatus.drone:
114+
return notConnectedError(action="write current mission")
115+
116+
mission_type = data.get("type")
117+
mission_type_array = ["mission", "fence", "rally"]
118+
119+
if mission_type not in mission_type_array:
120+
socketio.emit(
121+
"write_mission_result",
122+
{
123+
"success": False,
124+
"message": f"Invalid mission type. Must be 'mission', 'fence', or 'rally', got {mission_type}.",
125+
},
126+
)
127+
logger.error(
128+
f"Invalid mission type: {mission_type}. Must be 'mission', 'fence', or 'rally'."
129+
)
130+
return
131+
132+
items = data.get("items", [])
133+
134+
result = droneStatus.drone.missionController.uploadMission(
135+
mission_type_array.index(mission_type), items
136+
)
137+
if not result.get("success"):
138+
logger.error(result.get("message"))
139+
140+
socketio.emit("write_mission_result", result)
141+
142+
93143
@socketio.on("control_mission")
94144
def controlMission(data: ControlMissionType) -> None:
95145
"""

radio/app/utils.py

Lines changed: 0 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -185,32 +185,6 @@ def sendMessage(msg: Any) -> None:
185185
socketio.emit("incoming_msg", data)
186186

187187

188-
def wpToMissionItemInt(
189-
wp: mavutil.mavlink.MAVLink_message,
190-
) -> mavutil.mavlink.MAVLink_message:
191-
if wp.get_type() == "MISSION_ITEM_INT":
192-
return wp
193-
194-
wp_int = mavutil.mavlink.MAVLink_mission_item_int_message(
195-
wp.target_system,
196-
wp.target_component,
197-
wp.seq,
198-
wp.frame,
199-
wp.command,
200-
wp.current,
201-
wp.autocontinue,
202-
wp.param1,
203-
wp.param2,
204-
wp.param3,
205-
wp.param4,
206-
int(wp.x * 1e7),
207-
int(wp.y * 1e7),
208-
wp.z,
209-
wp.mission_type,
210-
)
211-
return wp_int
212-
213-
214188
FIXED_WING_TYPES = [
215189
mavutil.mavlink.MAV_TYPE_FIXED_WING,
216190
mavutil.mavlink.MAV_TYPE_VTOL_DUOROTOR,

0 commit comments

Comments
 (0)