Commit 609e71ac authored by Valentin Platzgummer's avatar Valentin Platzgummer

Wima Menu in flight view improved

parent ced7b198
......@@ -202,7 +202,9 @@ FlightMap {
// Add wima Areas to the Map
MapItemView {
model: wimaController.visualItems
property bool _enableWima: wimaController.enableWimaController.value
model: _enableWima ? wimaController.visualItems : 0
delegate: MapPolygon{
path: object.path;
......
......@@ -120,16 +120,16 @@ Item {
// Buttons
QGCButton {
id: buttonNextMissionPhase
text: qsTr("Next Phase")
onClicked: wimaController.nextPhase();
id: buttonPreviousMissionPhase
text: qsTr("Reverse")
onClicked: wimaController.previousPhase();
Layout.fillWidth: true
}
QGCButton {
id: buttonPreviousMissionPhase
text: qsTr("Previous Phase")
onClicked: wimaController.previousPhase();
id: buttonNextMissionPhase
text: qsTr("Forward")
onClicked: wimaController.nextPhase();
Layout.fillWidth: true
}
......
......@@ -33,10 +33,11 @@ Item {
property bool _showAllItems: wimaController.showAllMissionItems.value
property bool _showCurrentItems: wimaController.showCurrentMissionItems.value
property bool _wimaEnabled: wimaController.enableWimaController.value
// Add the mission item visuals to the map
Repeater {
model: largeMapView ? (_showAllItems ? wimaController.missionItems : 0) : 0
model: largeMapView ? (_showAllItems ? (_wimaEnabled ? wimaController.missionItems : 0) : 0) : 0
z: QGroundControl.zOrderWaypointIndicators-2
delegate: WimaMissionItemMapVisual {
......@@ -53,7 +54,7 @@ Item {
// Add the current mission item visuals to the map
Repeater {
model: largeMapView ? (_showCurrentItems ? wimaController.currentMissionItems : 0) : 0
model: largeMapView ? (_showCurrentItems ? (_wimaEnabled ? wimaController.currentMissionItems :0 ) : 0) : 0
z: QGroundControl.zOrderWaypointIndicators-1
delegate: WimaMissionItemMapVisual {
......@@ -85,7 +86,7 @@ Item {
MapPolyline {
line.width: 3
line.color: _showAllItems ? mIlineColor : "transparent"
line.color: _showAllItems ? (_wimaEnabled ? mIlineColor : "transparent"): "transparent"
z: QGroundControl.zOrderWaypointLines-2
path: wimaController.waypointPath
}
......@@ -96,7 +97,7 @@ Item {
MapPolyline {
line.width: 3
line.color: _showCurrentItems ? cMIlineColor : "transparent"
line.color: _showCurrentItems ? (_wimaEnabled ? cMIlineColor : "transparent") : "transparent"
z: QGroundControl.zOrderWaypointLines-1
path: wimaController.currentWaypointPath
}
......
......@@ -168,7 +168,7 @@ SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, bool flyVie
_editorQml = QStringLiteral("qrc:/qml/SimpleItemEditor.qml");
_altitudeFact.setRawValue(other._altitudeFact.rawValue());
_amslAltAboveTerrainFact.setRawValue(other._amslAltAboveTerrainFact.rawValue());
_amslAltAboveTerrainFact.setRawValue(other._amslAltAboveTerrainFact.rawValue());
_setupMetaData();
_connectSignals();
......@@ -954,7 +954,7 @@ void SimpleMissionItem::applyNewAltitude(double newAltitude)
}
}
void SimpleMissionItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus)
void SimpleMissionItem::setMissionFlightStatus(const MissionController::MissionFlightStatus_t& missionFlightStatus)
{
// If user has not already set speed/gimbal, set defaults from previous items.
VisualMissionItem::setMissionFlightStatus(missionFlightStatus);
......
......@@ -112,7 +112,7 @@ public:
QString mapVisualQML (void) const final { return QStringLiteral("SimpleItemMapVisual.qml"); }
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void applyNewAltitude (double newAltitude) final;
void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
void setMissionFlightStatus (const MissionController::MissionFlightStatus_t &missionFlightStatus) final;
bool readyForSave (void) const final;
double additionalTimeDelay (void) const final;
......
......@@ -441,7 +441,7 @@ int StructureScanComplexItem::cameraShots(void) const
return _cameraShots;
}
void StructureScanComplexItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus)
void StructureScanComplexItem::setMissionFlightStatus(const MissionController::MissionFlightStatus_t &missionFlightStatus)
{
ComplexMissionItem::setMissionFlightStatus(missionFlightStatus);
if (!qFuzzyCompare(_cruiseSpeed, missionFlightStatus.vehicleSpeed)) {
......
......@@ -86,7 +86,7 @@ public:
double specifiedGimbalYaw (void) final { return std::numeric_limits<double>::quiet_NaN(); }
double specifiedGimbalPitch (void) final { return std::numeric_limits<double>::quiet_NaN(); }
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
void setMissionFlightStatus (const MissionController::MissionFlightStatus_t& missionFlightStatus) final;
void applyNewAltitude (double newAltitude) final;
double additionalTimeDelay (void) const final { return 0; }
......
......@@ -291,7 +291,7 @@ double TransectStyleComplexItem::greatestDistanceTo(const QGeoCoordinate &other)
return greatestDistance;
}
void TransectStyleComplexItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus)
void TransectStyleComplexItem::setMissionFlightStatus(const MissionController::MissionFlightStatus_t &missionFlightStatus)
{
ComplexMissionItem::setMissionFlightStatus(missionFlightStatus);
if (!qFuzzyCompare(_cruiseSpeed, missionFlightStatus.vehicleSpeed)) {
......
......@@ -98,7 +98,7 @@ public:
double specifiedFlightSpeed (void) final { return std::numeric_limits<double>::quiet_NaN(); }
double specifiedGimbalYaw (void) final { return std::numeric_limits<double>::quiet_NaN(); }
double specifiedGimbalPitch (void) final { return std::numeric_limits<double>::quiet_NaN(); }
void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
void setMissionFlightStatus (const MissionController::MissionFlightStatus_t& missionFlightStatus) final;
bool readyForSave (void) const override;
QString commandDescription (void) const override { return tr("Transect"); }
QString commandName (void) const override { return tr("Transect"); }
......
......@@ -85,8 +85,14 @@ const VisualMissionItem& VisualMissionItem::operator=(const VisualMissionItem& o
setAltDifference(other._altDifference);
setAltPercent(other._altPercent);
setTerrainPercent(other._terrainPercent);
setTerrainCollision(other._terrainCollision);
setAzimuth(other._azimuth);
setDistance(other._distance);
_missionGimbalYaw = other._missionGimbalYaw;
_missionVehicleYaw = other._missionVehicleYaw;
_setBoundingCube(other._boundingCube);
setMissionFlightStatus(other._missionFlightStatus);
// _childItems // necessary here?
return *this;
}
......@@ -151,7 +157,7 @@ void VisualMissionItem::setAzimuth(double azimuth)
}
}
void VisualMissionItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus)
void VisualMissionItem::setMissionFlightStatus(const MissionController::MissionFlightStatus_t& missionFlightStatus)
{
_missionFlightStatus = missionFlightStatus;
if (qIsNaN(_missionFlightStatus.gimbalYaw) && qIsNaN(_missionGimbalYaw)) {
......
......@@ -128,7 +128,7 @@ public:
/// Update item to mission flight status at point where this item appears in mission.
/// IMPORTANT: Overrides must call base class implementation
virtual void setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus);
virtual void setMissionFlightStatus(const MissionController::MissionFlightStatus_t &missionFlightStatus);
virtual bool coordinateHasRelativeAltitude (void) const = 0;
virtual bool exitCoordinateHasRelativeAltitude (void) const = 0;
......
......@@ -23,16 +23,16 @@ WimaController::WimaController(QObject *parent)
, _enableWimaController (settingsGroup, _metaDataMap[enableWimaControllerName])
, _overlapWaypoints (settingsGroup, _metaDataMap[overlapWaypointsName])
, _maxWaypointsPerPhase (settingsGroup, _metaDataMap[maxWaypointsPerPhaseName])
, _startWaypointIndex (settingsGroup, _metaDataMap[startWaypointIndexName])
, _nestPhaseStartWaypointIndex (settingsGroup, _metaDataMap[startWaypointIndexName])
, _showAllMissionItems (settingsGroup, _metaDataMap[showAllMissionItemsName])
, _showCurrentMissionItems (settingsGroup, _metaDataMap[showCurrentMissionItemsName])
{
_startWaypointIndex.setRawValue(int(1));
_nestPhaseStartWaypointIndex.setRawValue(int(1));
_showAllMissionItems.setRawValue(true);
_showCurrentMissionItems.setRawValue(true);
connect(&_overlapWaypoints, &Fact::rawValueChanged, this, &WimaController::updateNextWaypoint);
connect(&_maxWaypointsPerPhase, &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
connect(&_startWaypointIndex, &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
connect(&_maxWaypointsPerPhase, &Fact::rawValueChanged, this, &WimaController::recalcCurrentPhase);
connect(&_nestPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
}
QmlObjectListModel* WimaController::visualItems()
......@@ -109,7 +109,7 @@ Fact *WimaController::showCurrentMissionItems()
Fact *WimaController::startWaypointIndex()
{
return &_startWaypointIndex;
return &_nestPhaseStartWaypointIndex;
}
void WimaController::setMasterController(PlanMasterController *masterC)
......@@ -134,11 +134,11 @@ void WimaController::setDataContainer(WimaDataContainer *container)
{
if (container != nullptr) {
if (_container != nullptr) {
disconnect(_container, &WimaDataContainer::dataValidChanged, this, &WimaController::containerDataValidChanged);
disconnect(_container, &WimaDataContainer::dataValidChanged, this, &WimaController::fetchContainerData);
}
_container = container;
connect(_container, &WimaDataContainer::dataValidChanged, this, &WimaController::containerDataValidChanged);
connect(_container, &WimaDataContainer::dataValidChanged, this, &WimaController::fetchContainerData);
emit dataContainerChanged();
}
......@@ -146,22 +146,21 @@ void WimaController::setDataContainer(WimaDataContainer *container)
void WimaController::nextPhase()
{
updateCurrentMissionItems();
calcNextPhase();
}
void WimaController::previousPhase()
{
if (_startWaypointIndex.rawValue().toInt() > 0) {
_startWaypointIndex.setRawValue( _startWaypointIndex.rawValue().toInt() - _maxWaypointsPerPhase.rawValue().toInt()
+ _overlapWaypoints.rawValue().toInt());
if (_nestPhaseStartWaypointIndex.rawValue().toInt() > 0) {
_nestPhaseStartWaypointIndex.setRawValue( 1 + std::max(_startWaypointIndex
- _maxWaypointsPerPhase.rawValue().toInt()
+ _overlapWaypoints.rawValue().toInt(), 0));
}
}
void WimaController::resetPhase()
{
_startWaypointIndex.setRawValue(int(1));
_nestPhaseStartWaypointIndex.setRawValue(int(1));
}
void WimaController::uploadToVehicle()
......@@ -300,7 +299,7 @@ bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QVa
*
* \sa WimaDataContainer, WimaPlaner, WimaPlanData
*/
void WimaController::containerDataValidChanged(bool valid)
void WimaController::fetchContainerData(bool valid)
{
if ( valid ) {
if (_container == nullptr) {
......@@ -403,6 +402,10 @@ void WimaController::containerDataValidChanged(bool valid)
return;
}
SimpleMissionItem *visualItemCopy = new SimpleMissionItem(*visualItem, true, this);
qWarning() << visualItem->missionGimbalYaw();
qWarning() << visualItemCopy->missionGimbalYaw();
qWarning("");
_missionItems.append(visualItemCopy);
}
......@@ -410,8 +413,8 @@ void WimaController::containerDataValidChanged(bool valid)
_localPlanDataValid = true;
updateWaypointPath();
_startWaypointIndex.setRawValue(int(1));
updateCurrentMissionItems();
_nestPhaseStartWaypointIndex.setRawValue(int(1));
calcNextPhase();
} else {
_localPlanDataValid = false;
......@@ -428,21 +431,21 @@ void WimaController::containerDataValidChanged(bool valid)
#endif
}
void WimaController::updateCurrentMissionItems()
void WimaController::calcNextPhase()
{
int startWaypointIndexInt = _startWaypointIndex.rawValue().toInt()-1;
_startWaypointIndex = _nestPhaseStartWaypointIndex.rawValue().toInt()-1;
// check if data was fetched and mission end is not reached yet
if (_missionItems.count() < 1 || !_localPlanDataValid || startWaypointIndexInt >= _missionItems.count()-2)
if (_missionItems.count() < 1 || !_localPlanDataValid || _startWaypointIndex >= _missionItems.count()-2)
return;
int maxWaypointsPerPhaseInt = _maxWaypointsPerPhase.rawValue().toInt();
// determine end waypoint index
_endWaypointIndex = std::min(startWaypointIndexInt + maxWaypointsPerPhaseInt - 1, _missionItems.count()-2); // -2 -> last item is land item
_endWaypointIndex = std::min(_startWaypointIndex + maxWaypointsPerPhaseInt - 1, _missionItems.count()-2); // -2 -> last item is land item
// extract waypoints
QList<QGeoCoordinate> geoCoordinateList; // list with potential waypoints (from _missionItems), for _currentMissionItems
if (!extractCoordinateList(_missionItems, geoCoordinateList, startWaypointIndexInt, _endWaypointIndex)) {
if (!extractCoordinateList(_missionItems, geoCoordinateList, _startWaypointIndex, _endWaypointIndex)) {
qWarning("WimaController::updateCurrentMissionItems(): error on waypoint extraction.");
_currentMissionItems.clear();
return;
......@@ -450,16 +453,17 @@ void WimaController::updateCurrentMissionItems()
// set start waypoint index for next phase
if (_endWaypointIndex < _missionItems.count()-2) {
_startWaypointIndexList.append(_startWaypointIndex.rawValue().toInt());
_startWaypointIndexList.append(_nestPhaseStartWaypointIndex.rawValue().toInt());
disconnect(&_startWaypointIndex, &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
_startWaypointIndex.setRawValue(std::max(_endWaypointIndex + 2 - _overlapWaypoints.rawValue().toInt(), 1));
connect(&_startWaypointIndex, &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
disconnect(&_nestPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
int temp = 1 + std::max(_endWaypointIndex + 1 - _overlapWaypoints.rawValue().toInt(), 0);
_nestPhaseStartWaypointIndex.setRawValue(std::min(temp , _missionItems.count()-1));
connect(&_nestPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
}
else {
disconnect(&_startWaypointIndex, &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
_startWaypointIndex.setRawValue(_missionItems.count()-1); // marks that end of mission is reached
connect(&_startWaypointIndex, &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
disconnect(&_nestPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
_nestPhaseStartWaypointIndex.setRawValue(_missionItems.count()-1); // marks that end of mission is reached
connect(&_nestPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
}
// calculate path from home to first waypoint
......@@ -538,7 +542,10 @@ void WimaController::updateCurrentMissionItems()
return;
}
SimpleMissionItem *visualItemCopy = new SimpleMissionItem(*visualItem, true, this);
SimpleMissionItem *visualItemCopy = new SimpleMissionItem(*visualItem, true, this);
qWarning() << visualItem->missionGimbalYaw();
qWarning() << visualItemCopy->missionGimbalYaw();
qWarning("");
_currentMissionItems.append(visualItemCopy);
}
......@@ -564,11 +571,16 @@ void WimaController::updateCurrentPath()
void WimaController::updateNextWaypoint()
{
if (_endWaypointIndex < _missionItems.count()-2) {
disconnect(&_startWaypointIndex, &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
_startWaypointIndex.setRawValue(_endWaypointIndex + 2 - _overlapWaypoints.rawValue().toInt());
connect(&_startWaypointIndex, &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
disconnect(&_nestPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
_nestPhaseStartWaypointIndex.setRawValue(1 + std::max(_endWaypointIndex + 1 - _overlapWaypoints.rawValue().toInt(), 0));
connect(&_nestPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
}
}
void WimaController::recalcCurrentPhase()
{
_nestPhaseStartWaypointIndex.setRawValue(_startWaypointIndex + 1);
}
......@@ -137,11 +137,12 @@ signals:
void currentWaypointPathChanged (void);
private slots:
void containerDataValidChanged (bool valid);
void updateCurrentMissionItems (void);
void fetchContainerData (bool valid);
void calcNextPhase (void);
void updateWaypointPath (void);
void updateCurrentPath (void);
void updateNextWaypoint (void);
void recalcCurrentPhase (void);
private:
......@@ -169,11 +170,13 @@ private:
SettingsFact _enableWimaController; // enables or disables the wimaControler
SettingsFact _overlapWaypoints; // determines the number of overlapping waypoints between two consecutive mission phases
SettingsFact _maxWaypointsPerPhase; // determines the maximum number waypoints per phase
SettingsFact _startWaypointIndex; // index (displayed on the map, -1 to get index of item in _missionItems) of the mission item
//stored in _missionItems defining the first element of _currentMissionItems
SettingsFact _nestPhaseStartWaypointIndex; // index (displayed on the map, -1 to get index of item in _missionItems) of the mission item
// defining the first element of the next phase
SettingsFact _showAllMissionItems; // bool value, Determines whether the mission items of the overall mission are displayed or not.
SettingsFact _showCurrentMissionItems; // bool value, Determines whether the mission items of the current mission phase are displayed or not.
int _endWaypointIndex; // indes of the mission item stored in _missionItems defining the last element
// (which is not part of the return path) of _currentMissionItem
int _startWaypointIndex; // indes of the mission item stored in _missionItems defining the first element
// (which is not part of the arrival path) of _currentMissionItem
};
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