diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponent.qml b/src/AutoPilotPlugins/APM/APMSensorsComponent.qml index 907188f048a5a4db9ceb790434d08e5a10d42da6..645fa091ea8d018ca0f81a8ce921160e59ebfdb9 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponent.qml +++ b/src/AutoPilotPlugins/APM/APMSensorsComponent.qml @@ -37,8 +37,8 @@ SetupPage { // Help text which is shown both in the status text area prior to pressing a cal button and in the // pre-calibration dialog. - readonly property string orientationHelpSet: qsTr("If the orientation is in the direction of flight, select None.") - readonly property string orientationHelpCal: qsTr("Before calibrating make sure orientation settings are correct. ") + orientationHelpSet + readonly property string orientationHelpSet: qsTr("If mounted in the direction of flight, select None.") + readonly property string orientationHelpCal: qsTr("Before calibrating make sure rotation settings are correct. ") + orientationHelpSet readonly property string compassRotationText: qsTr("If the compass or GPS module is mounted in flight direction, leave the default value (None)") readonly property string compassHelp: qsTr("For Compass calibration you will need to rotate your vehicle through a number of positions.") @@ -137,10 +137,10 @@ SetupPage { onCalibrationComplete: { switch (calType) { case APMSensorsComponentController.CalTypeAccel: - showMessage(qsTr("Calibration complete"), qsTr("Accelerometer calibration complete."), StandardButton.Ok) + showDialog(postCalibrationComponent, qsTr("Accelerometer calibration complete"), qgcView.showDialogDefaultWidth, StandardButton.Ok) break case APMSensorsComponentController.CalTypeOffboardCompass: - showMessage(qsTr("Calibration complete"), qsTr("Compass calibration complete."), StandardButton.Ok) + showDialog(postCalibrationComponent, qsTr("Compass calibration complete"), qgcView.showDialogDefaultWidth, StandardButton.Ok) break case APMSensorsComponentController.CalTypeOnboardCompass: showDialog(postOnboardCompassCalibrationComponent, qsTr("Calibration complete"), qgcView.showDialogDefaultWidth, StandardButton.Ok) @@ -262,6 +262,36 @@ SetupPage { qsTr("- Red indicates a compass which should not be used.\n\n") + qsTr("YOU MUST REBOOT YOUR VEHICLE AFTER EACH CALIBRATION.") } + + QGCButton { + text: qsTr("Reboot Vehicle") + onClicked: controller.vehicle.reboot() + } + } + } + } + + Component { + id: postCalibrationComponent + + QGCViewDialog { + Column { + anchors.margins: ScreenTools.defaultFontPixelWidth + anchors.left: parent.left + anchors.right: parent.right + spacing: ScreenTools.defaultFontPixelHeight + + QGCLabel { + anchors.left: parent.left + anchors.right: parent.right + wrapMode: Text.WordWrap + text: qsTr("YOU MUST REBOOT YOUR VEHICLE AFTER EACH CALIBRATION.") + } + + QGCButton { + text: qsTr("Reboot Vehicle") + onClicked: controller.vehicle.rebootVehicle() + } } } } @@ -343,7 +373,7 @@ SetupPage { } Column { - QGCLabel { text: qsTr("Autopilot Orientation:") } + QGCLabel { text: qsTr("Autopilot Rotation:") } FactComboBox { width: rotationColumnWidth diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index b6eedb014ec61a2d4977615a4ff5bb46863c8ce3..cd12a23557a9813a092bdb574269ec631beb63b0 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -3139,6 +3139,7 @@ QString Vehicle::firmwareVersionTypeString(void) const void Vehicle::rebootVehicle() { + _autoDisconnect = true; sendMavCommand(_defaultComponentId, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, true, 1.0f); } diff --git a/src/comm/LinkInterface.cc b/src/comm/LinkInterface.cc index d2c1923cb7e058eb4d889fe2ab05942e6006b1af..d23201c5ef4481effaa225e102b3f21b9901f069 100644 --- a/src/comm/LinkInterface.cc +++ b/src/comm/LinkInterface.cc @@ -204,7 +204,7 @@ void LinkInterface::stopHeartbeatTimer() { while (iter.hasNext()) { iter.next(); QObject::disconnect(iter.value(), &HeartbeatTimer::activeChanged, this, &LinkInterface::_activeChanged); - delete _heartbeatTimers[iter.key()]; + _heartbeatTimers[iter.key()]->deleteLater(); _heartbeatTimers[iter.key()] = nullptr; }