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
2 changes: 1 addition & 1 deletion gcs/src/components/missions/missionStatistics.jsx
Original file line number Diff line number Diff line change
Expand Up @@ -213,7 +213,7 @@ export default function MissionStatistics({ missionItems }) {
value={maxSlopeGradient.maxGradient}
tooltip={
maxSlopeGradient.points &&
`Between ${maxSlopeGradient.points[0].seq} and ${maxSlopeGradient.points[1].seq}`
`Between ${maxSlopeGradient.points[0]?.seq} and ${maxSlopeGradient.points[1]?.seq}`
}
units="%"
/>
Expand Down
2 changes: 2 additions & 0 deletions radio/app/controllers/missionController.py
Original file line number Diff line number Diff line change
Expand Up @@ -605,6 +605,8 @@ def uploadMission(
"success": False,
"message": "Could not upload mission, received mission acknowledgement error",
}
elif response.msgname == "MISSION_ACK" and response.type == 0:
continue # Continue to next iteration if we received a MISSION_ACK
elif response.mission_type == mission_type:
self.drone.logger.debug(
f"Sending mission item {response.seq} out of {new_loader.count()-1}"
Expand Down
15 changes: 15 additions & 0 deletions radio/tests/mission_test_files/default_fence.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
QGC WPL 110
0 1 0 16 0 0 0 0 52.7806539 -0.7083070 136.350000 1
1 0 3 5001 6.00000000 0.00000000 0.00000000 0.00000000 52.78146190 -0.71057081 0.000000 1
2 0 3 5001 6.00000000 0.00000000 0.00000000 0.00000000 52.78105306 -0.71029186 1.000000 1
3 0 3 5001 6.00000000 0.00000000 0.00000000 0.00000000 52.78003421 -0.71083903 2.000000 1
4 0 3 5001 6.00000000 0.00000000 0.00000000 0.00000000 52.78185126 -0.70354342 3.000000 1
5 0 3 5001 6.00000000 0.00000000 0.00000000 0.00000000 52.78305826 -0.70601106 4.000000 1
6 0 3 5001 6.00000000 0.00000000 0.00000000 0.00000000 52.78254562 -0.70815682 5.000000 1
7 0 3 5004 25.00000000 0.00000000 0.00000000 0.00000000 52.77965780 -0.70921630 0.000000 1
8 0 3 5003 50.00000000 0.00000000 0.00000000 0.00000000 52.78019000 -0.70440170 0.000000 1
9 0 3 5002 5.00000000 0.00000000 0.00000000 0.00000000 52.78282465 -0.70610762 0.000000 1
10 0 3 5002 5.00000000 0.00000000 0.00000000 0.00000000 52.78187073 -0.70415497 1.000000 1
11 0 3 5002 5.00000000 0.00000000 0.00000000 0.00000000 52.78144892 -0.70581794 2.000000 1
12 0 3 5002 5.00000000 0.00000000 0.00000000 0.00000000 52.78218871 -0.70580721 3.000000 1
13 0 3 5002 5.00000000 0.00000000 0.00000000 0.00000000 52.78263647 -0.70689082 4.000000 1
9 changes: 9 additions & 0 deletions radio/tests/mission_test_files/default_mission.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
QGC WPL 110
0 1 0 16 0 0 0 0 52.7806539 -0.7083070 136.350000 1
1 0 3 22 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 30.000000 1
2 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 52.78031970 -0.70979300 30.000000 1
3 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 52.78122830 -0.70989490 30.000000 1
4 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 52.78169880 -0.70795300 30.000000 1
5 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 52.78144240 -0.70571600 30.000000 1
6 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 52.78079670 -0.70659580 30.000000 1
7 0 3 21 0.00000000 0.00000000 0.00000000 0.00000000 52.78043980 -0.70819970 0.000000 1
4 changes: 4 additions & 0 deletions radio/tests/mission_test_files/default_rally.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
QGC WPL 110
0 1 0 16 0 0 0 0 52.7806539 -0.7083070 136.350000 1
1 0 3 5100 0.00000000 0.00000000 0.00000000 0.00000000 52.78100110 -0.70948720 10.000000 1
2 0 3 5100 0.00000000 0.00000000 0.00000000 0.00000000 52.78211080 -0.70567850 10.000000 1
Original file line number Diff line number Diff line change
@@ -0,0 +1,240 @@
{
"success": true,
"mission_type": "fence",
"items": [
{
"autocontinue": 0,
"command": 5001,
"current": 0,
"frame": 0,
"mavpackettype": "MISSION_ITEM_INT",
"mission_type": 1,
"param1": 6.0,
"param2": 0.0,
"param3": 0.0,
"param4": 0.0,
"seq": 0,
"target_component": 0,
"target_system": 255,
"x": 527814618,
"y": -7105708,
"z": 0.0
},
{
"autocontinue": 0,
"command": 5001,
"current": 0,
"frame": 0,
"mavpackettype": "MISSION_ITEM_INT",
"mission_type": 1,
"param1": 6.0,
"param2": 0.0,
"param3": 0.0,
"param4": 0.0,
"seq": 1,
"target_component": 0,
"target_system": 255,
"x": 527810530,
"y": -7102918,
"z": 0.0
},
{
"autocontinue": 0,
"command": 5001,
"current": 0,
"frame": 0,
"mavpackettype": "MISSION_ITEM_INT",
"mission_type": 1,
"param1": 6.0,
"param2": 0.0,
"param3": 0.0,
"param4": 0.0,
"seq": 2,
"target_component": 0,
"target_system": 255,
"x": 527800342,
"y": -7108390,
"z": 0.0
},
{
"autocontinue": 0,
"command": 5001,
"current": 0,
"frame": 0,
"mavpackettype": "MISSION_ITEM_INT",
"mission_type": 1,
"param1": 6.0,
"param2": 0.0,
"param3": 0.0,
"param4": 0.0,
"seq": 3,
"target_component": 0,
"target_system": 255,
"x": 527818512,
"y": -7035434,
"z": 0.0
},
{
"autocontinue": 0,
"command": 5001,
"current": 0,
"frame": 0,
"mavpackettype": "MISSION_ITEM_INT",
"mission_type": 1,
"param1": 6.0,
"param2": 0.0,
"param3": 0.0,
"param4": 0.0,
"seq": 4,
"target_component": 0,
"target_system": 255,
"x": 527830582,
"y": -7060110,
"z": 0.0
},
{
"autocontinue": 0,
"command": 5001,
"current": 0,
"frame": 0,
"mavpackettype": "MISSION_ITEM_INT",
"mission_type": 1,
"param1": 6.0,
"param2": 0.0,
"param3": 0.0,
"param4": 0.0,
"seq": 5,
"target_component": 0,
"target_system": 255,
"x": 527825456,
"y": -7081568,
"z": 0.0
},
{
"autocontinue": 0,
"command": 5004,
"current": 0,
"frame": 0,
"mavpackettype": "MISSION_ITEM_INT",
"mission_type": 1,
"param1": 25.0,
"param2": 0.0,
"param3": 0.0,
"param4": 0.0,
"seq": 6,
"target_component": 0,
"target_system": 255,
"x": 527796578,
"y": -7092163,
"z": 0.0
},
{
"autocontinue": 0,
"command": 5003,
"current": 0,
"frame": 0,
"mavpackettype": "MISSION_ITEM_INT",
"mission_type": 1,
"param1": 50.0,
"param2": 0.0,
"param3": 0.0,
"param4": 0.0,
"seq": 7,
"target_component": 0,
"target_system": 255,
"x": 527801900,
"y": -7044017,
"z": 0.0
},
{
"autocontinue": 0,
"command": 5002,
"current": 0,
"frame": 0,
"mavpackettype": "MISSION_ITEM_INT",
"mission_type": 1,
"param1": 5.0,
"param2": 0.0,
"param3": 0.0,
"param4": 0.0,
"seq": 8,
"target_component": 0,
"target_system": 255,
"x": 527828246,
"y": -7061076,
"z": 0.0
},
{
"autocontinue": 0,
"command": 5002,
"current": 0,
"frame": 0,
"mavpackettype": "MISSION_ITEM_INT",
"mission_type": 1,
"param1": 5.0,
"param2": 0.0,
"param3": 0.0,
"param4": 0.0,
"seq": 9,
"target_component": 0,
"target_system": 255,
"x": 527818707,
"y": -7041549,
"z": 0.0
},
{
"autocontinue": 0,
"command": 5002,
"current": 0,
"frame": 0,
"mavpackettype": "MISSION_ITEM_INT",
"mission_type": 1,
"param1": 5.0,
"param2": 0.0,
"param3": 0.0,
"param4": 0.0,
"seq": 10,
"target_component": 0,
"target_system": 255,
"x": 527814489,
"y": -7058179,
"z": 0.0
},
{
"autocontinue": 0,
"command": 5002,
"current": 0,
"frame": 0,
"mavpackettype": "MISSION_ITEM_INT",
"mission_type": 1,
"param1": 5.0,
"param2": 0.0,
"param3": 0.0,
"param4": 0.0,
"seq": 11,
"target_component": 0,
"target_system": 255,
"x": 527821887,
"y": -7058072,
"z": 0.0
},
{
"autocontinue": 0,
"command": 5002,
"current": 0,
"frame": 0,
"mavpackettype": "MISSION_ITEM_INT",
"mission_type": 1,
"param1": 5.0,
"param2": 0.0,
"param3": 0.0,
"param4": 0.0,
"seq": 12,
"target_component": 0,
"target_system": 255,
"x": 527826364,
"y": -7068908,
"z": 0.0
}
]
}
Loading
Loading