diff --git a/SaveFiles/Klingenbach.wima b/SaveFiles/Klingenbach.wima new file mode 100644 index 0000000000000000000000000000000000000000..cf7bbf12c8423b4103c66b8d35e2eabd54be05c3 --- /dev/null +++ b/SaveFiles/Klingenbach.wima @@ -0,0 +1,2003 @@ +{ + "AreaItems": [ + { + "AreaType": "Operation Area", + "BorderPolygonOffset": 5, + "BottomLayerAltitude": 10, + "LayerDistance": 2, + "NumberOfLayers": 1, + "maxAltitude": 30, + "polygon": [ + [ + 47.76814130285164, + 16.530347986094483 + ], + [ + 47.768405048556495, + 16.530985979841546 + ], + [ + 47.76804190441199, + 16.531139778691 + ], + [ + 47.76780598957649, + 16.53043671316874 + ] + ] + }, + { + "AreaType": "Service Area", + "maxAltitude": 30, + "polygon": [ + [ + 47.76775534116353, + 16.53042897362141 + ], + [ + 47.76780537519892, + 16.530588940000627 + ], + [ + 47.76771276042304, + 16.530596856755835 + ], + [ + 47.767657403517816, + 16.530447977233962 + ] + ] + }, + { + "AreaType": "Corridor", + "maxAltitude": 30, + "polygon": [ + [ + 47.76777556807082, + 16.53055092911842 + ], + [ + 47.76781389199906, + 16.530691889469182 + ], + [ + 47.76790225054143, + 16.53064278774005 + ], + [ + 47.76792886425493, + 16.530728315200577 + ], + [ + 47.7677888758332, + 16.53078295757672 + ], + [ + 47.767725534701874, + 16.530560429265805 + ] + ] + } + ], + "MissionItems": { + "fileType": "Plan", + "geoFence": { + "circles": [ + ], + "polygons": [ + ], + "version": 2 + }, + "groundStation": "QGroundControl", + "mission": { + "cruiseSpeed": 15, + "firmwareType": 12, + "hoverSpeed": 5, + "items": [ + { + "autoContinue": true, + "command": 530, + "doJumpId": 1, + "frame": 2, + "params": [ + 0, + 2, + null, + null, + null, + null, + null + ], + "type": "SimpleItem" + }, + { + "AMSLAltAboveTerrain": null, + "Altitude": 50, + "AltitudeMode": 1, + "autoContinue": true, + "command": 22, + "doJumpId": 2, + "frame": 3, + "params": [ + 15, + 0, + 0, + null, + 47.76773272010195, + 16.53051568687008, + 50 + ], + "type": "SimpleItem" + }, + { + "AMSLAltAboveTerrain": null, + "Altitude": 50, + "AltitudeMode": 1, + "autoContinue": true, + "command": 16, + "doJumpId": 3, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76781389199906, + 16.530691889469182, + 50 + ], + "type": "SimpleItem" + }, + { + "AMSLAltAboveTerrain": null, + "Altitude": 50, + "AltitudeMode": 1, + "autoContinue": true, + "command": 16, + "doJumpId": 4, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76787939989352, + 16.530655486091632, + 50 + ], + "type": "SimpleItem" + }, + { + "TransectStyleComplexItem": { + "CameraCalc": { + "AdjustedFootprintFrontal": 25, + "AdjustedFootprintSide": 2, + "CameraName": "Manual (no camera specs)", + "DistanceToSurface": 50, + "DistanceToSurfaceRelative": true, + "version": 1 + }, + "CameraShots": 47, + "CameraTriggerInTurnAround": true, + "FollowTerrain": false, + "HoverAndCapture": false, + "Items": [ + { + "autoContinue": true, + "command": 16, + "doJumpId": 5, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76781102855973, + 16.530451729978072, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 6, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 7, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 8, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76787704224262, + 16.53041791205613, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 9, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76799131139914, + 16.530387675399677, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 10, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 11, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.7678191324091, + 16.530475880495707, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 12, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76782723625342, + 16.53050003102087, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 13, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 14, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76810558054772, + 16.530357438610363, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 15, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76814793980895, + 16.530364040530976, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 16, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 17, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76783534009267, + 16.530524181553563, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 18, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76784344392685, + 16.530548332093776, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 19, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 20, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76815759518296, + 16.530387396369257, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 21, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.768167250552246, + 16.530410752216213, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 22, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 23, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76785154775597, + 16.530572482641514, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 24, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76785965158001, + 16.53059663319678, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 25, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 26, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76817690591679, + 16.530434108071837, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 27, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.768186561276586, + 16.530457463936134, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 28, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 29, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76786775539899, + 16.530620783759574, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 30, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.767875859212914, + 16.53064493432989, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 31, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 32, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.768196216631665, + 16.530480819809103, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 33, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76820587198199, + 16.53050417569074, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 34, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 35, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76788396302177, + 16.530669084907732, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 36, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76789206682555, + 16.530693235493104, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 37, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 38, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.768215527327584, + 16.53052753158105, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 39, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76822518266844, + 16.530550887480036, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 40, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 41, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.767900170624266, + 16.530717386085996, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 42, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76790827441793, + 16.530741536686417, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 43, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 44, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76823483800455, + 16.530574243387694, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 45, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.768244493335935, + 16.53059759930402, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 46, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 47, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76791637820651, + 16.530765687294366, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 48, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76792448199002, + 16.530789837909836, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 49, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 50, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.768254148662564, + 16.530620955229015, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 51, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76826380398446, + 16.53064431116269, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 52, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 53, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76793258576849, + 16.530813988532834, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 54, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.767940689541874, + 16.530838139163357, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 55, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 56, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.768273459301625, + 16.530667667105032, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 57, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76828311461405, + 16.530691023056043, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 58, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 59, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76794879331019, + 16.53086228980141, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 60, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76795689707344, + 16.53088644044698, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 61, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 62, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.768292769921736, + 16.53071437901573, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 63, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76830242522469, + 16.530737734984086, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 64, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 65, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76796500083164, + 16.530910591100085, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 66, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.767973104584755, + 16.530934741760714, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 67, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 68, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76831208052289, + 16.530761090961114, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 69, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.768321735816365, + 16.530784446946814, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 70, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 71, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76798120833281, + 16.530958892428863, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 72, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.7679893120758, + 16.53098304310454, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 73, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 74, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76833139110509, + 16.530807802941187, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 75, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.7683410463891, + 16.53083115894423, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 76, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 77, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76799741581374, + 16.531007193787744, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 78, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.7680055195466, + 16.531031344478475, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 79, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 80, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.768350701668346, + 16.530854514955948, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 81, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.768360356942864, + 16.530877870976333, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 82, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 83, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.768013623274385, + 16.53105549517673, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 84, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76802172699712, + 16.531079645882514, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 85, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 86, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.768370012212635, + 16.53090122700539, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 87, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76837966747768, + 16.530924583043124, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 88, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 89, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76802983071477, + 16.53110379659582, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 90, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76803793442736, + 16.53112794731665, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 91, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 92, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76838932273799, + 16.530947939089526, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 93, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.768398977993556, + 16.5309712951446, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 94, + "frame": 2, + "params": [ + 25, + 0, + 1, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 16, + "doJumpId": 95, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76820456269355, + 16.531070889913362, + 50 + ], + "type": "SimpleItem" + }, + { + "autoContinue": true, + "command": 206, + "doJumpId": 96, + "frame": 2, + "params": [ + 0, + 0, + 0, + 0, + 0, + 0, + 0 + ], + "type": "SimpleItem" + } + ], + "Refly90Degrees": false, + "TurnAroundDistance": 0, + "VisualTransectPoints": [ + [ + 47.76781102855973, + 16.530451729978072 + ], + [ + 47.76787704224262, + 16.53041791205613 + ], + [ + 47.76799131139914, + 16.530387675399677 + ], + [ + 47.7678191324091, + 16.530475880495707 + ], + [ + 47.76782723625342, + 16.53050003102087 + ], + [ + 47.76810558054772, + 16.530357438610363 + ], + [ + 47.76814793980895, + 16.530364040530976 + ], + [ + 47.76783534009267, + 16.530524181553563 + ], + [ + 47.76784344392685, + 16.530548332093776 + ], + [ + 47.76815759518296, + 16.530387396369257 + ], + [ + 47.768167250552246, + 16.530410752216213 + ], + [ + 47.76785154775597, + 16.530572482641514 + ], + [ + 47.76785965158001, + 16.53059663319678 + ], + [ + 47.76817690591679, + 16.530434108071837 + ], + [ + 47.768186561276586, + 16.530457463936134 + ], + [ + 47.76786775539899, + 16.530620783759574 + ], + [ + 47.767875859212914, + 16.53064493432989 + ], + [ + 47.768196216631665, + 16.530480819809103 + ], + [ + 47.76820587198199, + 16.53050417569074 + ], + [ + 47.76788396302177, + 16.530669084907732 + ], + [ + 47.76789206682555, + 16.530693235493104 + ], + [ + 47.768215527327584, + 16.53052753158105 + ], + [ + 47.76822518266844, + 16.530550887480036 + ], + [ + 47.767900170624266, + 16.530717386085996 + ], + [ + 47.76790827441793, + 16.530741536686417 + ], + [ + 47.76823483800455, + 16.530574243387694 + ], + [ + 47.768244493335935, + 16.53059759930402 + ], + [ + 47.76791637820651, + 16.530765687294366 + ], + [ + 47.76792448199002, + 16.530789837909836 + ], + [ + 47.768254148662564, + 16.530620955229015 + ], + [ + 47.76826380398446, + 16.53064431116269 + ], + [ + 47.76793258576849, + 16.530813988532834 + ], + [ + 47.767940689541874, + 16.530838139163357 + ], + [ + 47.768273459301625, + 16.530667667105032 + ], + [ + 47.76828311461405, + 16.530691023056043 + ], + [ + 47.76794879331019, + 16.53086228980141 + ], + [ + 47.76795689707344, + 16.53088644044698 + ], + [ + 47.768292769921736, + 16.53071437901573 + ], + [ + 47.76830242522469, + 16.530737734984086 + ], + [ + 47.76796500083164, + 16.530910591100085 + ], + [ + 47.767973104584755, + 16.530934741760714 + ], + [ + 47.76831208052289, + 16.530761090961114 + ], + [ + 47.768321735816365, + 16.530784446946814 + ], + [ + 47.76798120833281, + 16.530958892428863 + ], + [ + 47.7679893120758, + 16.53098304310454 + ], + [ + 47.76833139110509, + 16.530807802941187 + ], + [ + 47.7683410463891, + 16.53083115894423 + ], + [ + 47.76799741581374, + 16.531007193787744 + ], + [ + 47.7680055195466, + 16.531031344478475 + ], + [ + 47.768350701668346, + 16.530854514955948 + ], + [ + 47.768360356942864, + 16.530877870976333 + ], + [ + 47.768013623274385, + 16.53105549517673 + ], + [ + 47.76802172699712, + 16.531079645882514 + ], + [ + 47.768370012212635, + 16.53090122700539 + ], + [ + 47.76837966747768, + 16.530924583043124 + ], + [ + 47.76802983071477, + 16.53110379659582 + ], + [ + 47.76803793442736, + 16.53112794731665 + ], + [ + 47.76838932273799, + 16.530947939089526 + ], + [ + 47.768398977993556, + 16.5309712951446 + ], + [ + 47.76820456269355, + 16.531070889913362 + ] + ], + "version": 1 + }, + "angle": 161, + "complexItemType": "survey", + "entryLocation": 0, + "flyAlternateTransects": false, + "polygon": [ + [ + 47.76814130285164, + 16.530347986094483 + ], + [ + 47.768405048556495, + 16.530985979841546 + ], + [ + 47.76804190441199, + 16.531139778691 + ], + [ + 47.76780598957649, + 16.53043671316874 + ] + ], + "splitConcavePolygons": false, + "type": "ComplexItem", + "version": 5 + }, + { + "AMSLAltAboveTerrain": null, + "Altitude": 50, + "AltitudeMode": 1, + "autoContinue": true, + "command": 16, + "doJumpId": 97, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76790673620743, + 16.53073695257154, + 50 + ], + "type": "SimpleItem" + }, + { + "AMSLAltAboveTerrain": null, + "Altitude": 50, + "AltitudeMode": 1, + "autoContinue": true, + "command": 16, + "doJumpId": 98, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76781389199906, + 16.530691889469182, + 50 + ], + "type": "SimpleItem" + }, + { + "AMSLAltAboveTerrain": null, + "Altitude": 0, + "AltitudeMode": 1, + "autoContinue": true, + "command": 21, + "doJumpId": 99, + "frame": 3, + "params": [ + 0, + 0, + 0, + null, + 47.76773272010195, + 16.53051568687008, + 0 + ], + "type": "SimpleItem" + } + ], + "plannedHomePosition": [ + 47.76773272010195, + 16.53051568687008, + 178 + ], + "vehicleType": 2, + "version": 2 + }, + "rallyPoints": { + "points": [ + ], + "version": 2 + }, + "version": 1 + } +} diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index b0040dae27dc38021a605234542088e545c7eac8..c99ebf2fc54f3594f7b788bca5ead26089aa2158 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -413,7 +413,8 @@ HEADERS += \ src/Wima/WimaVCorridor.h \ src/Wima/WimaTrackerPolyline.h \ src/Wima/WimaController.h \ - src/Wima/WimaVehicle.h + src/Wima/WimaVehicle.h \ + src/Wima/WimaDataContainer.h SOURCES += \ src/api/QGCCorePlugin.cc \ src/api/QGCOptions.cc \ @@ -426,7 +427,8 @@ SOURCES += \ src/Wima/WimaVCorridor.cc \ src/Wima/WimaTrackerPolyline.cc \ src/Wima/WimaController.cc \ - src/Wima/WimaVehicle.cc + src/Wima/WimaVehicle.cc \ + src/Wima/WimaDataContainer.cc # # Unit Test specific configuration goes here (requires full debug build with all plugins) diff --git a/src/FlightDisplay/FlightDisplayView.qml b/src/FlightDisplay/FlightDisplayView.qml index 1edae2934ae56568375eeb3b4729aefa5b482244..98edc17e8dfe643ec90a673895bf86b376bc73d9 100644 --- a/src/FlightDisplay/FlightDisplayView.qml +++ b/src/FlightDisplay/FlightDisplayView.qml @@ -28,14 +28,13 @@ import QGroundControl.FlightMap 1.0 import QGroundControl.Palette 1.0 import QGroundControl.ScreenTools 1.0 import QGroundControl.Vehicle 1.0 +import Wima 1.0 /// Flight Display View QGCView { id: root viewPanel: _panel - property var wimaController - QGCPalette { id: qgcPal; colorGroupEnabled: enabled } property alias guidedController: guidedActionsController @@ -115,6 +114,13 @@ QGCView { Component.onCompleted: start(true /* flyView */) } + WimaController { + id: wimaController + Component.onCompleted: { + startWimaController(true /* flyView */) + } + } + BuiltInPreFlightCheckModel { id: preFlightCheckModel } @@ -129,6 +135,10 @@ QGCView { if(QGroundControl.corePlugin.options.flyViewOverlay.toString().length) { flyViewOverlay.source = QGroundControl.corePlugin.options.flyViewOverlay } + + wimaController.masterController = masterController + wimaController.missionController = masterController.missionController + wimaController.dataContainer = dataContainer } // The following code is used to track vehicle states such that we prompt to remove mission from vehicle when mission completes @@ -331,6 +341,7 @@ QGCView { id: _flightMap anchors.fill: parent planMasterController: masterController + wimaController: wimaController guidedActionsController: _guidedController flightWidgets: flightDisplayViewWidgets rightPanelWidth: ScreenTools.defaultFontPixelHeight * 9 diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml index b71adf181e129193b5724e212aa731f7d91c9227..3ab72e3ca06232ce561bb27853ee26ec3689a44d 100644 --- a/src/FlightDisplay/FlightDisplayViewMap.qml +++ b/src/FlightDisplay/FlightDisplayViewMap.qml @@ -37,12 +37,12 @@ FlightMap { // The following properties must be set by the consumer property var planMasterController + property var wimaController property var guidedActionsController property var flightWidgets property var rightPanelWidth property var qgcView ///< QGCView control which contains this map property var multiVehicleView ///< true: multi-vehicle view, false: single vehicle view - property var wimaController property rect centerViewport: Qt.rect(0, 0, width, height) @@ -196,7 +196,7 @@ FlightMap { // Add wima Areas to the Map WimaMapPolygonVisuals { mapControl: flightMap - mapPolygon: wimaController ? wimaController.joinedArea : undefined + mapPolygon: wimaController.joinedArea borderWidth: 1 borderColor: "transparent" interiorColor: "gray" diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index fce8b868b329011c9b594597840ccb2e5f45d23e..07e9ebe64c185e0912f708d61226fdff0cacca01 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -68,6 +68,7 @@ #include "CoordinateVector.h" #include "PlanMasterController.h" #include "Wima/WimaController.h" //custom +#include "Wima/WimaDataContainer.h" //custom #include "VideoManager.h" #include "VideoSurface.h" #include "VideoReceiver.h" @@ -465,6 +466,7 @@ void QGCApplication::_initCommon(void) #endif // Wima qmlRegisterType ("Wima", 1, 0, "WimaController"); //custom + qmlRegisterType ("Wima", 1, 0, "WimaDataContainer"); //custom // Register Qml Singletons diff --git a/src/Wima/WimaController.cc b/src/Wima/WimaController.cc index 9259319e37798e6b5d8d4c0f91388e24977a560f..3cd57f4d03c293bda27928227198fb20bdea4a6f 100644 --- a/src/Wima/WimaController.cc +++ b/src/Wima/WimaController.cc @@ -6,9 +6,9 @@ const char* WimaController::missionItemsName = "MissionItems"; WimaController::WimaController(QObject *parent) : QObject (parent) - ,_planView (true) - ,_visualItems (new QmlObjectListModel(parent)) + ,_flyView (true) ,_currentPolygonIndex (-1) + ,_container(nullptr) { connect(this, &WimaController::currentPolygonIndexChanged, this, &WimaController::recalcPolygonInteractivity); } @@ -44,36 +44,48 @@ void WimaController::setMissionController(MissionController *missionC) void WimaController::setCurrentPolygonIndex(int index) { - if(index >= 0 && index < _visualItems->count() && index != _currentPolygonIndex){ + if(_container != nullptr && index >= 0 && index < _container->visualItems()->count() && index != _currentPolygonIndex){ _currentPolygonIndex = index; emit currentPolygonIndexChanged(index); } } +void WimaController::setDataContainer(WimaDataContainer *container) +{ + if (container != nullptr && _container != container) { + _container = container; + + emit dataContainerChanged(); + } +} + +void WimaController::startWimaController(bool flyView) +{ + _flyView = flyView; +} + void WimaController::removeArea(int index) { - if(index >= 0 && index < _visualItems->count()){ - WimaArea* area = qobject_cast(_visualItems->removeAt(index)); + if(_container != nullptr && index >= 0 && index < _container->visualItems()->count()){ + WimaArea* area = qobject_cast(_container->visualItems()->removeAt(index)); if ( area == nullptr) { qWarning("WimaController::removeArea(): nullptr catched, internal error."); return; } - disconnect(area, &WimaArea::pathChanged, this, &WimaController::updateJoinedArea); - emit visualItemsChanged(); - if (_visualItems->count() == 0) { + if (_container->visualItems()->count() == 0) { // this branch is reached if all items are removed // to guarentee proper behavior, _currentPolygonIndex must be set to a invalid value, as on constructor init. _currentPolygonIndex = -1; return; } - if(_currentPolygonIndex >= _visualItems->count()){ - setCurrentPolygonIndex(_visualItems->count() - 1); + if(_currentPolygonIndex >= _container->visualItems()->count()){ + setCurrentPolygonIndex(_container->visualItems()->count() - 1); }else{ recalcPolygonInteractivity(_currentPolygonIndex); } @@ -85,10 +97,15 @@ void WimaController::removeArea(int index) bool WimaController::addGOperationArea() { + if (_container == nullptr) { + qWarning("WimaController::addGOperationArea(): container not initialized!"); + return false; + } + // check if opArea exists already WimaGOperationArea* opArea = nullptr; - for (int i = 0; i < _visualItems->count(); i++) { - WimaGOperationArea* currentArea = qobject_cast(_visualItems->get(i)); + for (int i = 0; i < _container->visualItems()->count(); i++) { + WimaGOperationArea* currentArea = qobject_cast(_container->visualItems()->get(i)); if ( currentArea != nullptr ) { opArea = currentArea; return false; @@ -97,10 +114,8 @@ bool WimaController::addGOperationArea() // create one if no opArea available opArea = new WimaGOperationArea(this); - connect(opArea, &WimaGOperationArea::pathChanged, this, &WimaController::updateJoinedArea); - - _visualItems->append(opArea); - int newIndex = _visualItems->count()-1; + _container->visualItems()->append(opArea); + int newIndex = _container->visualItems()->count()-1; setCurrentPolygonIndex(newIndex); emit visualItemsChanged(); @@ -109,10 +124,15 @@ bool WimaController::addGOperationArea() bool WimaController::addServiceArea() { + if (_container == nullptr) { + qWarning("WimaController::addGOperationArea(): container not initialized!"); + return false; + } + // check if serArea exists already WimaServiceArea* serArea = nullptr; - for (int i = 0; i < _visualItems->count(); i++) { - WimaServiceArea* currentArea = qobject_cast(_visualItems->get(i)); + for (int i = 0; i < _container->visualItems()->count(); i++) { + WimaServiceArea* currentArea = qobject_cast(_container->visualItems()->get(i)); if ( currentArea != nullptr ) { serArea = currentArea; return false; @@ -121,10 +141,9 @@ bool WimaController::addServiceArea() // create one if no serArea available serArea = new WimaServiceArea(this); - connect(serArea, &WimaServiceArea::pathChanged, this, &WimaController::updateJoinedArea); - _visualItems->append(serArea); - int newIndex = _visualItems->count()-1; + _container->visualItems()->append(serArea); + int newIndex = _container->visualItems()->count()-1; setCurrentPolygonIndex(newIndex); emit visualItemsChanged(); @@ -133,10 +152,15 @@ bool WimaController::addServiceArea() bool WimaController::addVehicleCorridor() { + if (_container == nullptr) { + qWarning("WimaController::addGOperationArea(): container not initialized!"); + return false; + } + // check if corridor exists already WimaVCorridor* corridor = nullptr; - for (int i = 0; i < _visualItems->count(); i++) { - WimaVCorridor* currentArea = qobject_cast(_visualItems->get(i)); + for (int i = 0; i < _container->visualItems()->count(); i++) { + WimaVCorridor* currentArea = qobject_cast(_container->visualItems()->get(i)); if ( currentArea != nullptr ) { corridor = currentArea; return false; @@ -145,10 +169,9 @@ bool WimaController::addVehicleCorridor() // create one if no corridor available corridor = new WimaVCorridor(this); - connect(corridor, &WimaVCorridor::pathChanged, this, &WimaController::updateJoinedArea); - _visualItems->append(corridor); - int newIndex = _visualItems->count()-1; + _container->visualItems()->append(corridor); + int newIndex = _container->visualItems()->count()-1; setCurrentPolygonIndex(newIndex); emit visualItemsChanged(); @@ -157,8 +180,13 @@ bool WimaController::addVehicleCorridor() void WimaController::removeAll() { + if (_container == nullptr) { + qWarning("WimaController::addGOperationArea(): container not initialized!"); + return; + } + bool changesApplied = false; - while (_visualItems->count() > 0) { + while (_container->visualItems()->count() > 0) { removeArea(0); changesApplied = true; } @@ -194,11 +222,16 @@ void WimaController::resumeMission() bool WimaController::updateMission() { + if (_container == nullptr) { + qWarning("WimaController::addGOperationArea(): container not initialized!"); + return false; + } + #define debug 0 // pick first WimaGOperationArea WimaGOperationArea* opArea = nullptr; - for (int i = 0; i < _visualItems->count(); i++) { - WimaGOperationArea* currentArea = qobject_cast(_visualItems->get(i)); + for (int i = 0; i < _container->visualItems()->count(); i++) { + WimaGOperationArea* currentArea = qobject_cast(_container->visualItems()->get(i)); if (currentArea != nullptr){ opArea = currentArea; break; @@ -209,8 +242,8 @@ bool WimaController::updateMission() // pick first WimaServiceArea WimaServiceArea* serArea = nullptr; - for (int i = 0; i < _visualItems->count(); i++) { - WimaServiceArea* currentArea = qobject_cast(_visualItems->get(i)); + for (int i = 0; i < _container->visualItems()->count(); i++) { + WimaServiceArea* currentArea = qobject_cast(_container->visualItems()->get(i)); if (currentArea != nullptr){ serArea = currentArea; break; @@ -221,8 +254,8 @@ bool WimaController::updateMission() // pick first WimaVCorridor WimaVCorridor* corridor = nullptr; - for (int i = 0; i < _visualItems->count(); i++) { - WimaVCorridor* currentArea = qobject_cast(_visualItems->get(i)); + for (int i = 0; i < _container->visualItems()->count(); i++) { + WimaVCorridor* currentArea = qobject_cast(_container->visualItems()->get(i)); if (currentArea != nullptr){ corridor = currentArea; break; @@ -230,11 +263,13 @@ bool WimaController::updateMission() } + updateJoinedArea(); + #if debug - WimaArea* joinedAreaPt = new WimaArea(joinedArea, this); - _visualItems->append(joinedAreaPt); + _container->visualItems()->append(&_joinedArea); #endif + // reset visual items _missionController->removeAll(); QmlObjectListModel* missionItems = _missionController->visualItems(); @@ -280,7 +315,7 @@ bool WimaController::updateMission() QGeoCoordinate start = serArea->center(); QGeoCoordinate end = survey->visualTransectPoints().first().value(); QList path; - WimaArea::dijkstraPath(start, end, _joinedArea, path); + WimaArea::dijkstraPath(start, end, *_container->joinedArea(), path); for (int i = 1; i < path.count()-1; i++) { sequenceNumber = _missionController->insertSimpleMissionItem(path.value(i), missionItems->count()-1); _missionController->setCurrentPlanViewIndex(sequenceNumber, true); @@ -290,7 +325,7 @@ bool WimaController::updateMission() start = survey->visualTransectPoints().last().value(); end = serArea->center(); path.clear(); - WimaArea::dijkstraPath(start, end, _joinedArea, path); + WimaArea::dijkstraPath(start, end, *_container->joinedArea(), path); for (int i = 1; i < path.count()-1; i++) { sequenceNumber = _missionController->insertSimpleMissionItem(path.value(i), missionItems->count()); _missionController->setCurrentPlanViewIndex(sequenceNumber, true); @@ -366,6 +401,11 @@ bool WimaController::loadFromCurrent() bool WimaController::loadFromFile(const QString &filename) { + if (_container == nullptr) { + qWarning("WimaController::addGOperationArea(): container not initialized!"); + return false; + } + #define debug 0 QString errorString; QString errorMessage = tr("Error loading Plan file (%1). %2").arg(filename).arg("%1"); @@ -396,7 +436,7 @@ bool WimaController::loadFromFile(const QString &filename) // AreaItems QJsonArray areaArray = json[areaItemsName].toArray(); - _visualItems->clear(); + _container->visualItems()->clear(); for( int i = 0; i < areaArray.size(); i++) { QJsonObject jsonArea = areaArray[i].toObject(); @@ -411,7 +451,7 @@ bool WimaController::loadFromFile(const QString &filename) return false; } - _visualItems->append(area); + _container->visualItems()->append(area); emit visualItemsChanged(); } else if ( jsonArea[WimaArea::areaTypeName] == WimaGOperationArea::wimaGOperationAreaName) { WimaGOperationArea* opArea = new WimaGOperationArea(this); @@ -422,7 +462,7 @@ bool WimaController::loadFromFile(const QString &filename) return false; } - _visualItems->append(opArea); + _container->visualItems()->append(opArea); emit visualItemsChanged(); } else if ( jsonArea[WimaArea::areaTypeName] == WimaServiceArea::wimaServiceAreaName) { WimaServiceArea* serArea = new WimaServiceArea(this); @@ -433,7 +473,7 @@ bool WimaController::loadFromFile(const QString &filename) return false; } - _visualItems->append(serArea); + _container->visualItems()->append(serArea); emit visualItemsChanged(); } else if ( jsonArea[WimaArea::areaTypeName] == WimaVCorridor::wimaVCorridorName) { WimaVCorridor* corridor = new WimaVCorridor(this); @@ -444,7 +484,7 @@ bool WimaController::loadFromFile(const QString &filename) return false; } - _visualItems->append(corridor); + _container->visualItems()->append(corridor); emit visualItemsChanged(); } else { errorString += QString(tr("%s not supported.\n").arg(WimaArea::areaTypeName)); @@ -529,19 +569,24 @@ void WimaController::recalcAll() void WimaController::recalcPolygonInteractivity(int index) { - if (index >= 0 && index < _visualItems->count()) { + if (_container != nullptr && index >= 0 && index < _container->visualItems()->count()) { resetAllInteractive(); - WimaArea* interactivePoly = qobject_cast(_visualItems->get(index)); + WimaArea* interactivePoly = qobject_cast(_container->visualItems()->get(index)); interactivePoly->setInteractive(true); } } void WimaController::updateJoinedArea() { + if (_container == nullptr) { + qWarning("WimaController::addGOperationArea(): container not initialized!"); + return; + } + // pick first WimaGOperationArea WimaGOperationArea* opArea = nullptr; - for (int i = 0; i < _visualItems->count(); i++) { - WimaGOperationArea* currentArea = qobject_cast(_visualItems->get(i)); + for (int i = 0; i < _container->visualItems()->count(); i++) { + WimaGOperationArea* currentArea = qobject_cast(_container->visualItems()->get(i)); if (currentArea != nullptr){ opArea = currentArea; break; @@ -552,8 +597,8 @@ void WimaController::updateJoinedArea() // pick first WimaServiceArea WimaServiceArea* serArea = nullptr; - for (int i = 0; i < _visualItems->count(); i++) { - WimaServiceArea* currentArea = qobject_cast(_visualItems->get(i)); + for (int i = 0; i < _container->visualItems()->count(); i++) { + WimaServiceArea* currentArea = qobject_cast(_container->visualItems()->get(i)); if (currentArea != nullptr){ serArea = currentArea; break; @@ -564,8 +609,8 @@ void WimaController::updateJoinedArea() // pick first WimaVCorridor WimaVCorridor* corridor = nullptr; - for (int i = 0; i < _visualItems->count(); i++) { - WimaVCorridor* currentArea = qobject_cast(_visualItems->get(i)); + for (int i = 0; i < _container->visualItems()->count(); i++) { + WimaVCorridor* currentArea = qobject_cast(_container->visualItems()->get(i)); if (currentArea != nullptr){ corridor = currentArea; break; @@ -574,10 +619,10 @@ void WimaController::updateJoinedArea() // join service area, op area and corridor if (corridor != nullptr) { - WimaArea::join(*serArea, *corridor, _joinedArea); - _joinedArea.join(*opArea); + WimaArea::join(*serArea, *corridor, *_container->joinedArea()); + _container->joinedArea()->join(*opArea); } else { - WimaArea::join(*serArea, *opArea, _joinedArea); + WimaArea::join(*serArea, *opArea, *_container->joinedArea()); } emit joinedAreaChanged() ; @@ -585,10 +630,15 @@ void WimaController::updateJoinedArea() void WimaController::resetAllInteractive() { - int itemCount = _visualItems->count(); + if (_container == nullptr) { + qWarning("WimaController::addGOperationArea(): container not initialized!"); + return ; + } + + int itemCount = _container->visualItems()->count(); if (itemCount > 0){ for (int i = 0; i < itemCount; i++) { - WimaArea* iteratorPoly = qobject_cast(_visualItems->get(i)); + WimaArea* iteratorPoly = qobject_cast(_container->visualItems()->get(i)); iteratorPoly->setInteractive(false); } } @@ -601,15 +651,20 @@ void WimaController::setInteractive() QJsonDocument WimaController::saveToJson(FileType fileType) { + if (_container == nullptr) { + qWarning("WimaController::addGOperationArea(): container not initialized!"); + return QJsonDocument(); + } + QJsonObject json; if ( fileType == FileType::WimaFile ) { QJsonArray jsonArray; - for (int i = 0; i < _visualItems->count(); i++) { + for (int i = 0; i < _container->visualItems()->count(); i++) { QJsonObject json; - WimaArea* area = qobject_cast(_visualItems->get(i)); + WimaArea* area = qobject_cast(_container->visualItems()->get(i)); if (area == nullptr) { qWarning("WimaController::saveToJson(): Internal error, area == nullptr!"); @@ -650,14 +705,6 @@ QJsonDocument WimaController::saveToJson(FileType fileType) return _masterController->saveToJson(); } - - - - - - - - return QJsonDocument(json); } diff --git a/src/Wima/WimaController.h b/src/Wima/WimaController.h index 0b6c33e1cc55424ca07831ebe60d8a80686197ae..d88526d9d7b5a9fc208551777c59302edb4afd32 100644 --- a/src/Wima/WimaController.h +++ b/src/Wima/WimaController.h @@ -8,22 +8,23 @@ #include "WimaGOperationArea.h" #include "WimaServiceArea.h" #include "WimaVCorridor.h" +#include "WimaDataContainer.h" #include "PlanMasterController.h" #include "MissionController.h" #include "SurveyComplexItem.h" #include "SimpleMissionItem.h" #include "MissionSettingsItem.h" - #include "JsonHelper.h" #include "QGCApplication.h" class WimaController : public QObject { + Q_OBJECT + enum FileType {WimaFile, PlanFile}; - Q_OBJECT public: WimaController(QObject *parent = nullptr); @@ -37,20 +38,25 @@ public: Q_PROPERTY(QStringList saveNameFilters READ saveNameFilters CONSTANT) Q_PROPERTY(QString fileExtension READ fileExtension CONSTANT) Q_PROPERTY(QGeoCoordinate joinedAreaCenter READ joinedAreaCenter CONSTANT) - Q_PROPERTY(QGCMapPolygon joinedArea READ joinedArea NOTIFY joinedAreaChanged) + Q_PROPERTY(WimaArea* joinedArea READ joinedArea NOTIFY joinedAreaChanged) + Q_PROPERTY(bool flyView READ flyView CONSTANT) + Q_PROPERTY(WimaDataContainer* dataContainer READ dataContainer WRITE setDataContainer NOTIFY dataContainerChanged) + // Property accessors PlanMasterController* masterController (void) const { return _masterController; } MissionController* missionController (void) const { return _missionController; } - QmlObjectListModel* visualItems (void) const { return _visualItems; } + QmlObjectListModel* visualItems (void) const { return _container->visualItems(); } int currentPolygonIndex (void) const { return _currentPolygonIndex; } QString currentFile (void) const { return _currentFile; } QStringList loadNameFilters (void) const; QStringList saveNameFilters (void) const; QString fileExtension (void) const { return wimaFileExtension; } - QGeoCoordinate joinedAreaCenter (void) const { return _joinedArea.center(); } - QGCMapPolygon joinedArea (void) const { return _joinedArea.toQGCPolygon(); } + QGeoCoordinate joinedAreaCenter (void) const { return _container->joinedArea()->center(); } + WimaArea* joinedArea (void) const { return _container->joinedArea(); } + WimaDataContainer* dataContainer (void) const { return _container; } + bool flyView (void) const { return _flyView; } @@ -59,7 +65,9 @@ public: void setMissionController (MissionController* missionController); /// Sets the integer index pointing to the current polygon. Current polygon is set interactive. void setCurrentPolygonIndex (int index); + void setDataContainer (WimaDataContainer* container); + Q_INVOKABLE void startWimaController(bool flyView); Q_INVOKABLE bool addGOperationArea(); /// Removes an area from _visualItems /// @param index Index of the area to be removed @@ -103,6 +111,7 @@ signals: void currentPolygonIndexChanged (int index); void currentFileChanged (); void joinedAreaChanged (); + void dataContainerChanged (); private slots: void recalcVehicleCorridor(); @@ -113,12 +122,12 @@ private slots: private: - bool _planView; - QmlObjectListModel* _visualItems; - WimaArea _joinedArea; + bool _flyView; PlanMasterController* _masterController; MissionController* _missionController; int _currentPolygonIndex; QString _currentFile; + WimaDataContainer* _container; + }; diff --git a/src/Wima/WimaDataContainer.cc b/src/Wima/WimaDataContainer.cc new file mode 100644 index 0000000000000000000000000000000000000000..1571cdec96b1dcf5d816c540771f557be3bacb9d --- /dev/null +++ b/src/Wima/WimaDataContainer.cc @@ -0,0 +1,9 @@ +#include "WimaDataContainer.h" + +WimaDataContainer::WimaDataContainer(QObject *parent) + : QObject(parent) + , _visualItems(this) + , _joinedArea(this) +{ + +} diff --git a/src/Wima/WimaDataContainer.h b/src/Wima/WimaDataContainer.h new file mode 100644 index 0000000000000000000000000000000000000000..cbc29c3a940e0c185952acdd6ca2039d919ceb4b --- /dev/null +++ b/src/Wima/WimaDataContainer.h @@ -0,0 +1,28 @@ +#ifndef WIMADATACONTAINER_H +#define WIMADATACONTAINER_H + +#include + +#include "QmlObjectListModel.h" + +#include "WimaArea.h" + +class WimaDataContainer : public QObject +{ + Q_OBJECT +public: + explicit WimaDataContainer(QObject *parent = nullptr); + + QmlObjectListModel* visualItems (void) { return &_visualItems; } + WimaArea* joinedArea (void) { return &_joinedArea; } + +signals: + +public slots: + +private: + QmlObjectListModel _visualItems; + WimaArea _joinedArea; +}; + +#endif // WIMADATACONTAINER_H diff --git a/src/WimaView/WimaView.qml b/src/WimaView/WimaView.qml index 77060c509d7ccfe005d271bea1a065df1bababba..274168abbd00a8c4ebb3b922c6755415129ae1ab 100644 --- a/src/WimaView/WimaView.qml +++ b/src/WimaView/WimaView.qml @@ -68,7 +68,7 @@ QGCView { property var _appSettings: QGroundControl.settingsManager.appSettings readonly property int _layerMission: 1 - readonly property int _layerWima: 2 + readonly property int _layerWima: 2 readonly property string _armedVehicleUploadPrompt: qsTr("Vehicle is currently armed. Do you want to upload the mission to the vehicle?") Component.onCompleted: { @@ -76,6 +76,7 @@ QGCView { toolbar.currentMissionItem = Qt.binding(function () { return _missionController.currentPlanViewItem }) _wimaController.masterController = _planMasterController _wimaController.missionController = _planMasterController.missionController + _wimaController.dataContainer = dataContainer; } function addComplexItem(complexItemName) { @@ -194,6 +195,7 @@ QGCView { Component.onCompleted: { wimaController.masterController = Qt.binding(function () { return masterController}) wimaController.missionController = Qt.binding(function () { return masterController.missionController}) + startWimaController(false /* flyView */) } function addComplexItem(complexItemName) { var coordinate = editorMap.center diff --git a/src/ui/MainWindowInner.qml b/src/ui/MainWindowInner.qml index ba72d872173df52f3d9c7417bccecda8288f21f4..da34a418e04944a8306d545b3b440c9135a024fb 100644 --- a/src/ui/MainWindowInner.qml +++ b/src/ui/MainWindowInner.qml @@ -19,6 +19,7 @@ import QGroundControl.Controls 1.0 import QGroundControl.FlightDisplay 1.0 import QGroundControl.ScreenTools 1.0 import QGroundControl.MultiVehicleManager 1.0 +import Wima 1.0 /// Inner common QML for mainWindow Item { @@ -28,8 +29,6 @@ Item { QGCPalette { id: qgcPal; colorGroupEnabled: true } - property var wimaController - property bool wimaAvailable: wimaViewLoader.wimaController !== undefined property var currentPopUp: null property real currentCenterX: 0 property var activeVehicle: QGroundControl.multiVehicleManager.activeVehicle @@ -50,16 +49,6 @@ Item { } } - onWimaAvailableChanged: { - if ( available ) { - wimaController = wimaViewLoader.wimaController - console.log("WimaController connected"); - } - else { - wimaController = undefined - } - } - function disableToolbar() { toolbarBlocker.enabled = true @@ -88,7 +77,7 @@ Item { if (settingsViewLoader.source != _settingsViewSource) { settingsViewLoader.source = _settingsViewSource } - settingsViewLoader.visible = true, wimaFlightView + settingsViewLoader.visible = true toolBar.checkSettingsButton() } @@ -182,6 +171,11 @@ Item { } } + // Wima Data Container + WimaDataContainer{ + id: wimaDataContainer + } + MessageDialog { id: unsavedMissionCloseDialog title: qsTr("%1 close").arg(QGroundControl.appName) @@ -192,15 +186,6 @@ Item { onYes: activeConnectionsCloseDialog.check() - - - - - - - - - // here what to do? function check() { if (planViewLoader.item && planViewLoader.item.dirty) { @@ -397,8 +382,9 @@ Item { anchors.bottom: parent.bottom visible: false - property var planToolBar: planToolBar - } wimaController: wimaViewLoader.wimaController ? wimaViewLoader.wimaController : undefined + property var planToolBar: planToolBar + property var dataContainer: wimaDataContainer + } Loader { @@ -414,7 +400,8 @@ Item { anchors.fill: parent visible: false - property var toolbar: wimaToolBar + property var toolbar: wimaToolBar + property var dataContainer: wimaDataContainer } @@ -422,6 +409,8 @@ Item { id: flightView anchors.fill: parent visible: true + + property var dataContainer: wimaDataContainer //------------------------------------------------------------------------- //-- Loader helper for any child, no matter how deep can display an element // on top of the video window.