Commit 0b539643 authored by Lorenz Meier's avatar Lorenz Meier

Merge pull request #1759 from mavlink/airframeconfig_usability_fix

Airframeconfig usability fix
parents 32ec7228 76905ae6
...@@ -111,7 +111,7 @@ QGCView { ...@@ -111,7 +111,7 @@ QGCView {
QGCLabel { QGCLabel {
anchors.top: headingSpacer.bottom anchors.top: headingSpacer.bottom
width: parent.width - applyButton.width - 5 width: parent.width - applyButton.width - 5
text: "Select your airframe type and specific vehicle bellow. Click 'Apply and Restart' when ready and your vehicle will be disconnected, rebooted to the new settings and re-connected." text: "Please select your airframe type. Click 'Apply and Restart' to reboot the autopilot. Please re-connect then manually."
wrapMode: Text.WordWrap wrapMode: Text.WordWrap
} }
...@@ -151,12 +151,18 @@ QGCView { ...@@ -151,12 +151,18 @@ QGCView {
// Outer summary item rectangle // Outer summary item rectangle
Rectangle { Rectangle {
id: airframeBackground
readonly property real titleHeight: 30 readonly property real titleHeight: 30
readonly property real innerMargin: 10 readonly property real innerMargin: 10
width: 250 width: 250
height: 200 height: 200
color: qgcPal.windowShade color: (modelData.name != controller.currentAirframeType) ? qgcPal.windowShade : qgcPal.buttonHighlight
MouseArea {
anchors.fill: parent
onClicked: airframeCheckBox.checked = true
}
Rectangle { Rectangle {
id: title id: title
...@@ -200,6 +206,9 @@ QGCView { ...@@ -200,6 +206,9 @@ QGCView {
onCheckedChanged: { onCheckedChanged: {
if (checked && combo.currentIndex != -1) { if (checked && combo.currentIndex != -1) {
controller.autostartId = modelData.airframes[combo.currentIndex].autostartId controller.autostartId = modelData.airframes[combo.currentIndex].autostartId
airframeBackground.color = qgcPal.buttonHighlight;
} else {
airframeBackground.color = qgcPal.windowShade;
} }
} }
} }
...@@ -212,11 +221,13 @@ QGCView { ...@@ -212,11 +221,13 @@ QGCView {
anchors.top: image.bottom anchors.top: image.bottom
width: parent.width - (innerMargin * 2) width: parent.width - (innerMargin * 2)
model: modelData.airframes model: modelData.airframes
currentIndex: (modelData.name == controller.currentAirframeType) ? controller.currentVehicleIndex : 0 currentIndex: (modelData.name == controller.currentAirframeType) ? controller.currentVehicleIndex : -1
onCurrentIndexChanged: { onActivated: {
if (airframeCheckBox.checked) { if (index != -1) {
controller.autostartId = modelData.airframes[currentIndex].autostartId currentIndex = index
controller.autostartId = modelData.airframes[index].autostartId
airframeCheckBox.checked = true;
} }
} }
} }
......
...@@ -127,7 +127,7 @@ void AirframeComponentController::_waitParamWriteSignal(QVariant value) ...@@ -127,7 +127,7 @@ void AirframeComponentController::_waitParamWriteSignal(QVariant value)
// Now that both params have made it to the vehicle we can reboot it. All these signals are flying // Now that both params have made it to the vehicle we can reboot it. All these signals are flying
// around on the main thread, so we need to allow the stack to unwind back to the event loop before // around on the main thread, so we need to allow the stack to unwind back to the event loop before
// we reboot. // we reboot.
QTimer::singleShot(100, this, &AirframeComponentController::_rebootAfterStackUnwind); QTimer::singleShot(800, this, &AirframeComponentController::_rebootAfterStackUnwind);
} }
} }
...@@ -135,8 +135,10 @@ void AirframeComponentController::_rebootAfterStackUnwind(void) ...@@ -135,8 +135,10 @@ void AirframeComponentController::_rebootAfterStackUnwind(void)
{ {
_uas->executeCommand(MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0); _uas->executeCommand(MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0);
qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents); qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
QGC::SLEEP::sleep(1); for (unsigned i = 0; i < 2000; i++) {
qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents); QGC::SLEEP::usleep(500);
qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
}
LinkManager::instance()->disconnectAll(); LinkManager::instance()->disconnectAll();
qgcApp()->restoreOverrideCursor(); qgcApp()->restoreOverrideCursor();
} }
......
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