Unverified Commit 98565fdb authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #6654 from DonLakeFlyer/ArduPilotReboot

Ardu pilot reboot
parents 35d09c3c bc829486
......@@ -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
......
......@@ -3139,6 +3139,7 @@ QString Vehicle::firmwareVersionTypeString(void) const
void Vehicle::rebootVehicle()
{
_autoDisconnect = true;
sendMavCommand(_defaultComponentId, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, true, 1.0f);
}
......
......@@ -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;
}
......
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