Commit 3b151cb4 authored by Valentin Platzgummer's avatar Valentin Platzgummer

123

parent 8a973ac5
...@@ -19,14 +19,16 @@ import QGroundControl.FactControls 1.0 ...@@ -19,14 +19,16 @@ import QGroundControl.FactControls 1.0
Item { Item {
id: _root id: _root
height: 600 height: mainFrame.height
width: 300 width: mainFrame.width
property var maxHeight: 500
property var maxWidth: 300
property var wimaController // must be provided by the user property var wimaController // must be provided by the user
property var planMasterController // must be provided by the user property var planMasterController // must be provided by the user
property bool _controllerValid: planMasterController !== undefined property bool _controllerValid: planMasterController !== undefined
property real _controllerProgressPct: _controllerValid ? planMasterController.missionController.progressPct : 0 property real _controllerProgressPct: _controllerValid ? planMasterController.missionController.progressPct : 0
property double _margins: ScreenTools.defaultPixelWidth*0.3
signal initSmartRTL(); signal initSmartRTL();
...@@ -58,22 +60,48 @@ Item { ...@@ -58,22 +60,48 @@ Item {
id: mainFrame id: mainFrame
anchors.left: parent.left anchors.left: parent.left
anchors.bottom: parent.bottom anchors.bottom: parent.bottom
height: enableWima.enableWimaBoolean ? parent.height : enableWima.height height: enableWima.enableWimaBoolean ? Math.min(parent.maxHeight, enableWima.height + flickable.contentHeight + 2*_margins) : enableWima.height + _margins
width: enableWima.enableWimaBoolean ? parent.width : enableWima.width width: enableWima.enableWimaBoolean ? Math.min(parent.maxWidth, flickable.contentWidth + 2*_margins) : enableWima.width
color: enableWima.enableWimaBoolean ? qgcPal.window : "transparent" color: enableWima.enableWimaBoolean ? qgcPal.window : "transparent"
radius: ScreenTools.defaultFontPixelHeight / 4 radius: ScreenTools.defaultFontPixelHeight / 4
clip: false
Component.onCompleted: {
console.log('onCompleted')
console.log('height')
console.log(height)
console.log('width')
console.log(width)
}
onHeightChanged: {
console.log('height')
console.log(height)
_root.height = mainFrame.height
}
onWidthChanged: {
console.log('width')
console.log(width)
_root.width = mainFrame.width
}
// checkbox to enable/ disable wima // checkbox to enable/ disable wima
SliderSwitch { SliderSwitch {
id: enableWima id: enableWima
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
anchors.topMargin: ScreenTools.defaultFontPixelHeight * 0.25 anchors.topMargin: _margins
anchors.top: parent.top anchors.top: parent.top
confirmText: enableWimaBoolean ? qsTr("disable WiMA") : qsTr("enable WiMA") confirmText: enableWimaBoolean ? qsTr("disable WiMA") : qsTr("enable WiMA")
property var enableWimaFact: wimaController.enableWimaController property var enableWimaFact: wimaController.enableWimaController
property bool enableWimaBoolean: enableWimaFact.value property bool enableWimaBoolean: enableWimaFact.value
Component.onCompleted: {
enableWimaFact.value = false
}
onAccept: { onAccept: {
if (enableWimaBoolean) { if (enableWimaBoolean) {
enableWimaFact.value = false enableWimaFact.value = false
...@@ -83,252 +111,276 @@ Item { ...@@ -83,252 +111,276 @@ Item {
} }
} }
Item { /*MouseArea {
id: flickableWrapper anchors.fill: enableWima
hoverEnabled: true
property var enableWimaFact: wimaController.enableWimaController
property bool enableWimaBoolean: enableWimaFact.value
onEntered: {
timer.stop()
enableWima.visible = true
}
onExited: {
if (enableWimaBoolean === false) {
timer.start()
}
}
}
Timer {
id: timer
interval: 1000
running: false
repeat: false
onTriggered: enableWima.visible = false
}*/
QGCFlickable {
id: flickable
clip: false
anchors.top: enableWima.bottom anchors.top: enableWima.bottom
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right contentHeight: mainColumn.height
anchors.bottom: parent.bottom contentWidth: mainColumn.width
anchors.margins: ScreenTools.defaultFontPixelHeight*0.5
onContentHeightChanged: {
QGCFlickable { console.log('contentHeight')
clip: true console.log(contentHeight)
anchors.fill: parent mainFrame.height = enableWima.enableWimaBoolean ? Math.min(parent.maxHeight, enableWima.height + flickable.contentHeight + 2*_margins) : enableWima.height + _margins
contentHeight: wrapperItem.height }
contentWidth: wrapperItem.width
onContentWidthChanged: {
Item { console.log('contentWidth')
id: wrapperItem console.log(contentWidth)
width: Math.max(flickableWrapper.width, mainColumn.width) mainFrame.width = enableWima.enableWimaBoolean ? Math.min(parent.maxWidth, flickable.contentWidth + 2*_margins) : enableWima.width
height: mainColumn.height }
Column {
property int itemWidth: 120 id: mainColumn
anchors.horizontalCenter: parent.horizontalCenter
Column { spacing: ScreenTools.defaultFontPixelHeight * 0.3
id: mainColumn
anchors.horizontalCenter: parent.horizontalCenter SectionHeader{
spacing: ScreenTools.defaultFontPixelHeight * 0.3 id: settingsHeader
text: qsTr("Settings")
SectionHeader{ }
id: settingsHeader GridLayout {
text: qsTr("Settings") columns: 2
} rowSpacing: ScreenTools.defaultFontPixelHeight * 0.5
GridLayout { columnSpacing: ScreenTools.defaultFontPixelHeight * 0.5
columns: 2 visible: settingsHeader.checked
rowSpacing: ScreenTools.defaultFontPixelHeight * 0.5
columnSpacing: ScreenTools.defaultFontPixelHeight * 0.5 QGCLabel {
visible: settingsHeader.checked text: qsTr("Next Waypoint")
Layout.fillWidth: true
QGCLabel { }
text: qsTr("Next Waypoint") FactTextField {
Layout.fillWidth: true fact: wimaController.startWaypointIndex
} Layout.fillWidth: true
FactTextField { }
fact: wimaController.startWaypointIndex
Layout.fillWidth: true QGCLabel {
} text: qsTr("Max Waypoints")
Layout.fillWidth: true
QGCLabel { }
text: qsTr("Max Waypoints") FactTextField {
Layout.fillWidth: true fact: wimaController.maxWaypointsPerPhase
} Layout.fillWidth: true
FactTextField { }
fact: wimaController.maxWaypointsPerPhase
Layout.fillWidth: true QGCLabel {
} text: qsTr("Overlap")
Layout.fillWidth: true
QGCLabel { }
text: qsTr("Overlap") FactTextField {
Layout.fillWidth: true fact: wimaController.overlapWaypoints
} Layout.fillWidth: true
FactTextField { }
fact: wimaController.overlapWaypoints }
Layout.fillWidth: true GridLayout {
} columns: 2
} rowSpacing: ScreenTools.defaultFontPixelHeight * 0.5
GridLayout { columnSpacing: ScreenTools.defaultFontPixelHeight * 0.5
columns: 2 visible: settingsHeader.checked
rowSpacing: ScreenTools.defaultFontPixelHeight * 0.5
columnSpacing: ScreenTools.defaultFontPixelHeight * 0.5 FactCheckBox {
visible: settingsHeader.checked text: qsTr("Show All")
fact: wimaController.showAllMissionItems
FactCheckBox { Layout.fillWidth: true
text: qsTr("Show All") }
fact: wimaController.showAllMissionItems
Layout.fillWidth: true FactCheckBox {
} text: qsTr("Show Current")
fact: wimaController.showCurrentMissionItems
FactCheckBox { Layout.fillWidth: true
text: qsTr("Show Current") }
fact: wimaController.showCurrentMissionItems
Layout.fillWidth: true FactCheckBox {
} text: qsTr("Reverse")
fact: wimaController.reverse
FactCheckBox { Layout.fillWidth: true
text: qsTr("Reverse") }
fact: wimaController.reverse } // Grid
Layout.fillWidth: true
} SectionHeader{
} // Grid id: missionHeader
text: qsTr("Mission")
SectionHeader{ }
id: missionHeader GridLayout {
text: qsTr("Mission") columns: 2
} rowSpacing: ScreenTools.defaultFontPixelHeight * 0.5
GridLayout { columnSpacing: ScreenTools.defaultFontPixelHeight * 0.5
columns: 2 visible: missionHeader.checked
rowSpacing: ScreenTools.defaultFontPixelHeight * 0.5 width: parent.width
columnSpacing: ScreenTools.defaultFontPixelHeight * 0.5
visible: missionHeader.checked QGCLabel {
width: parent.width text: qsTr("Speed")
Layout.fillWidth: true
QGCLabel { }
text: qsTr("Speed") FactTextField {
Layout.fillWidth: true fact: wimaController.flightSpeed
} Layout.fillWidth: true
FactTextField { }
fact: wimaController.flightSpeed
Layout.fillWidth: true QGCLabel {
} text: qsTr("Altitude")
Layout.fillWidth: true
QGCLabel { }
text: qsTr("Altitude") FactTextField {
Layout.fillWidth: true fact: wimaController.altitude
} Layout.fillWidth: true
FactTextField { }
fact: wimaController.altitude
Layout.fillWidth: true }
}
GridLayout {
} columns: 2
rowSpacing: ScreenTools.defaultFontPixelHeight * 0.5
GridLayout { columnSpacing: ScreenTools.defaultFontPixelHeight * 0.5
columns: 2 visible: missionHeader.checked
rowSpacing: ScreenTools.defaultFontPixelHeight * 0.5 width: parent.width
columnSpacing: ScreenTools.defaultFontPixelHeight * 0.5
visible: missionHeader.checked // Buttons
width: parent.width QGCButton {
id: buttonPreviousMissionPhase
// Buttons text: qsTr("Reverse")
QGCButton { onClicked: wimaController.previousPhase()
id: buttonPreviousMissionPhase Layout.fillWidth: true
text: qsTr("Reverse") }
onClicked: wimaController.previousPhase()
Layout.fillWidth: true QGCButton {
} id: buttonNextMissionPhase
text: qsTr("Forward")
QGCButton { onClicked: wimaController.nextPhase()
id: buttonNextMissionPhase Layout.fillWidth: true
text: qsTr("Forward") }
onClicked: wimaController.nextPhase()
Layout.fillWidth: true QGCButton {
} id: buttonResetPhase
text: qsTr("Reset Phase")
QGCButton { onClicked: wimaController.resetPhase();
id: buttonResetPhase Layout.columnSpan: 2
text: qsTr("Reset Phase") Layout.fillWidth: true
onClicked: wimaController.resetPhase(); }
Layout.columnSpan: 2 } // Grid
Layout.fillWidth: true
} SectionHeader{
} // Grid id: vehicleHeader
text: qsTr("Vehicle")
SectionHeader{ }
id: vehicleHeader GridLayout {
text: qsTr("Vehicle") columns: 2
} rowSpacing: ScreenTools.defaultFontPixelHeight * 0.5
GridLayout { columnSpacing: ScreenTools.defaultFontPixelHeight * 0.5
columns: 2 visible: vehicleHeader.checked
rowSpacing: ScreenTools.defaultFontPixelHeight * 0.5 width: parent.width
columnSpacing: ScreenTools.defaultFontPixelHeight * 0.5
visible: vehicleHeader.checked QGCButton {
width: parent.width id: buttonUpload
text: qsTr("Upload")
QGCButton { onClicked: wimaController.uploadToVehicle()
id: buttonUpload Layout.fillWidth: true
text: qsTr("Upload") }
onClicked: wimaController.uploadToVehicle()
Layout.fillWidth: true QGCButton {
} id: buttonRemoveFromVehicle
text: qsTr("Remove")
QGCButton { onClicked: wimaController.removeFromVehicle()
id: buttonRemoveFromVehicle Layout.fillWidth: true
text: qsTr("Remove") }
onClicked: wimaController.removeFromVehicle()
Layout.fillWidth: true QGCButton {
} id: buttonSmartRTL
text: qsTr("Smart RTL")
QGCButton { onClicked: initSmartRTL()
id: buttonSmartRTL Layout.columnSpan: 2
text: qsTr("Smart RTL") Layout.fillWidth: true
onClicked: initSmartRTL() }
Layout.columnSpan: 2
Layout.fillWidth: true
} // progess bar
Rectangle {
id: progressBar
// progess bar height: 4
Rectangle { width: _controllerProgressPct * parent.width
id: progressBar color: qgcPal.colorGreen
height: 4 visible: false
width: _controllerProgressPct * parent.width Layout.columnSpan: 2
color: qgcPal.colorGreen Layout.fillWidth: true
visible: false }
Layout.columnSpan: 2
Layout.fillWidth: true QGCLabel {
} id: uploadCompleteText
font.pointSize: ScreenTools.largeFontPointSize
QGCLabel { Layout.columnSpan: 2
id: uploadCompleteText horizontalAlignment: Text.AlignHCenter
font.pointSize: ScreenTools.largeFontPointSize verticalAlignment: Text.AlignVCenter
Layout.columnSpan: 2 text: "Done"
horizontalAlignment: Text.AlignHCenter visible: false
verticalAlignment: Text.AlignVCenter Layout.fillWidth: true
text: "Done" }
visible: false }
Layout.fillWidth: true
} SectionHeader {
} id: statsHeader
text: qsTr("Statistics")
SectionHeader { }
id: statsHeader GridLayout {
text: qsTr("Statistics") columns: 2
} rowSpacing: ScreenTools.defaultFontPixelHeight * 0.5
GridLayout { anchors.topMargin: ScreenTools.defaultFontPixelHeight * 0.5
columns: 2 visible: statsHeader.checked
rowSpacing: ScreenTools.defaultFontPixelHeight * 0.5
anchors.topMargin: ScreenTools.defaultFontPixelHeight * 0.5 QGCLabel {
visible: statsHeader.checked text: qsTr("Phase Length: ")
wrapMode: Text.WordWrap
QGCLabel { Layout.fillWidth: true
text: qsTr("Phase Length: ") }
wrapMode: Text.WordWrap QGCLabel {
Layout.fillWidth: true text: wimaController.phaseDistance >= 0 ? wimaController.phaseDistance.toFixed(2) + " m": ""
} wrapMode: Text.WordWrap
QGCLabel { Layout.fillWidth: true
text: wimaController.phaseDistance >= 0 ? wimaController.phaseDistance.toFixed(2) + " m": "" }
wrapMode: Text.WordWrap
Layout.fillWidth: true QGCLabel {
} text: qsTr("Phase Duration: ")
wrapMode: Text.WordWrap
QGCLabel { Layout.fillWidth: true
text: qsTr("Phase Duration: ") }
wrapMode: Text.WordWrap QGCLabel {
Layout.fillWidth: true text: wimaController.phaseDuration >= 0 ? getTime(wimaController.phaseDuration) : ""
} wrapMode: Text.WordWrap
QGCLabel { Layout.fillWidth: true
text: wimaController.phaseDuration >= 0 ? getTime(wimaController.phaseDuration) : "" }
wrapMode: Text.WordWrap QGCLabel {
Layout.fillWidth: true text: ""
} Layout.columnSpan: 2
QGCLabel { }
text: "" }
Layout.columnSpan: 2 } // settingsColumn
} } // QGCFlickable
}
} // settingsColumn
} // wrapperItem
} // QGCFlickable
} // Item
} }
} }
...@@ -32,8 +32,8 @@ WimaController::WimaController(QObject *parent) ...@@ -32,8 +32,8 @@ WimaController::WimaController(QObject *parent)
, _flightSpeed (settingsGroup, _metaDataMap[flightSpeedName]) , _flightSpeed (settingsGroup, _metaDataMap[flightSpeedName])
, _altitude (settingsGroup, _metaDataMap[altitudeName]) , _altitude (settingsGroup, _metaDataMap[altitudeName])
, _reverse (settingsGroup, _metaDataMap[reverseName]) , _reverse (settingsGroup, _metaDataMap[reverseName])
, _endWaypointIndex (0)
, _startWaypointIndex (0) , _startWaypointIndex (0)
, _lastMissionPhaseReached (false)
, _uploadOverrideRequired (false) , _uploadOverrideRequired (false)
, _phaseDistance (-1) , _phaseDistance (-1)
, _phaseDuration (-1) , _phaseDuration (-1)
...@@ -42,7 +42,7 @@ WimaController::WimaController(QObject *parent) ...@@ -42,7 +42,7 @@ WimaController::WimaController(QObject *parent)
, _executingSmartRTL (false) , _executingSmartRTL (false)
{ {
_nextPhaseStartWaypointIndex.setRawValue(int(1)); //_nextPhaseStartWaypointIndex.setRawValue(int(1));
_showAllMissionItems.setRawValue(true); _showAllMissionItems.setRawValue(true);
_showCurrentMissionItems.setRawValue(true); _showCurrentMissionItems.setRawValue(true);
connect(&_overlapWaypoints, &Fact::rawValueChanged, this, &WimaController::updateNextWaypoint); connect(&_overlapWaypoints, &Fact::rawValueChanged, this, &WimaController::updateNextWaypoint);
...@@ -50,6 +50,7 @@ WimaController::WimaController(QObject *parent) ...@@ -50,6 +50,7 @@ WimaController::WimaController(QObject *parent)
connect(&_nextPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase); connect(&_nextPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
connect(&_flightSpeed, &Fact::rawValueChanged, this, &WimaController::updateSpeed); connect(&_flightSpeed, &Fact::rawValueChanged, this, &WimaController::updateSpeed);
connect(&_altitude, &Fact::rawValueChanged, this, &WimaController::updateAltitude); connect(&_altitude, &Fact::rawValueChanged, this, &WimaController::updateAltitude);
connect(&_reverse, &Fact::rawValueChanged, this, &WimaController::reverseChangedHandler);
// setup low battery handling // setup low battery handling
connect(&_checkBatteryTimer, &QTimer::timeout, this, &WimaController::checkBatteryLevel); connect(&_checkBatteryTimer, &QTimer::timeout, this, &WimaController::checkBatteryLevel);
...@@ -218,19 +219,35 @@ void WimaController::nextPhase() ...@@ -218,19 +219,35 @@ void WimaController::nextPhase()
} }
void WimaController::previousPhase() void WimaController::previousPhase()
{ {
if (_nextPhaseStartWaypointIndex.rawValue().toInt() > 0) { bool reverseBool = _reverse.rawValue().toBool();
_lastMissionPhaseReached = false; if (!reverseBool){
_nextPhaseStartWaypointIndex.setRawValue(std::max(_startWaypointIndex int startIndex = _nextPhaseStartWaypointIndex.rawValue().toInt();
- _maxWaypointsPerPhase.rawValue().toInt() if (startIndex > 0) {
+ _overlapWaypoints.rawValue().toInt(), 1)); _nextPhaseStartWaypointIndex.setRawValue(1+std::max(_startWaypointIndex
- _maxWaypointsPerPhase.rawValue().toInt()
+ _overlapWaypoints.rawValue().toInt(), 0));
}
}
else {
int startIndex = _nextPhaseStartWaypointIndex.rawValue().toInt();
if (startIndex <= _missionItems.count()) {
_nextPhaseStartWaypointIndex.setRawValue(1+std::min(_startWaypointIndex
+ _maxWaypointsPerPhase.rawValue().toInt()
- _overlapWaypoints.rawValue().toInt(), _missionItems.count()-1));
}
} }
} }
void WimaController::resetPhase() void WimaController::resetPhase()
{ {
_lastMissionPhaseReached = false; bool reverseBool = _reverse.rawValue().toBool();
_nextPhaseStartWaypointIndex.setRawValue(int(1)); if (!reverseBool) {
_nextPhaseStartWaypointIndex.setRawValue(int(1));
}
else {
_nextPhaseStartWaypointIndex.setRawValue(_missionItems.count());
}
} }
bool WimaController::uploadToVehicle() bool WimaController::uploadToVehicle()
...@@ -450,7 +467,6 @@ bool WimaController::fetchContainerData() ...@@ -450,7 +467,6 @@ bool WimaController::fetchContainerData()
emit currentWaypointPathChanged(); emit currentWaypointPathChanged();
_localPlanDataValid = false; _localPlanDataValid = false;
_lastMissionPhaseReached = false;
if (_container == nullptr) { if (_container == nullptr) {
qWarning("WimaController::fetchContainerData(): No container assigned!"); qWarning("WimaController::fetchContainerData(): No container assigned!");
...@@ -536,7 +552,8 @@ bool WimaController::fetchContainerData() ...@@ -536,7 +552,8 @@ bool WimaController::fetchContainerData()
// set _nextPhaseStartWaypointIndex to 1 // set _nextPhaseStartWaypointIndex to 1
disconnect(&_nextPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase); disconnect(&_nextPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
_nextPhaseStartWaypointIndex.setRawValue(int(1)); bool reverse = _reverse.rawValue().toBool();
_nextPhaseStartWaypointIndex.setRawValue(reverse? _missionItems.count() : int(1));
connect(&_nextPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase); connect(&_nextPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
if(!calcNextPhase()) if(!calcNextPhase())
...@@ -554,46 +571,51 @@ bool WimaController::fetchContainerData() ...@@ -554,46 +571,51 @@ bool WimaController::fetchContainerData()
bool WimaController::calcNextPhase() bool WimaController::calcNextPhase()
{ {
if (_missionItems.count() < 1 || _lastMissionPhaseReached) if (_missionItems.count() < 1) {
_startWaypointIndex = 0;
_endWaypointIndex = 0;
return false; return false;
}
_currentMissionItems.clearAndDeleteContents(); _currentMissionItems.clearAndDeleteContents();
_currentWaypointPath.clear(); _currentWaypointPath.clear();
emit currentMissionItemsChanged(); emit currentMissionItemsChanged();
emit currentWaypointPathChanged(); emit currentWaypointPathChanged();
bool reverseBool = _reverse.rawValue().toBool(); // Reverses the phase direction. Phases go from high to low waypoint numbers, if true. bool reverse = _reverse.rawValue().toBool(); // Reverses the phase direction. Phases go from high to low waypoint numbers, if true.
_startWaypointIndex = _nextPhaseStartWaypointIndex.rawValue().toInt()-1; int startIndex = _nextPhaseStartWaypointIndex.rawValue().toInt()-1;
if (!reverseBool) { if (!reverse) {
if (_startWaypointIndex > _missionItems.count()-1) if (startIndex > _missionItems.count()-1)
return false; return false;
} }
else { else {
if (_startWaypointIndex < 0) if (startIndex < 0)
return false; return false;
} }
_startWaypointIndex = startIndex;
int maxWaypointsPerPhaseInt = _maxWaypointsPerPhase.rawValue().toInt(); int maxWaypointsPerPhase = _maxWaypointsPerPhase.rawValue().toInt();
// determine end waypoint index // determine end waypoint index
if (!reverseBool) { bool lastMissionPhaseReached = false;
_endWaypointIndex = std::min(_startWaypointIndex + maxWaypointsPerPhaseInt - 1, _missionItems.count()-1); if (!reverse) {
_endWaypointIndex = std::min(_startWaypointIndex + maxWaypointsPerPhase - 1, _missionItems.count()-1);
if (_endWaypointIndex == _missionItems.count() - 1) if (_endWaypointIndex == _missionItems.count() - 1)
_lastMissionPhaseReached = true; lastMissionPhaseReached = true;
} }
else { else {
_endWaypointIndex = std::max(_startWaypointIndex - maxWaypointsPerPhaseInt + 1, 0); _endWaypointIndex = std::max(_startWaypointIndex - maxWaypointsPerPhase + 1, 0);
if (_endWaypointIndex == 0) if (_endWaypointIndex == 0)
_lastMissionPhaseReached = true; lastMissionPhaseReached = true;
} }
// extract waypoints // extract waypoints
QList<QGeoCoordinate> geoCoordinateList; // list with potential waypoints (from _missionItems), for _currentMissionItems QList<QGeoCoordinate> geoCoordinateList; // list with potential waypoints (from _missionItems), for _currentMissionItems
if (!reverseBool) { if (!reverse) {
if (!extractCoordinateList(_missionItems, geoCoordinateList, _startWaypointIndex, _endWaypointIndex)) { if (!extractCoordinateList(_missionItems, geoCoordinateList, _startWaypointIndex, _endWaypointIndex)) {
qWarning("WimaController::calcNextPhase(): error on waypoint extraction."); qWarning("WimaController::calcNextPhase(): error on waypoint extraction.");
return false; return false;
...@@ -614,9 +636,9 @@ bool WimaController::calcNextPhase() ...@@ -614,9 +636,9 @@ bool WimaController::calcNextPhase()
// set start waypoint index for next phase // set start waypoint index for next phase
if (!_lastMissionPhaseReached) { if (!lastMissionPhaseReached) {
disconnect(&_nextPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase); disconnect(&_nextPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
if (!reverseBool) { if (!reverse) {
int untruncated = std::max(_endWaypointIndex + 1 - _overlapWaypoints.rawValue().toInt(), 0); int untruncated = std::max(_endWaypointIndex + 1 - _overlapWaypoints.rawValue().toInt(), 0);
int truncated = std::min(untruncated , _missionItems.count()-1); int truncated = std::min(untruncated , _missionItems.count()-1);
_nextPhaseStartWaypointIndex.setRawValue(truncated + 1); _nextPhaseStartWaypointIndex.setRawValue(truncated + 1);
...@@ -747,7 +769,6 @@ void WimaController::updateNextWaypoint() ...@@ -747,7 +769,6 @@ void WimaController::updateNextWaypoint()
void WimaController::recalcCurrentPhase() void WimaController::recalcCurrentPhase()
{ {
_lastMissionPhaseReached = false;
disconnect(&_nextPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase); disconnect(&_nextPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
_nextPhaseStartWaypointIndex.setRawValue(_startWaypointIndex + 1); _nextPhaseStartWaypointIndex.setRawValue(_startWaypointIndex + 1);
connect(&_nextPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase); connect(&_nextPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
...@@ -845,6 +866,15 @@ void WimaController::enableDisableLowBatteryHandling(QVariant enable) ...@@ -845,6 +866,15 @@ void WimaController::enableDisableLowBatteryHandling(QVariant enable)
} }
} }
void WimaController::reverseChangedHandler()
{
disconnect(&_nextPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
_nextPhaseStartWaypointIndex.setRawValue(_endWaypointIndex+1);
connect(&_nextPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
calcNextPhase();
}
void WimaController::_setPhaseDistance(double distance) void WimaController::_setPhaseDistance(double distance)
{ {
if (!qFuzzyCompare(distance, _phaseDistance)) { if (!qFuzzyCompare(distance, _phaseDistance)) {
...@@ -996,7 +1026,7 @@ void WimaController::_setVehicleHasLowBattery(bool batteryLow) ...@@ -996,7 +1026,7 @@ void WimaController::_setVehicleHasLowBattery(bool batteryLow)
bool WimaController::_executeSmartRTL(QString &errorSring) bool WimaController::_executeSmartRTL(QString &errorSring)
{ {
Q_UNUSED(errorSring); Q_UNUSED(errorSring)
_executingSmartRTL = true; _executingSmartRTL = true;
connect(masterController()->managerVehicle(), &Vehicle::flyingChanged, this, &WimaController::smartRTLCleanUp); connect(masterController()->managerVehicle(), &Vehicle::flyingChanged, this, &WimaController::smartRTLCleanUp);
forceUploadToVehicle(); forceUploadToVehicle();
......
...@@ -177,6 +177,7 @@ private slots: ...@@ -177,6 +177,7 @@ private slots:
void checkBatteryLevel (void); void checkBatteryLevel (void);
void smartRTLCleanUp (bool flying); // cleans up after successfull smart RTL void smartRTLCleanUp (bool flying); // cleans up after successfull smart RTL
void enableDisableLowBatteryHandling (QVariant enable); void enableDisableLowBatteryHandling (QVariant enable);
void reverseChangedHandler ();
private: private:
void _setPhaseDistance(double distance); void _setPhaseDistance(double distance);
...@@ -224,7 +225,6 @@ private: ...@@ -224,7 +225,6 @@ private:
// (which is not part of the return path) of _currentMissionItem // (which is not part of the return path) of _currentMissionItem
int _startWaypointIndex; // indes of the mission item stored in _missionItems defining the first element int _startWaypointIndex; // indes of the mission item stored in _missionItems defining the first element
// (which is not part of the arrival path) of _currentMissionItem // (which is not part of the arrival path) of _currentMissionItem
bool _lastMissionPhaseReached;
bool _uploadOverrideRequired; // Is set to true if uploadToVehicle() did not suceed because the vehicle is not inside the service area. bool _uploadOverrideRequired; // Is set to true if uploadToVehicle() did not suceed because the vehicle is not inside the service area.
// The user can override the upload lock with a slider, this will reset this variable to false. // The user can override the upload lock with a slider, this will reset this variable to false.
double _phaseDistance; // the lenth in meters of the current phase double _phaseDistance; // the lenth in meters of the current phase
......
...@@ -708,7 +708,11 @@ WimaPlanData WimaPlaner::toPlanData() ...@@ -708,7 +708,11 @@ WimaPlanData WimaPlaner::toPlanData()
// convert mission items to mavlink commands // convert mission items to mavlink commands
QObject deleteObject; // used to automatically delete content of rgMissionItems after this function call QObject deleteObject; // used to automatically delete content of rgMissionItems after this function call
QList<MissionItem*> rgMissionItems; QList<MissionItem*> rgMissionItems;
MissionController::convertToMissionItems(_missionController->visualItems(), rgMissionItems, &deleteObject); QmlObjectListModel *visualItems = _missionController->visualItems();
QmlObjectListModel visualItemsToCopy;
for (int i = _arrivalPathLength+1; i < visualItems->count()-_returnPathLength; i++)
visualItemsToCopy.append(visualItems->get(i));
MissionController::convertToMissionItems(&visualItemsToCopy, rgMissionItems, &deleteObject);
// store mavlink commands // store mavlink commands
planData.append(rgMissionItems); planData.append(rgMissionItems);
......
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