Commit de01b189 authored by Valentin Platzgummer's avatar Valentin Platzgummer

wp added to flight view

parent 00b3967d
...@@ -228,6 +228,7 @@ ...@@ -228,6 +228,7 @@
<file alias="QGroundControl/Controls/WimaJoinedAreaMapVisual.qml">src/WimaView/WimaJoinedAreaMapVisual.qml</file> <file alias="QGroundControl/Controls/WimaJoinedAreaMapVisual.qml">src/WimaView/WimaJoinedAreaMapVisual.qml</file>
<file alias="QGroundControl/Controls/WimaCorridorEditor.qml">src/WimaView/WimaCorridorEditor.qml</file> <file alias="QGroundControl/Controls/WimaCorridorEditor.qml">src/WimaView/WimaCorridorEditor.qml</file>
<file alias="QGroundControl/FlightMap/WimaPlanMapItems.qml">src/FlightMap/MapItems/WimaPlanMapItems.qml</file> <file alias="QGroundControl/FlightMap/WimaPlanMapItems.qml">src/FlightMap/MapItems/WimaPlanMapItems.qml</file>
<file alias="QGroundControl/Controls/WimaMissionItemMapVisual.qml">src/PlanView/WimaMissionItemMapVisual.qml</file>
</qresource> </qresource>
<qresource prefix="/json"> <qresource prefix="/json">
<file alias="APMMavlinkStreamRate.SettingsGroup.json">src/Settings/APMMavlinkStreamRate.SettingsGroup.json</file> <file alias="APMMavlinkStreamRate.SettingsGroup.json">src/Settings/APMMavlinkStreamRate.SettingsGroup.json</file>
......
...@@ -205,7 +205,7 @@ FlightMap { ...@@ -205,7 +205,7 @@ FlightMap {
: object.type === "WimaMeasurementAreaData" ? "green" : object.type === "WimaMeasurementAreaData" ? "green"
: "transparent" : "transparent"
opacity: 0.25 opacity: 0.25
z: QGroundControl.zOrderTrajectoryLines-1 z: QGroundControl.zOrderTrajectoryLines-2
} }
} }
...@@ -214,7 +214,8 @@ FlightMap { ...@@ -214,7 +214,8 @@ FlightMap {
map: flightMap map: flightMap
largeMapView: _mainIsMap largeMapView: _mainIsMap
wimaController: flightMap.wimaController wimaController: flightMap.wimaController
z: 1000 z: QGroundControl.zOrderTrajectoryLines-1
color: "gray"
} }
// Add trajectory points to the map // Add trajectory points to the map
......
...@@ -21,6 +21,7 @@ MapQuickItem { ...@@ -21,6 +21,7 @@ MapQuickItem {
property var missionItem property var missionItem
property int sequenceNumber property int sequenceNumber
property var color
signal clicked signal clicked
...@@ -37,6 +38,7 @@ MapQuickItem { ...@@ -37,6 +38,7 @@ MapQuickItem {
vehicleYaw: missionItem.missionVehicleYaw vehicleYaw: missionItem.missionVehicleYaw
showGimbalYaw: !isNaN(missionItem.missionGimbalYaw) showGimbalYaw: !isNaN(missionItem.missionGimbalYaw)
onClicked: _item.clicked() onClicked: _item.clicked()
color: _item.color
property bool _isCurrentItem: missionItem ? missionItem.isCurrentItem : false property bool _isCurrentItem: missionItem ? missionItem.isCurrentItem : false
} }
......
...@@ -22,6 +22,7 @@ Item { ...@@ -22,6 +22,7 @@ Item {
property var map ///< Map control to show items on property var map ///< Map control to show items on
property bool largeMapView ///< true: map takes up entire view, false: map is in small window property bool largeMapView ///< true: map takes up entire view, false: map is in small window
property var wimaController property var wimaController
property var color
property var _map: map property var _map: map
property var _missionLineViewComponent property var _missionLineViewComponent
...@@ -30,14 +31,15 @@ Item { ...@@ -30,14 +31,15 @@ Item {
Repeater { Repeater {
model: largeMapView ? wimaController.missionItems : 0 model: largeMapView ? wimaController.missionItems : 0
delegate: MissionItemMapVisual { delegate: WimaMissionItemMapVisual {
map: _map map: _map
onClicked: { color: _root.color
if (isActiveVehicle) { // onClicked: {
// Only active vehicle supports click to change current mission item // if (isActiveVehicle) {
guidedActionsController.confirmAction(guidedActionsController.actionSetWaypoint, Math.max(object.sequenceNumber, 1)) // // Only active vehicle supports click to change current mission item
} // guidedActionsController.confirmAction(guidedActionsController.actionSetWaypoint, Math.max(object.sequenceNumber, 1))
} // }
// }
} }
/*onItemAdded: { /*onItemAdded: {
...@@ -66,9 +68,9 @@ Item { ...@@ -66,9 +68,9 @@ Item {
MapPolyline { MapPolyline {
line.width: 3 line.width: 3
line.color: "#be781c" // Hack, can't get palette to work in here line.color: "gray" // Hack, can't get palette to work in here
z: QGroundControl.zOrderWaypointLines z: QGroundControl.zOrderWaypointLines
path: undefined //wimaController.waypointPath path: wimaController.waypointPath
} }
} }
} }
...@@ -148,7 +148,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, const Missi ...@@ -148,7 +148,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, const Missi
SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, bool flyView, QObject* parent) SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, bool flyView, QObject* parent)
: VisualMissionItem (other, flyView, parent) : VisualMissionItem (other, flyView, parent)
, _missionItem (other._vehicle) , _missionItem (other._missionItem, this)
, _rawEdit (false) , _rawEdit (false)
, _dirty (false) , _dirty (false)
, _ignoreDirtyChangeSignals (false) , _ignoreDirtyChangeSignals (false)
......
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtLocation 5.3
import QtPositioning 5.3
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.FlightMap 1.0
/// Simple Mission Item visuals
Item {
id: _root
property var map ///< Map control to place item in
property var qgcView ///< QGCView to use for popping dialogs
property var color
property var _missionItem: object
property var _itemVisual
property var _dragArea
property bool _itemVisualShowing: false
property bool _dragAreaShowing: false
signal clicked(int sequenceNumber)
function hideItemVisuals() {
if (_itemVisualShowing) {
_itemVisual.destroy()
_itemVisualShowing = false
}
}
function showItemVisuals() {
if (!_itemVisualShowing) {
_itemVisual = indicatorComponent.createObject(map)
map.addMapItem(_itemVisual)
_itemVisualShowing = true
}
}
function hideDragArea() {
if (_dragAreaShowing) {
_dragArea.destroy()
_dragAreaShowing = false
}
}
function showDragArea() {
if (!_dragAreaShowing && _missionItem.specifiesCoordinate) {
_dragArea = dragAreaComponent.createObject(map)
_dragAreaShowing = true
}
}
Component.onCompleted: {
showItemVisuals()
if (_missionItem.isCurrentItem && map.planView) {
showDragArea()
}
}
Component.onDestruction: {
hideDragArea()
hideItemVisuals()
}
Connections {
target: _missionItem
onIsCurrentItemChanged: {
if (_missionItem.isCurrentItem) {
showDragArea()
} else {
hideDragArea()
}
}
}
// Control which is used to drag items
Component {
id: dragAreaComponent
MissionItemIndicatorDrag {
mapControl: _root.map
itemIndicator: _itemVisual
itemCoordinate: _missionItem.coordinate
onItemCoordinateChanged: _missionItem.coordinate = itemCoordinate
}
}
Component {
id: indicatorComponent
MissionItemIndicator {
coordinate: _missionItem.coordinate
visible: _missionItem.specifiesCoordinate
z: QGroundControl.zOrderMapItems
missionItem: _missionItem
sequenceNumber: _missionItem.sequenceNumber
color: _root.color
onClicked: _root.clicked(_missionItem.sequenceNumber)
}
}
}
...@@ -38,7 +38,7 @@ QStringList WimaController::saveNameFilters() const ...@@ -38,7 +38,7 @@ QStringList WimaController::saveNameFilters() const
return filters; return filters;
} }
WimaDataContainer *WimaController::dataContainer() const WimaDataContainer *WimaController::dataContainer()
{ {
return _container; return _container;
} }
...@@ -48,6 +48,11 @@ QmlObjectListModel *WimaController::missionItems() ...@@ -48,6 +48,11 @@ QmlObjectListModel *WimaController::missionItems()
return &_missionItems; return &_missionItems;
} }
QVariantList WimaController::waypointPath()
{
return _waypointPath;
}
void WimaController::setMasterController(PlanMasterController *masterC) void WimaController::setMasterController(PlanMasterController *masterC)
{ {
_masterController = masterC; _masterController = masterC;
...@@ -159,14 +164,11 @@ void WimaController::containerDataValidChanged(bool valid) ...@@ -159,14 +164,11 @@ void WimaController::containerDataValidChanged(bool valid)
int areaCounter = 0; int areaCounter = 0;
int numAreas = 4; // extract only numAreas Areas, if there are more they are invalid and ignored int numAreas = 4; // extract only numAreas Areas, if there are more they are invalid and ignored
qWarning() << QString("List Size: %1").arg(areaList.size());
for (int i = 0; i < areaList.size(); i++) { for (int i = 0; i < areaList.size(); i++) {
const WimaAreaData *areaData = areaList[i]; const WimaAreaData *areaData = areaList[i];
qWarning() << areaData->type();
if (areaData->type() == WimaServiceAreaData::typeString) { // is it a service area? if (areaData->type() == WimaServiceAreaData::typeString) { // is it a service area?
_serviceArea = *qobject_cast<const WimaServiceAreaData*>(areaData); _serviceArea = *qobject_cast<const WimaServiceAreaData*>(areaData);
// qWarning("Service area, wuhuuu!");
areaCounter++; areaCounter++;
_visualItems.append(&_serviceArea); _visualItems.append(&_serviceArea);
...@@ -175,7 +177,6 @@ void WimaController::containerDataValidChanged(bool valid) ...@@ -175,7 +177,6 @@ void WimaController::containerDataValidChanged(bool valid)
if (areaData->type() == WimaMeasurementAreaData::typeString) { // is it a measurement area? if (areaData->type() == WimaMeasurementAreaData::typeString) { // is it a measurement area?
_measurementArea = *qobject_cast<const WimaMeasurementAreaData*>(areaData); _measurementArea = *qobject_cast<const WimaMeasurementAreaData*>(areaData);
// qWarning("Measurement area, wuhuuu!");
areaCounter++; areaCounter++;
_visualItems.append(&_measurementArea); _visualItems.append(&_measurementArea);
...@@ -184,7 +185,6 @@ void WimaController::containerDataValidChanged(bool valid) ...@@ -184,7 +185,6 @@ void WimaController::containerDataValidChanged(bool valid)
if (areaData->type() == WimaCorridorData::typeString) { // is it a corridor? if (areaData->type() == WimaCorridorData::typeString) { // is it a corridor?
_corridor = *qobject_cast<const WimaCorridorData*>(areaData); _corridor = *qobject_cast<const WimaCorridorData*>(areaData);
// qWarning("WimaCorridorData, wuhuuu!");
areaCounter++; areaCounter++;
//_visualItems.append(&_corridor); // not needed //_visualItems.append(&_corridor); // not needed
...@@ -193,7 +193,6 @@ void WimaController::containerDataValidChanged(bool valid) ...@@ -193,7 +193,6 @@ void WimaController::containerDataValidChanged(bool valid)
if (areaData->type() == WimaJoinedAreaData::typeString) { // is it a corridor? if (areaData->type() == WimaJoinedAreaData::typeString) { // is it a corridor?
_joinedArea = *qobject_cast<const WimaJoinedAreaData*>(areaData); _joinedArea = *qobject_cast<const WimaJoinedAreaData*>(areaData);
// qWarning("WimaJoinedAreaData, wuhuuu!");
areaCounter++; areaCounter++;
_visualItems.append(&_joinedArea); _visualItems.append(&_joinedArea);
...@@ -213,8 +212,9 @@ void WimaController::containerDataValidChanged(bool valid) ...@@ -213,8 +212,9 @@ void WimaController::containerDataValidChanged(bool valid)
_missionController->removeAll(); _missionController->removeAll();
QmlObjectListModel* missionControllerVisualItems = _missionController->visualItems(); QmlObjectListModel* missionControllerVisualItems = _missionController->visualItems();
for ( auto missionItem : tempMissionItems) for ( auto missionItem : tempMissionItems) {
_missionController->insertSimpleMissionItem(*missionItem, missionControllerVisualItems->count()); _missionController->insertSimpleMissionItem(*missionItem, missionControllerVisualItems->count());
}
MissionSettingsItem *settingsItem = qobject_cast<MissionSettingsItem *>((*missionControllerVisualItems)[0]); MissionSettingsItem *settingsItem = qobject_cast<MissionSettingsItem *>((*missionControllerVisualItems)[0]);
if (settingsItem == nullptr) { if (settingsItem == nullptr) {
...@@ -233,10 +233,7 @@ void WimaController::containerDataValidChanged(bool valid) ...@@ -233,10 +233,7 @@ void WimaController::containerDataValidChanged(bool valid)
_missionItems.append(visualItemCopy); _missionItems.append(visualItemCopy);
} }
// remove warnings if you read this updateWaypointPath();
qWarning("WimaController::containerDataValidChanged(): Mission Item count:");
qWarning() << _missionItems.count();
_missionController->removeAll(); _missionController->removeAll();
if (areaCounter == numAreas) if (areaCounter == numAreas)
...@@ -257,6 +254,22 @@ void WimaController::containerDataValidChanged(bool valid) ...@@ -257,6 +254,22 @@ void WimaController::containerDataValidChanged(bool valid)
#endif #endif
} }
void WimaController::updateWaypointPath()
{
_waypointPath.clear();
for ( int i = 1; i < _missionItems.count(); i++) {
SimpleMissionItem *item = qobject_cast<SimpleMissionItem *>(_missionItems[i]);
if (item == nullptr) {
qWarning("WimaController::updateWaypointPath(): nullptr");
return;
}
_waypointPath.append(QVariant::fromValue(item->coordinate()));
}
emit waypointPathChanged();
}
......
...@@ -39,21 +39,23 @@ public: ...@@ -39,21 +39,23 @@ public:
Q_PROPERTY(QStringList loadNameFilters READ loadNameFilters CONSTANT) Q_PROPERTY(QStringList loadNameFilters READ loadNameFilters CONSTANT)
Q_PROPERTY(QStringList saveNameFilters READ saveNameFilters CONSTANT) Q_PROPERTY(QStringList saveNameFilters READ saveNameFilters CONSTANT)
Q_PROPERTY(QString fileExtension READ fileExtension CONSTANT) Q_PROPERTY(QString fileExtension READ fileExtension CONSTANT)
Q_PROPERTY(WimaDataContainer* dataContainer READ dataContainer WRITE setDataContainer NOTIFY dataContainerChanged) Q_PROPERTY(WimaDataContainer* dataContainer READ dataContainer WRITE setDataContainer NOTIFY dataContainerChanged)
Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems NOTIFY missionItemsChanged) Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems NOTIFY missionItemsChanged)
Q_PROPERTY(QVariantList waypointPath READ waypointPath NOTIFY waypointPathChanged)
// Property accessors // Property accessors
PlanMasterController* masterController (void) { return _masterController; } PlanMasterController* masterController (void) { return _masterController; }
MissionController* missionController (void) { return _missionController; } MissionController* missionController (void) { return _missionController; }
QmlObjectListModel* visualItems (void) ; QmlObjectListModel* visualItems (void);
QString currentFile (void) const { return _currentFile; } QString currentFile (void) const { return _currentFile; }
QStringList loadNameFilters (void) const; QStringList loadNameFilters (void) const;
QStringList saveNameFilters (void) const; QStringList saveNameFilters (void) const;
QString fileExtension (void) const { return wimaFileExtension; } QString fileExtension (void) const { return wimaFileExtension; }
QGCMapPolygon joinedArea (void) const; QGCMapPolygon joinedArea (void) const;
WimaDataContainer* dataContainer (void) const; WimaDataContainer* dataContainer (void);
QmlObjectListModel* missionItems (void); QmlObjectListModel* missionItems (void);
QVariantList waypointPath (void);
// Property setters // Property setters
...@@ -90,9 +92,11 @@ signals: ...@@ -90,9 +92,11 @@ signals:
void dataContainerChanged (); void dataContainerChanged ();
void readyForSaveSendChanged (bool ready); void readyForSaveSendChanged (bool ready);
void missionItemsChanged (void); void missionItemsChanged (void);
void waypointPathChanged (void);
private slots: private slots:
void containerDataValidChanged (bool valid); void containerDataValidChanged (bool valid);
void updateWaypointPath (void);
private: private:
PlanMasterController *_masterController; PlanMasterController *_masterController;
...@@ -106,5 +110,6 @@ private: ...@@ -106,5 +110,6 @@ private:
WimaCorridorData _corridor; // corridor connecting opArea and serArea WimaCorridorData _corridor; // corridor connecting opArea and serArea
bool _localPlanDataValid; bool _localPlanDataValid;
QmlObjectListModel _missionItems; // all mission itmes generaded by wimaPlaner, displayed in flightView QmlObjectListModel _missionItems; // all mission itmes generaded by wimaPlaner, displayed in flightView
QVariantList _waypointPath;
}; };
...@@ -242,7 +242,6 @@ bool WimaPlaner::updateMission() ...@@ -242,7 +242,6 @@ bool WimaPlaner::updateMission()
qWarning("WimaPlaner::updateMission(): settingsItem == nullptr"); qWarning("WimaPlaner::updateMission(): settingsItem == nullptr");
return false; return false;
} }
// set altitudes, temporary measure to solve bugs // set altitudes, temporary measure to solve bugs
QGeoCoordinate center = _serviceArea.center(); QGeoCoordinate center = _serviceArea.center();
center.setAltitude(0); center.setAltitude(0);
...@@ -253,15 +252,20 @@ bool WimaPlaner::updateMission() ...@@ -253,15 +252,20 @@ bool WimaPlaner::updateMission()
center = _corridor.center(); center = _corridor.center();
center.setAltitude(0); center.setAltitude(0);
_corridor.setCenter(center); _corridor.setCenter(center);
// set HomePos. to serArea center // set HomePos. to serArea center
settingsItem->setCoordinate(_serviceArea.center()); settingsItem->setCoordinate(_serviceArea.center());
// create take off position item // create take off position item
int sequenceNumber = _missionController->insertSimpleMissionItem(_serviceArea.center(), missionItems->count()); int sequenceNumber = _missionController->insertSimpleMissionItem(_serviceArea.center(), missionItems->count());
_missionController->setCurrentPlanViewIndex(sequenceNumber, true);
_missionController->setCurrentPlanViewIndex(sequenceNumber, true);
SimpleMissionItem* takeOffItem = qobject_cast<SimpleMissionItem*>(missionItems->get(missionItems->count()-1));
if (takeOffItem == nullptr){
qWarning("WimaPlaner::updateMission(): takeOffItem == nullptr");
return false;
} else {
takeOffItem->setCoordinate(_serviceArea.center()); //necessary, insertSimpleMissionItem does not copy coordinate (why?)
}
// create survey item, will be extened with more()-> mission types in the future // create survey item, will be extened with more()-> mission types in the future
_missionController->insertComplexMissionItem(_missionController->circularSurveyComplexItemName(), _measurementArea.center(), missionItems->count()); _missionController->insertComplexMissionItem(_missionController->circularSurveyComplexItemName(), _measurementArea.center(), missionItems->count());
...@@ -280,13 +284,9 @@ bool WimaPlaner::updateMission() ...@@ -280,13 +284,9 @@ bool WimaPlaner::updateMission()
survey->setAutoGenerated(true); // prevents reinitialisation from gui survey->setAutoGenerated(true); // prevents reinitialisation from gui
survey->surveyAreaPolygon()->clear(); survey->surveyAreaPolygon()->clear();
survey->surveyAreaPolygon()->appendVertices(_measurementArea.coordinateList()); survey->surveyAreaPolygon()->appendVertices(_measurementArea.coordinateList());
} }
// calculate path from take off to opArea // calculate path from take off to opArea
if (survey->visualTransectPoints().size() == 0) { if (survey->visualTransectPoints().size() == 0) {
qWarning("WimaPlaner::updateMission(): survey no points."); qWarning("WimaPlaner::updateMission(): survey no points.");
...@@ -345,6 +345,8 @@ bool WimaPlaner::updateMission() ...@@ -345,6 +345,8 @@ bool WimaPlaner::updateMission()
MAV_CMD landCmd = controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_LAND; MAV_CMD landCmd = controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_LAND;
if (controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(landCmd)) { if (controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(landCmd)) {
landItem->setCommand(landCmd); landItem->setCommand(landCmd);
} else {
return false;
} }
} }
...@@ -588,26 +590,6 @@ bool WimaPlaner::recalcJoinedArea(QString &errorString) ...@@ -588,26 +590,6 @@ bool WimaPlaner::recalcJoinedArea(QString &errorString)
return false; // this happens if all areas are pairwise disjoint return false; // this happens if all areas are pairwise disjoint
} }
// join service area, op area and corridor // join service area, op area and corridor
// // remove if debugging finished
// WimaServiceArea *test = new WimaServiceArea(this);
// WimaServiceArea *test1 = new WimaServiceArea(this);
// WimaServiceArea *test2 = new WimaServiceArea(this);
// WimaServiceArea *test3 = new WimaServiceArea(this);
// Circle circle(25, this);
// using namespace GeoUtilities;
// test->setPath(toGeo(circle.approximateSektor(0.5, 1, 3), _joinedArea.center()));
// _visualItems.append(test);
// test1->setPath(toGeo(circle.approximateSektor(0.5, 1, -1), _joinedArea.center()));
// _visualItems.append(test1);
// test2->setPath(toGeo(circle.approximateSektor(0.5,-1, 3), _joinedArea.center()));
// _visualItems.append(test2);
// test3->setPath(toGeo(circle.approximateSektor(0.5, -1, -3), _joinedArea.center()));
// _visualItems.append(test3);
return true; return true;
} }
...@@ -682,6 +664,21 @@ WimaPlanData WimaPlaner::toPlanData() ...@@ -682,6 +664,21 @@ WimaPlanData WimaPlaner::toPlanData()
// convert mission items to mavlink commands // convert mission items to mavlink commands
QList<MissionItem*> rgMissionItems; QList<MissionItem*> rgMissionItems;
MissionController::convertToMissionItems(_missionController->visualItems(), rgMissionItems, this); MissionController::convertToMissionItems(_missionController->visualItems(), rgMissionItems, this);
// remove warnings if you read this
// qWarning("WimaPlaner::toPlanData(): rgMissionItems");
// for (auto item : rgMissionItems) {
// qWarning() << item->command();
// qWarning() << item->param1();
// qWarning() << item->param2();
// qWarning() << item->param3();
// qWarning() << item->param4();
// qWarning() << item->param5();
// qWarning() << item->param6();
// qWarning() << item->param7();
// qWarning(" ");
// }
QList<const MissionItem*> rgMissionItemsConst; QList<const MissionItem*> rgMissionItemsConst;
for (auto missionItem : rgMissionItems) for (auto missionItem : rgMissionItems)
rgMissionItemsConst.append(missionItem); rgMissionItemsConst.append(missionItem);
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment