Commit 46268575 authored by Valentin Platzgummer's avatar Valentin Platzgummer

adding currentMissionItems

parent fd653f79
...@@ -215,7 +215,6 @@ FlightMap { ...@@ -215,7 +215,6 @@ FlightMap {
largeMapView: _mainIsMap largeMapView: _mainIsMap
wimaController: flightMap.wimaController wimaController: flightMap.wimaController
z: QGroundControl.zOrderTrajectoryLines-1 z: QGroundControl.zOrderTrajectoryLines-1
color: "#B4808080" // gray with alpha #AARRGGBB
} }
// Add trajectory points to the map // Add trajectory points to the map
......
...@@ -19,14 +19,17 @@ import QGroundControl.FlightMap 1.0 ...@@ -19,14 +19,17 @@ import QGroundControl.FlightMap 1.0
Item { Item {
id: _root id: _root
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 string mIColor: "#B4808080" // Mission Items Color, gray with alpha 0.7 #AARRGGBB
property var lineColor: color property string mIlineColor: mIColor
property string cMIColor: "orangered" // Current Mission Items Color
property string cMIlineColor: cMIColor
property var _map: map property var _map: map
property var _missionLineViewComponent property var _missionLineViewComponent
property var _currentMissionLineViewComponent
// Add the mission item visuals to the map // Add the mission item visuals to the map
Repeater { Repeater {
...@@ -34,7 +37,7 @@ Item { ...@@ -34,7 +37,7 @@ Item {
delegate: WimaMissionItemMapVisual { delegate: WimaMissionItemMapVisual {
map: _map map: _map
color: _root.color color: _root.mIColor
// onClicked: { // onClicked: {
// if (isActiveVehicle) { // if (isActiveVehicle) {
// // Only active vehicle supports click to change current mission item // // Only active vehicle supports click to change current mission item
...@@ -52,16 +55,32 @@ Item { ...@@ -52,16 +55,32 @@ Item {
}*/ }*/
} }
// Add the current mission item visuals to the map
Repeater {
model: largeMapView ? wimaController.currentMissionItems : 0
delegate: WimaMissionItemMapVisual {
map: _map
color: _root.cMIColor
}
}
Component.onCompleted: { Component.onCompleted: {
_missionLineViewComponent = missionLineViewComponent.createObject(map) _missionLineViewComponent = missionLineViewComponent.createObject(map)
if (_missionLineViewComponent.status === Component.Error) if (_missionLineViewComponent.status === Component.Error)
console.log(_missionLineViewComponent.errorString()) console.log(_missionLineViewComponent.errorString())
map.addMapItem(_missionLineViewComponent) map.addMapItem(_missionLineViewComponent)
_currentMissionLineViewComponent = currentMissionLineViewComponent.createObject(map)
if (_currentMissionLineViewComponent.status === Component.Error)
console.log(_currentMissionLineViewComponent.errorString())
map.addMapItem(_currentMissionLineViewComponent)
} }
Component.onDestruction: { Component.onDestruction: {
_missionLineViewComponent.destroy() _missionLineViewComponent.destroy()
_currentMissionLineViewComponent.destroy()
} }
Component { Component {
...@@ -69,9 +88,20 @@ Item { ...@@ -69,9 +88,20 @@ Item {
MapPolyline { MapPolyline {
line.width: 3 line.width: 3
line.color: lineColor // Hack, can't get palette to work in here line.color: mIlineColor
z: QGroundControl.zOrderWaypointLines z: QGroundControl.zOrderWaypointLines
path: wimaController.waypointPath path: wimaController.waypointPath
} }
} }
Component {
id: currentMissionLineViewComponent
MapPolyline {
line.width: 3
line.color: cMIlineColor
z: QGroundControl.zOrderWaypointLines
path: wimaController.currentWaypointPath
}
}
} }
...@@ -26,6 +26,16 @@ QVariantList WimaAreaData::path() const ...@@ -26,6 +26,16 @@ QVariantList WimaAreaData::path() const
return _path; return _path;
} }
QList<QGeoCoordinate> WimaAreaData::coordinateList() const
{
QList<QGeoCoordinate> coordinateList;
for ( auto coorinate : _path)
coordinateList.append(coorinate.value<QGeoCoordinate>());
return coordinateList;
}
/*! /*!
* \fn void WimaAreaData::setMaxAltitude(double maxAltitude) * \fn void WimaAreaData::setMaxAltitude(double maxAltitude)
* *
......
...@@ -19,8 +19,9 @@ public: ...@@ -19,8 +19,9 @@ public:
//WimaAreaData(const WimaArea &other, QObject *parent = nullptr); //WimaAreaData(const WimaArea &other, QObject *parent = nullptr);
WimaAreaData& operator=(const WimaAreaData& otherData) = delete; // avoid slicing WimaAreaData& operator=(const WimaAreaData& otherData) = delete; // avoid slicing
double maxAltitude() const; double maxAltitude() const;
QVariantList path() const; QVariantList path() const;
QList<QGeoCoordinate> coordinateList() const;
virtual QString type() const = 0; virtual QString type() const = 0;
......
...@@ -12,7 +12,8 @@ WimaController::WimaController(QObject *parent) ...@@ -12,7 +12,8 @@ WimaController::WimaController(QObject *parent)
, _serviceArea (this) , _serviceArea (this)
, _corridor (this) , _corridor (this)
, _localPlanDataValid (false) , _localPlanDataValid (false)
, _firstWaypointIndex (2) // starts with 2, 0 is home position, 1 is takeoff , _startWaypointIndex (0)
, _endWaypointIndex (0)
{ {
} }
...@@ -49,11 +50,21 @@ QmlObjectListModel *WimaController::missionItems() ...@@ -49,11 +50,21 @@ QmlObjectListModel *WimaController::missionItems()
return &_missionItems; return &_missionItems;
} }
QmlObjectListModel *WimaController::currentMissionItems()
{
return &_currentMissionItems;
}
QVariantList WimaController::waypointPath() QVariantList WimaController::waypointPath()
{ {
return _waypointPath; return _waypointPath;
} }
QVariantList WimaController::currentWaypointPath()
{
return _currentWaypointPath;
}
void WimaController::setMasterController(PlanMasterController *masterC) void WimaController::setMasterController(PlanMasterController *masterC)
{ {
_masterController = masterC; _masterController = masterC;
...@@ -157,12 +168,12 @@ bool WimaController::calcShortestPath(const QGeoCoordinate &start, const QGeoCoo ...@@ -157,12 +168,12 @@ bool WimaController::calcShortestPath(const QGeoCoordinate &start, const QGeoCoo
return retVal; return retVal;
} }
bool WimaController::extractCoordinateList(const QmlObjectListModel &missionItems, QList<QGeoCoordinate> &coordinateList) bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QList<QGeoCoordinate> &coordinateList)
{ {
return extractCoordinateList(missionItems, coordinateList, 0, missionItems.count()-1); return extractCoordinateList(missionItems, coordinateList, 0, missionItems.count()-1);
} }
bool WimaController::extractCoordinateList(const QmlObjectListModel &missionItems, QList<QGeoCoordinate> &coordinateList, int startIndex, int endIndex) bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QList<QGeoCoordinate> &coordinateList, int startIndex, int endIndex)
{ {
if ( startIndex >= 0 if ( startIndex >= 0
&& startIndex < missionItems.count() && startIndex < missionItems.count()
...@@ -175,7 +186,7 @@ bool WimaController::extractCoordinateList(const QmlObjectListModel &missionItem ...@@ -175,7 +186,7 @@ bool WimaController::extractCoordinateList(const QmlObjectListModel &missionItem
return false; return false;
} else { } else {
for (int i = startIndex; i <= endIndex; i++) { for (int i = startIndex; i <= endIndex; i++) {
const MissionItem *mItem = qobject_cast<MissionItem*>(missionItems[i]); SimpleMissionItem *mItem = missionItems.value<SimpleMissionItem *>(i);
if (mItem == nullptr) { if (mItem == nullptr) {
coordinateList.clear(); coordinateList.clear();
...@@ -190,12 +201,12 @@ bool WimaController::extractCoordinateList(const QmlObjectListModel &missionItem ...@@ -190,12 +201,12 @@ bool WimaController::extractCoordinateList(const QmlObjectListModel &missionItem
return true; return true;
} }
bool WimaController::extractCoordinateList(const QmlObjectListModel &missionItems, QVariantList &coordinateList) bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QVariantList &coordinateList)
{ {
return extractCoordinateList(missionItems, coordinateList, 0 , missionItems.count()-1); return extractCoordinateList(missionItems, coordinateList, 0 , missionItems.count()-1);
} }
bool WimaController::extractCoordinateList(const QmlObjectListModel &missionItems, QVariantList &coordinateList, int startIndex, int endIndex) bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QVariantList &coordinateList, int startIndex, int endIndex)
{ {
QList<QGeoCoordinate> geoCoordintateList; QList<QGeoCoordinate> geoCoordintateList;
...@@ -279,18 +290,22 @@ void WimaController::containerDataValidChanged(bool valid) ...@@ -279,18 +290,22 @@ void WimaController::containerDataValidChanged(bool valid)
QList<const MissionItem*> tempMissionItems = planData.missionItems(); QList<const MissionItem*> tempMissionItems = planData.missionItems();
// create mission items
_missionController->removeAll(); _missionController->removeAll();
QmlObjectListModel* missionControllerVisualItems = _missionController->visualItems(); QmlObjectListModel* missionControllerVisualItems = _missionController->visualItems();
for ( auto missionItem : tempMissionItems) { for ( int i = 1; i < tempMissionItems.size(); i++) {
const MissionItem *missionItem = tempMissionItems[i];
_missionController->insertSimpleMissionItem(*missionItem, missionControllerVisualItems->count()); _missionController->insertSimpleMissionItem(*missionItem, missionControllerVisualItems->count());
} }
MissionSettingsItem *settingsItem = qobject_cast<MissionSettingsItem *>((*missionControllerVisualItems)[0]);
if (settingsItem == nullptr) { // copy mission items to _missionItems
qWarning("WimaController::containerDataValidChanged(): Nullptr at MissionSettingsItem!"); // MissionSettingsItem *settingsItem = qobject_cast<MissionSettingsItem *>((*missionControllerVisualItems)[0]);
return; // if (settingsItem == nullptr) {
} // qWarning("WimaController::containerDataValidChanged(): Nullptr at MissionSettingsItem!");
//_missionItems.append(settingsItem); // return;
// }
// _missionItems.append(settingsItem);
for ( int i = 1; i < missionControllerVisualItems->count(); i++) { for ( int i = 1; i < missionControllerVisualItems->count(); i++) {
SimpleMissionItem *visualItem = qobject_cast<SimpleMissionItem *>((*missionControllerVisualItems)[i]); SimpleMissionItem *visualItem = qobject_cast<SimpleMissionItem *>((*missionControllerVisualItems)[i]);
...@@ -303,7 +318,8 @@ void WimaController::containerDataValidChanged(bool valid) ...@@ -303,7 +318,8 @@ void WimaController::containerDataValidChanged(bool valid)
} }
updateWaypointPath(); updateWaypointPath();
_missionController->removeAll(); updateCurrentMissionItems();
updateCurrentPath();
if (areaCounter == numAreas) if (areaCounter == numAreas)
_localPlanDataValid = true; _localPlanDataValid = true;
...@@ -327,28 +343,94 @@ void WimaController::updateCurrentMissionItems() ...@@ -327,28 +343,94 @@ void WimaController::updateCurrentMissionItems()
{ {
int numberWaypoints = 30; // the number of waypoints currentMissionItems must not exceed int numberWaypoints = 30; // the number of waypoints currentMissionItems must not exceed
SimpleMissionItem *homeItem = _missionItems.value<SimpleMissionItem *>(0);
if (homeItem == nullptr) {
qWarning("WimaController::updateCurrentMissionItems(): nullptr");
return;
}
QGeoCoordinate homeCoordinate(homeItem->coordinate());
QList<QGeoCoordinate> geoCoordinateList; // list with potential waypoints (from _missionItems), for _currentMissionItems QList<QGeoCoordinate> geoCoordinateList; // list with potential waypoints (from _missionItems), for _currentMissionItems
if (!extractCoordinateList(_missionItems, geoCoordinateList, _firstWaypointIndex, if (!extractCoordinateList(_missionItems, geoCoordinateList, _startWaypointIndex,
std::min(_firstWaypointIndex + numberWaypoints, _missionItems.count()-2))) // -2 -> last item is land item std::min(_startWaypointIndex + numberWaypoints - 1, _missionItems.count()-2))) // -2 -> last item is land item
{ {
qWarning("WimaController::updateCurrentMissionItems(): error on waypoint extraction."); qWarning("WimaController::updateCurrentMissionItems(): error on waypoint extraction.");
return; return;
} }
_currentMissionItems.clear();
// calculate path from home to first waypoint
QList<QGeoCoordinate> path;
if ( !calcShortestPath(homeCoordinate, geoCoordinateList[0], path) ) {
qWarning("WimaController::updateCurrentMissionItems(): Not able to calc path from home to first waypoint.");
return;
}
// prepend to geoCoordinateList
for (int i = path.size()-2; i >= 0; i--) // i = path.size()-2 : last coordinate already in geoCoordinateList
geoCoordinateList.prepend(path[i]);
// calculate path from last waypoint to home
path.clear();
if ( !calcShortestPath(geoCoordinateList.last(), homeCoordinate, path) ) {
qWarning("WimaController::updateCurrentMissionItems(): Not able to calc path from home to first waypoint.");
return;
}
path.removeFirst(); // first coordinate already in geoCoordinateList
geoCoordinateList.append(path);
// create Mission Items
_missionController->removeAll();
QmlObjectListModel* missionControllerVisuals = _missionController->visualItems();
for (auto coordinate : geoCoordinateList)
_missionController->insertSimpleMissionItem(coordinate, missionControllerVisuals->count());
// set land command for last mission item
SimpleMissionItem *landItem = missionControllerVisuals->value<SimpleMissionItem*>(missionControllerVisuals->count()-1);
if (landItem == nullptr) {
qWarning("WimaController::updateCurrentMissionItems(): nullptr");
return;
}
// check vehicle type, before setting land command
Vehicle* controllerVehicle = _masterController->controllerVehicle();
MAV_CMD landCmd = controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_LAND;
if (controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(landCmd)) {
landItem->setCommand(landCmd);
} else
return;
// copy mission items to _currentMissionItems
// MissionSettingsItem *settingsItem = qobject_cast<MissionSettingsItem *>((*missionControllerVisuals)[0]);
// if (settingsItem == nullptr) {
// qWarning("WimaController::containerDataValidChanged(): Nullptr at MissionSettingsItem!");
// return;
// }
// _missionItems.append(settingsItem);
for ( int i = 1; i < missionControllerVisuals->count(); i++) {
SimpleMissionItem *visualItem = missionControllerVisuals->value<SimpleMissionItem*>(i);
if (visualItem == nullptr) {
qWarning("WimaController::updateCurrentMissionItems(): Nullptr at SimpleMissionItem!");
return;
}
SimpleMissionItem *visualItemCopy = new SimpleMissionItem(*visualItem, true, this);
_currentMissionItems.append(visualItemCopy);
}
emit currentMissionItemsChanged();
} }
void WimaController::updateWaypointPath() void WimaController::updateWaypointPath()
{ {
_waypointPath.clear(); _waypointPath.clear();
extractCoordinateList(_missionItems, _waypointPath, 1, _missionItems.count()-1); extractCoordinateList(_missionItems, _waypointPath, 0, _missionItems.count()-1);
emit waypointPathChanged(); emit waypointPathChanged();
} }
void WimaController::updateCurrentPath() void WimaController::updateCurrentPath()
{ {
_currentWaypointPath.clear(); _currentWaypointPath.clear();
extractCoordinateList(_currentMissionItems, _currentWaypointPath, 1, _currentMissionItems.count()-1); extractCoordinateList(_currentMissionItems, _currentWaypointPath, 0, _currentMissionItems.count()-1);
emit currentWaypointPathChanged(); emit currentWaypointPathChanged();
} }
......
...@@ -41,7 +41,9 @@ public: ...@@ -41,7 +41,9 @@ public:
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(QmlObjectListModel* currentMissionItems READ currentMissionItems NOTIFY currentMissionItemsChanged)
Q_PROPERTY(QVariantList waypointPath READ waypointPath NOTIFY waypointPathChanged) Q_PROPERTY(QVariantList waypointPath READ waypointPath NOTIFY waypointPathChanged)
Q_PROPERTY(QVariantList currentWaypointPath READ currentWaypointPath NOTIFY currentWaypointPathChanged)
// Property accessors // Property accessors
...@@ -55,7 +57,9 @@ public: ...@@ -55,7 +57,9 @@ public:
QGCMapPolygon joinedArea (void) const; QGCMapPolygon joinedArea (void) const;
WimaDataContainer* dataContainer (void); WimaDataContainer* dataContainer (void);
QmlObjectListModel* missionItems (void); QmlObjectListModel* missionItems (void);
QmlObjectListModel* currentMissionItems (void);
QVariantList waypointPath (void); QVariantList waypointPath (void);
QVariantList currentWaypointPath (void);
// Property setters // Property setters
...@@ -84,6 +88,16 @@ public: ...@@ -84,6 +88,16 @@ public:
// Member Methodes // Member Methodes
QJsonDocument saveToJson(FileType fileType); QJsonDocument saveToJson(FileType fileType);
bool calcShortestPath(const QGeoCoordinate &start, const QGeoCoordinate &destination, QList<QGeoCoordinate> &path);
/// extracts the coordinates stored in missionItems (list of MissionItems) and stores them in coordinateList
bool extractCoordinateList(QmlObjectListModel &missionItems, QList<QGeoCoordinate> &coordinateList);
/// extracts the coordinates (between startIndex and endIndex) stored in missionItems (list of MissionItems) and stores them in coordinateList.
bool extractCoordinateList(QmlObjectListModel &missionItems, QList<QGeoCoordinate> &coordinateList, int startIndex, int endIndex);
/// extracts the coordinates stored in missionItems (list of MissionItems) and stores them in coordinateList
bool extractCoordinateList(QmlObjectListModel &missionItems, QVariantList &coordinateList);
/// extracts the coordinates (between startIndex and endIndex) stored in missionItems (list of MissionItems) and stores them in coordinateList.
bool extractCoordinateList(QmlObjectListModel &missionItems, QVariantList &coordinateList, int startIndex, int endIndex);
signals: signals:
void masterControllerChanged (void); void masterControllerChanged (void);
void missionControllerChanged (void); void missionControllerChanged (void);
...@@ -92,11 +106,16 @@ signals: ...@@ -92,11 +106,16 @@ signals:
void dataContainerChanged (); void dataContainerChanged ();
void readyForSaveSendChanged (bool ready); void readyForSaveSendChanged (bool ready);
void missionItemsChanged (void); void missionItemsChanged (void);
void currentMissionItemsChanged (void);
void waypointPathChanged (void); void waypointPathChanged (void);
void currentWaypointPathChanged (void);
private slots: private slots:
void containerDataValidChanged (bool valid); void containerDataValidChanged (bool valid);
void updateCurrentMissionItems (void);
void updateWaypointPath (void); void updateWaypointPath (void);
void updateCurrentPath (void);
private: private:
PlanMasterController *_masterController; PlanMasterController *_masterController;
...@@ -109,7 +128,12 @@ private: ...@@ -109,7 +128,12 @@ private:
WimaServiceAreaData _serviceArea; // area for supplying WimaServiceAreaData _serviceArea; // area for supplying
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 (Mission Items) generaded by wimaPlaner, displayed in flightView
QVariantList _waypointPath; QmlObjectListModel _currentMissionItems; // contains the current mission items, which are a sub set of _missionItems,
// _currentMissionItems contains a number of mission items which can be worked off with a single battery chrage
QVariantList _waypointPath; // path connecting the items in _missionItems
QVariantList _currentWaypointPath; // path connecting the items in _currentMissionItems
int _startWaypointIndex; // index to the mission item stored in _missionItems defining the first element of _currentMissionItems
int _endWaypointIndex; // index to the mission item stored in _missionItems defining the last element of _currentMissionItems
}; };
...@@ -109,6 +109,8 @@ public: ...@@ -109,6 +109,8 @@ public:
QJsonDocument saveToJson(FileType fileType); QJsonDocument saveToJson(FileType fileType);
bool calcShortestPath(const QGeoCoordinate &start, const QGeoCoordinate &destination, QList<QGeoCoordinate> &path);
// static Members // static Members
static const char* wimaFileExtension; static const char* wimaFileExtension;
static const char* areaItemsName; static const char* areaItemsName;
...@@ -127,7 +129,6 @@ private slots: ...@@ -127,7 +129,6 @@ private slots:
void recalcPolygonInteractivity (int index); void recalcPolygonInteractivity (int index);
bool recalcJoinedArea (QString &errorString); bool recalcJoinedArea (QString &errorString);
void pushToContainer (); void pushToContainer ();
bool calcShortestPath (const QGeoCoordinate &start, const QGeoCoordinate &destination, QList<QGeoCoordinate> &path);
private: private:
// Member Functions // Member Functions
......
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