15 changed files with 1518 additions and 41 deletions
@ -0,0 +1,116 @@ |
|||||||
|
/*=====================================================================
|
||||||
|
|
||||||
|
QGroundControl Open Source Ground Control Station |
||||||
|
|
||||||
|
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||||
|
|
||||||
|
This file is part of the QGROUNDCONTROL project |
||||||
|
|
||||||
|
QGROUNDCONTROL is free software: you can redistribute it and/or modify |
||||||
|
it under the terms of the GNU General Public License as published by |
||||||
|
the Free Software Foundation, either version 3 of the License, or |
||||||
|
(at your option) any later version. |
||||||
|
|
||||||
|
QGROUNDCONTROL is distributed in the hope that it will be useful, |
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of |
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |
||||||
|
GNU General Public License for more details. |
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License |
||||||
|
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
======================================================================*/ |
||||||
|
|
||||||
|
#include "APMSensorsComponent.h" |
||||||
|
#include "APMAutoPilotPlugin.h" |
||||||
|
#include "APMSensorsComponentController.h" |
||||||
|
|
||||||
|
// These two list must be kept in sync
|
||||||
|
|
||||||
|
APMSensorsComponent::APMSensorsComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : |
||||||
|
APMComponent(vehicle, autopilot, parent), |
||||||
|
_name(tr("Sensors")) |
||||||
|
{ |
||||||
|
|
||||||
|
} |
||||||
|
|
||||||
|
QString APMSensorsComponent::name(void) const |
||||||
|
{ |
||||||
|
return _name; |
||||||
|
} |
||||||
|
|
||||||
|
QString APMSensorsComponent::description(void) const |
||||||
|
{ |
||||||
|
return tr("The Sensors Component allows you to calibrate the sensors within your vehicle. " |
||||||
|
"Prior to flight you must calibrate the Magnetometer, Gyroscope and Accelerometer."); |
||||||
|
} |
||||||
|
|
||||||
|
QString APMSensorsComponent::iconResource(void) const |
||||||
|
{ |
||||||
|
return "/qmlimages/SensorsComponentIcon.png"; |
||||||
|
} |
||||||
|
|
||||||
|
bool APMSensorsComponent::requiresSetup(void) const |
||||||
|
{ |
||||||
|
return true; |
||||||
|
} |
||||||
|
|
||||||
|
bool APMSensorsComponent::setupComplete(void) const |
||||||
|
{ |
||||||
|
foreach(QString triggerParam, setupCompleteChangedTriggerList()) { |
||||||
|
if (_autopilot->getParameterFact(FactSystem::defaultComponentId, triggerParam)->rawValue().toFloat() == 0.0f) { |
||||||
|
return false; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
return true; |
||||||
|
} |
||||||
|
|
||||||
|
QString APMSensorsComponent::setupStateDescription(void) const |
||||||
|
{ |
||||||
|
const char* stateDescription; |
||||||
|
|
||||||
|
if (requiresSetup()) { |
||||||
|
stateDescription = "Requires calibration"; |
||||||
|
} else { |
||||||
|
stateDescription = "Calibrated"; |
||||||
|
} |
||||||
|
return QString(stateDescription); |
||||||
|
} |
||||||
|
|
||||||
|
QStringList APMSensorsComponent::setupCompleteChangedTriggerList(void) const |
||||||
|
{ |
||||||
|
QStringList triggers; |
||||||
|
|
||||||
|
triggers << "COMPASS_OFS_X" << "COMPASS_OFS_X" << "COMPASS_OFS_X" |
||||||
|
<< "INS_ACCOFFS_X" << "INS_ACCOFFS_Y" << "INS_ACCOFFS_Z"; |
||||||
|
|
||||||
|
return triggers; |
||||||
|
} |
||||||
|
|
||||||
|
QStringList APMSensorsComponent::paramFilterList(void) const |
||||||
|
{ |
||||||
|
return QStringList(); |
||||||
|
} |
||||||
|
|
||||||
|
QUrl APMSensorsComponent::setupSource(void) const |
||||||
|
{ |
||||||
|
return QUrl::fromUserInput("qrc:/qml/APMSensorsComponent.qml"); |
||||||
|
} |
||||||
|
|
||||||
|
QUrl APMSensorsComponent::summaryQmlSource(void) const |
||||||
|
{ |
||||||
|
return QUrl::fromUserInput("qrc:/qml/APMSensorsComponentSummary.qml"); |
||||||
|
} |
||||||
|
|
||||||
|
QString APMSensorsComponent::prerequisiteSetup(void) const |
||||||
|
{ |
||||||
|
APMAutoPilotPlugin* plugin = dynamic_cast<APMAutoPilotPlugin*>(_autopilot); |
||||||
|
Q_ASSERT(plugin); |
||||||
|
|
||||||
|
if (!plugin->airframeComponent()->setupComplete()) { |
||||||
|
return plugin->airframeComponent()->name(); |
||||||
|
} |
||||||
|
|
||||||
|
return QString(); |
||||||
|
} |
@ -0,0 +1,56 @@ |
|||||||
|
/*=====================================================================
|
||||||
|
|
||||||
|
QGroundControl Open Source Ground Control Station |
||||||
|
|
||||||
|
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||||
|
|
||||||
|
This file is part of the QGROUNDCONTROL project |
||||||
|
|
||||||
|
QGROUNDCONTROL is free software: you can redistribute it and/or modify |
||||||
|
it under the terms of the GNU General Public License as published by |
||||||
|
the Free Software Foundation, either version 3 of the License, or |
||||||
|
(at your option) any later version. |
||||||
|
|
||||||
|
QGROUNDCONTROL is distributed in the hope that it will be useful, |
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of |
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |
||||||
|
GNU General Public License for more details. |
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License |
||||||
|
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
======================================================================*/ |
||||||
|
|
||||||
|
#ifndef APMSensorsComponent_H |
||||||
|
#define APMSensorsComponent_H |
||||||
|
|
||||||
|
#include "APMComponent.h" |
||||||
|
|
||||||
|
class APMSensorsComponent : public APMComponent |
||||||
|
{ |
||||||
|
Q_OBJECT |
||||||
|
|
||||||
|
public: |
||||||
|
APMSensorsComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL); |
||||||
|
|
||||||
|
// Virtuals from APMComponent
|
||||||
|
virtual QStringList setupCompleteChangedTriggerList(void) const; |
||||||
|
|
||||||
|
// Virtuals from VehicleComponent
|
||||||
|
virtual QString name(void) const; |
||||||
|
virtual QString description(void) const; |
||||||
|
virtual QString iconResource(void) const; |
||||||
|
virtual bool requiresSetup(void) const; |
||||||
|
virtual bool setupComplete(void) const; |
||||||
|
virtual QString setupStateDescription(void) const; |
||||||
|
virtual QUrl setupSource(void) const; |
||||||
|
virtual QStringList paramFilterList(void) const; |
||||||
|
virtual QUrl summaryQmlSource(void) const; |
||||||
|
virtual QString prerequisiteSetup(void) const; |
||||||
|
|
||||||
|
private: |
||||||
|
const QString _name; |
||||||
|
QVariantList _summaryItems; |
||||||
|
}; |
||||||
|
|
||||||
|
#endif |
@ -0,0 +1,565 @@ |
|||||||
|
/*===================================================================== |
||||||
|
|
||||||
|
QGroundControl Open Source Ground Control Station |
||||||
|
|
||||||
|
(c) 2009 - 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> |
||||||
|
|
||||||
|
This file is part of the QGROUNDCONTROL project |
||||||
|
|
||||||
|
QGROUNDCONTROL is free software: you can redistribute it and/or modify |
||||||
|
it under the terms of the GNU General Public License as published by |
||||||
|
the Free Software Foundation, either version 3 of the License, or |
||||||
|
(at your option) any later version. |
||||||
|
|
||||||
|
QGROUNDCONTROL is distributed in the hope that it will be useful, |
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of |
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |
||||||
|
GNU General Public License for more details. |
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License |
||||||
|
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>. |
||||||
|
|
||||||
|
======================================================================*/ |
||||||
|
|
||||||
|
import QtQuick 2.2 |
||||||
|
import QtQuick.Controls 1.2 |
||||||
|
import QtQuick.Controls.Styles 1.2 |
||||||
|
import QtQuick.Dialogs 1.2 |
||||||
|
|
||||||
|
import QGroundControl.FactSystem 1.0 |
||||||
|
import QGroundControl.FactControls 1.0 |
||||||
|
import QGroundControl.Palette 1.0 |
||||||
|
import QGroundControl.Controls 1.0 |
||||||
|
import QGroundControl.ScreenTools 1.0 |
||||||
|
import QGroundControl.Controllers 1.0 |
||||||
|
|
||||||
|
QGCView { |
||||||
|
id: rootQGCView |
||||||
|
viewPanel: panel |
||||||
|
|
||||||
|
// 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 boardRotationText: "If the autopilot is mounted in flight direction, leave the default value (None)" |
||||||
|
readonly property string compassRotationText: "If the compass or GPS module is mounted in flight direction, leave the default value (None)" |
||||||
|
|
||||||
|
readonly property string compassHelp: "For Compass calibration you will need to rotate your vehicle through a number of positions. Most users prefer to do this wirelessly with the telemetry link." |
||||||
|
readonly property string gyroHelp: "For Gyroscope calibration you will need to place your vehicle on a surface and leave it still." |
||||||
|
readonly property string accelHelp: "For Accelerometer calibration you will need to place your vehicle on all six sides on a perfectly level surface and hold it still in each orientation for a few seconds." |
||||||
|
readonly property string levelHelp: "To level the horizon you need to place the vehicle in its level flight position and press OK." |
||||||
|
readonly property string airspeedHelp: "For Airspeed calibration you will need to keep your airspeed sensor out of any wind and then blow across the sensor." |
||||||
|
|
||||||
|
readonly property string statusTextAreaDefaultText: "Start the individual calibration steps by clicking one of the buttons above." |
||||||
|
|
||||||
|
// Used to pass what type of calibration is being performed to the preCalibrationDialog |
||||||
|
property string preCalibrationDialogType |
||||||
|
|
||||||
|
// Used to pass help text to the preCalibrationDialog dialog |
||||||
|
property string preCalibrationDialogHelp |
||||||
|
|
||||||
|
readonly property int sideBarH1PointSize: ScreenTools.mediumFontPixelSize |
||||||
|
readonly property int mainTextH1PointSize: ScreenTools.mediumFontPixelSize // Seems to be unused |
||||||
|
|
||||||
|
readonly property int rotationColumnWidth: 250 |
||||||
|
readonly property var rotations: [ |
||||||
|
"None", |
||||||
|
"Yaw 45", |
||||||
|
"Yaw 90", |
||||||
|
"Yaw 135", |
||||||
|
"Yaw 180", |
||||||
|
"Yaw 225", |
||||||
|
"Yaw 270", |
||||||
|
"Yaw 315", |
||||||
|
"Roll 180", |
||||||
|
"Roll 180. Yaw 45", |
||||||
|
"Roll 180. Yaw 90", |
||||||
|
"Roll 180. Yaw 135", |
||||||
|
"Pitch 180", |
||||||
|
"Roll 180. Yaw 225", |
||||||
|
"Roll 180, Yaw 270", |
||||||
|
"Roll 180, Yaw 315", |
||||||
|
"Roll 90", |
||||||
|
"Roll 90, Yaw 45", |
||||||
|
"Roll 90, Yaw 90", |
||||||
|
"Roll 90, Yaw 135", |
||||||
|
"Roll 270", |
||||||
|
"Roll 270, Yaw 45", |
||||||
|
"Roll 270, Yaw 90", |
||||||
|
"Roll 270, Yaw 136", |
||||||
|
"Pitch 90", |
||||||
|
"Pitch 270", |
||||||
|
"Pitch 180, Yaw 90", |
||||||
|
"Pitch 180, Yaw 270", |
||||||
|
"Roll 90, Pitch 90", |
||||||
|
"Roll 180, Pitch 90", |
||||||
|
"Roll 270, Pitch 90", |
||||||
|
"Roll 90, Pitch 180", |
||||||
|
"Roll 270, Pitch 180", |
||||||
|
"Roll 90, Pitch 270", |
||||||
|
"Roll 180, Pitch 270", |
||||||
|
"Roll 270, Pitch 270", |
||||||
|
"Roll 90, Pitch 180, Yaw 90", |
||||||
|
"Roll 90, Yaw 270", |
||||||
|
"Yaw 293, Pitch 68, Roll 90", |
||||||
|
] |
||||||
|
|
||||||
|
property Fact cal_mag0_id: controller.getParameterFact(-1, "COMPASS_DEV_ID") |
||||||
|
property Fact cal_mag1_id: controller.getParameterFact(-1, "COMPASS_DEV_ID2") |
||||||
|
property Fact cal_mag2_id: controller.getParameterFact(-1, "COMPASS_DEV_ID3") |
||||||
|
property Fact cal_mag0_rot: controller.getParameterFact(-1, "COMPASS_ORIENT") |
||||||
|
property Fact cal_mag1_rot: controller.getParameterFact(-1, "COMPASS_ORIENT2") |
||||||
|
property Fact cal_mag2_rot: controller.getParameterFact(-1, "COMPASS_ORIENT3") |
||||||
|
|
||||||
|
property Fact sens_board_rot: controller.getParameterFact(-1, "AHRS_ORIENTATION") |
||||||
|
|
||||||
|
/* |
||||||
|
property Fact cal_gyro0_id: controller.getParameterFact(-1, "CAL_GYRO0_ID") |
||||||
|
property Fact cal_acc0_id: controller.getParameterFact(-1, "CAL_ACC0_ID") |
||||||
|
|
||||||
|
property Fact sens_board_x_off: controller.getParameterFact(-1, "SENS_BOARD_X_OFF") |
||||||
|
property Fact sens_dpres_off: controller.getParameterFact(-1, "SENS_DPRES_OFF") |
||||||
|
*/ |
||||||
|
|
||||||
|
property Fact ins_accoffs_x: controller.getParameterFact(-1, "INS_ACCOFFS_X") |
||||||
|
property Fact ins_accoffs_y: controller.getParameterFact(-1, "INS_ACCOFFS_Y") |
||||||
|
property Fact ins_accoffs_z: controller.getParameterFact(-1, "INS_ACCOFFS_Z") |
||||||
|
|
||||||
|
property Fact compass_ofs_x: controller.getParameterFact(-1, "COMPASS_OFS_X") |
||||||
|
property Fact compass_ofs_y: controller.getParameterFact(-1, "COMPASS_OFS_Y") |
||||||
|
property Fact compass_ofs_z: controller.getParameterFact(-1, "COMPASS_OFS_Z") |
||||||
|
|
||||||
|
property bool accelCalNeeded: ins_accoffs_x.value == 0 && ins_accoffs_y.value == 0 && ins_accoffs_z.value == 0 |
||||||
|
property bool compassCalNeeded: compass_ofs_x.value == 0 && compass_ofs_y.value == 0 && compass_ofs_y.value == 0 |
||||||
|
|
||||||
|
// Id > = signals compass available, rot < 0 signals internal compass |
||||||
|
property bool showCompass0Rot: cal_mag0_id.value > 0 && cal_mag0_rot.value >= 0 |
||||||
|
property bool showCompass1Rot: cal_mag1_id.value > 0 && cal_mag1_rot.value >= 0 |
||||||
|
property bool showCompass2Rot: cal_mag2_id.value > 0 && cal_mag2_rot.value >= 0 |
||||||
|
|
||||||
|
APMSensorsComponentController { |
||||||
|
id: controller |
||||||
|
factPanel: panel |
||||||
|
statusLog: statusTextArea |
||||||
|
progressBar: progressBar |
||||||
|
compassButton: compassButton |
||||||
|
accelButton: accelButton |
||||||
|
nextButton: nextButton |
||||||
|
cancelButton: cancelButton |
||||||
|
orientationCalAreaHelpText: orientationCalAreaHelpText |
||||||
|
|
||||||
|
onResetStatusTextArea: statusLog.text = statusTextAreaDefaultText |
||||||
|
|
||||||
|
onSetCompassRotations: { |
||||||
|
if (showCompass0Rot || showCompass1Rot || showCompass2Rot) { |
||||||
|
showDialog(compassRotationDialogComponent, "Set Compass Rotation(s)", 50, StandardButton.Ok) |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
onWaitingForCancelChanged: { |
||||||
|
if (controller.waitingForCancel) { |
||||||
|
showMessage("Calibration Cancel", "Waiting for Vehicle to response to Cancel. This may take a few seconds.", 0) |
||||||
|
} else { |
||||||
|
hideDialog() |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
QGCPalette { id: qgcPal; colorGroupEnabled: panel.enabled } |
||||||
|
|
||||||
|
Component { |
||||||
|
id: preCalibrationDialogComponent |
||||||
|
|
||||||
|
QGCViewDialog { |
||||||
|
id: preCalibrationDialog |
||||||
|
|
||||||
|
function accept() { |
||||||
|
if (preCalibrationDialogType == "gyro") { |
||||||
|
controller.calibrateGyro() |
||||||
|
} else if (preCalibrationDialogType == "accel") { |
||||||
|
controller.calibrateAccel() |
||||||
|
} else if (preCalibrationDialogType == "level") { |
||||||
|
controller.calibrateLevel() |
||||||
|
} else if (preCalibrationDialogType == "compass") { |
||||||
|
controller.calibrateCompass() |
||||||
|
} else if (preCalibrationDialogType == "airspeed") { |
||||||
|
controller.calibrateAirspeed() |
||||||
|
} |
||||||
|
preCalibrationDialog.hideDialog() |
||||||
|
} |
||||||
|
|
||||||
|
Column { |
||||||
|
anchors.fill: parent |
||||||
|
spacing: 5 |
||||||
|
|
||||||
|
QGCLabel { |
||||||
|
width: parent.width |
||||||
|
wrapMode: Text.WordWrap |
||||||
|
text: preCalibrationDialogHelp |
||||||
|
} |
||||||
|
|
||||||
|
QGCLabel { |
||||||
|
width: parent.width |
||||||
|
wrapMode: Text.WordWrap |
||||||
|
visible: (preCalibrationDialogType != "airspeed") && (preCalibrationDialogType != "gyro") |
||||||
|
text: boardRotationText |
||||||
|
} |
||||||
|
|
||||||
|
FactComboBox { |
||||||
|
width: rotationColumnWidth |
||||||
|
model: rotations |
||||||
|
visible: preCalibrationDialogType != "airspeed" && (preCalibrationDialogType != "gyro") |
||||||
|
fact: sens_board_rot |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
Component { |
||||||
|
id: compassRotationDialogComponent |
||||||
|
|
||||||
|
QGCViewDialog { |
||||||
|
id: compassRotationDialog |
||||||
|
|
||||||
|
Column { |
||||||
|
anchors.fill: parent |
||||||
|
spacing: ScreenTools.defaultFontPixelHeight |
||||||
|
|
||||||
|
QGCLabel { |
||||||
|
width: parent.width |
||||||
|
wrapMode: Text.WordWrap |
||||||
|
text: compassRotationText |
||||||
|
} |
||||||
|
|
||||||
|
// Compass 0 rotation |
||||||
|
Component { |
||||||
|
id: compass0ComponentLabel |
||||||
|
|
||||||
|
QGCLabel { |
||||||
|
font.pixelSize: sideBarH1PointSize |
||||||
|
text: "External Compass Orientation" |
||||||
|
} |
||||||
|
|
||||||
|
} |
||||||
|
Component { |
||||||
|
id: compass0ComponentCombo |
||||||
|
|
||||||
|
FactComboBox { |
||||||
|
id: compass0RotationCombo |
||||||
|
width: rotationColumnWidth |
||||||
|
model: rotations |
||||||
|
fact: cal_mag0_rot |
||||||
|
} |
||||||
|
} |
||||||
|
Loader { sourceComponent: showCompass0Rot ? compass0ComponentLabel : null } |
||||||
|
Loader { sourceComponent: showCompass0Rot ? compass0ComponentCombo : null } |
||||||
|
// Compass 1 rotation |
||||||
|
Component { |
||||||
|
id: compass1ComponentLabel |
||||||
|
|
||||||
|
QGCLabel { text: "Compass 1 Orientation" } |
||||||
|
} |
||||||
|
Component { |
||||||
|
id: compass1ComponentCombo |
||||||
|
|
||||||
|
FactComboBox { |
||||||
|
id: compass1RotationCombo |
||||||
|
width: rotationColumnWidth |
||||||
|
model: rotations |
||||||
|
fact: cal_mag1_rot |
||||||
|
} |
||||||
|
} |
||||||
|
Loader { sourceComponent: showCompass1Rot ? compass1ComponentLabel : null } |
||||||
|
Loader { sourceComponent: showCompass1Rot ? compass1ComponentCombo : null } |
||||||
|
|
||||||
|
// Compass 2 rotation |
||||||
|
Component { |
||||||
|
id: compass2ComponentLabel |
||||||
|
|
||||||
|
QGCLabel { text: "Compass 2 Orientation" } |
||||||
|
} |
||||||
|
Component { |
||||||
|
id: compass2ComponentCombo |
||||||
|
|
||||||
|
FactComboBox { |
||||||
|
id: compass1RotationCombo |
||||||
|
width: rotationColumnWidth |
||||||
|
model: rotations |
||||||
|
fact: cal_mag2_rot |
||||||
|
} |
||||||
|
} |
||||||
|
Loader { sourceComponent: showCompass2Rot ? compass2ComponentLabel : null } |
||||||
|
Loader { sourceComponent: showCompass2Rot ? compass2ComponentCombo : null } |
||||||
|
} // Column |
||||||
|
} // QGCViewDialog |
||||||
|
} // Component - compassRotationDialogComponent |
||||||
|
|
||||||
|
QGCViewPanel { |
||||||
|
id: panel |
||||||
|
anchors.fill: parent |
||||||
|
|
||||||
|
Column { |
||||||
|
anchors.fill: parent |
||||||
|
|
||||||
|
Row { |
||||||
|
readonly property int buttonWidth: ScreenTools.defaultFontPixelWidth * 15 |
||||||
|
|
||||||
|
spacing: ScreenTools.defaultFontPixelWidth |
||||||
|
|
||||||
|
QGCLabel { text: "Calibrate:"; anchors.baseline: compassButton.baseline } |
||||||
|
|
||||||
|
IndicatorButton { |
||||||
|
id: compassButton |
||||||
|
width: parent.buttonWidth |
||||||
|
text: "Compass - NYI" |
||||||
|
indicatorGreen: !compassCalNeeded |
||||||
|
|
||||||
|
onClicked: { |
||||||
|
preCalibrationDialogType = "compass" |
||||||
|
preCalibrationDialogHelp = compassHelp |
||||||
|
showDialog(preCalibrationDialogComponent, "Calibrate Compass", 50, StandardButton.Cancel | StandardButton.Ok) |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
IndicatorButton { |
||||||
|
id: accelButton |
||||||
|
width: parent.buttonWidth |
||||||
|
text: "Accelerometer" |
||||||
|
indicatorGreen: !accelCalNeeded |
||||||
|
|
||||||
|
onClicked: { |
||||||
|
preCalibrationDialogType = "accel" |
||||||
|
preCalibrationDialogHelp = accelHelp |
||||||
|
showDialog(preCalibrationDialogComponent, "Calibrate Accelerometer", 50, StandardButton.Cancel | StandardButton.Ok) |
||||||
|
} |
||||||
|
} |
||||||
|
QGCButton { |
||||||
|
id: nextButton |
||||||
|
showBorder: true |
||||||
|
text: "Next" |
||||||
|
enabled: false |
||||||
|
onClicked: controller.nextClicked() |
||||||
|
} |
||||||
|
|
||||||
|
QGCButton { |
||||||
|
id: cancelButton |
||||||
|
showBorder: true |
||||||
|
text: "Cancel" |
||||||
|
enabled: false |
||||||
|
onClicked: controller.cancelCalibration() |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
Item { height: ScreenTools.defaultFontPixelHeight; width: 10 } // spacer |
||||||
|
|
||||||
|
ProgressBar { |
||||||
|
id: progressBar |
||||||
|
width: parent.width - rotationColumnWidth |
||||||
|
} |
||||||
|
|
||||||
|
Item { height: ScreenTools.defaultFontPixelHeight; width: 10 } // spacer |
||||||
|
|
||||||
|
Item { |
||||||
|
property int calDisplayAreaWidth: parent.width - rotationColumnWidth |
||||||
|
|
||||||
|
width: parent.width |
||||||
|
height: parent.height - y |
||||||
|
|
||||||
|
TextArea { |
||||||
|
id: statusTextArea |
||||||
|
width: parent.calDisplayAreaWidth |
||||||
|
height: parent.height |
||||||
|
readOnly: true |
||||||
|
frameVisible: false |
||||||
|
text: statusTextAreaDefaultText |
||||||
|
|
||||||
|
style: TextAreaStyle { |
||||||
|
textColor: qgcPal.text |
||||||
|
backgroundColor: qgcPal.windowShade |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
Rectangle { |
||||||
|
id: orientationCalArea |
||||||
|
width: parent.calDisplayAreaWidth |
||||||
|
height: parent.height |
||||||
|
visible: controller.showOrientationCalArea |
||||||
|
color: qgcPal.windowShade |
||||||
|
|
||||||
|
QGCLabel { |
||||||
|
id: orientationCalAreaHelpText |
||||||
|
anchors.margins: ScreenTools.defaultFontPixelWidth |
||||||
|
anchors.top: orientationCalArea.top |
||||||
|
anchors.left: orientationCalArea.left |
||||||
|
width: parent.width |
||||||
|
wrapMode: Text.WordWrap |
||||||
|
font.pixelSize: ScreenTools.mediumFontPixelSize |
||||||
|
} |
||||||
|
|
||||||
|
Flow { |
||||||
|
anchors.topMargin: ScreenTools.defaultFontPixelWidth |
||||||
|
anchors.top: orientationCalAreaHelpText.bottom |
||||||
|
anchors.left: orientationCalAreaHelpText.left |
||||||
|
width: parent.width |
||||||
|
height: parent.height - orientationCalAreaHelpText.implicitHeight |
||||||
|
spacing: ScreenTools.defaultFontPixelWidth |
||||||
|
|
||||||
|
VehicleRotationCal { |
||||||
|
visible: controller.orientationCalDownSideVisible |
||||||
|
calValid: controller.orientationCalDownSideDone |
||||||
|
calInProgress: controller.orientationCalDownSideInProgress |
||||||
|
calInProgressText: controller.orientationCalDownSideRotate ? "Rotate" : "Hold Still" |
||||||
|
imageSource: controller.orientationCalDownSideRotate ? "qrc:///qmlimages/VehicleDownRotate.png" : "qrc:///qmlimages/VehicleDown.png" |
||||||
|
} |
||||||
|
VehicleRotationCal { |
||||||
|
visible: controller.orientationCalUpsideDownSideVisible |
||||||
|
calValid: controller.orientationCalUpsideDownSideDone |
||||||
|
calInProgress: controller.orientationCalUpsideDownSideInProgress |
||||||
|
calInProgressText: controller.orientationCalUpsideDownSideRotate ? "Rotate" : "Hold Still" |
||||||
|
imageSource: "qrc:///qmlimages/VehicleUpsideDown.png" |
||||||
|
} |
||||||
|
VehicleRotationCal { |
||||||
|
visible: controller.orientationCalNoseDownSideVisible |
||||||
|
calValid: controller.orientationCalNoseDownSideDone |
||||||
|
calInProgress: controller.orientationCalNoseDownSideInProgress |
||||||
|
calInProgressText: controller.orientationCalNoseDownSideRotate ? "Rotate" : "Hold Still" |
||||||
|
imageSource: controller.orientationCalNoseDownSideRotate ? "qrc:///qmlimages/VehicleNoseDownRotate.png" : "qrc:///qmlimages/VehicleNoseDown.png" |
||||||
|
} |
||||||
|
VehicleRotationCal { |
||||||
|
visible: controller.orientationCalTailDownSideVisible |
||||||
|
calValid: controller.orientationCalTailDownSideDone |
||||||
|
calInProgress: controller.orientationCalTailDownSideInProgress |
||||||
|
calInProgressText: controller.orientationCalTailDownSideRotate ? "Rotate" : "Hold Still" |
||||||
|
imageSource: "qrc:///qmlimages/VehicleTailDown.png" |
||||||
|
} |
||||||
|
VehicleRotationCal { |
||||||
|
visible: controller.orientationCalLeftSideVisible |
||||||
|
calValid: controller.orientationCalLeftSideDone |
||||||
|
calInProgress: controller.orientationCalLeftSideInProgress |
||||||
|
calInProgressText: controller.orientationCalLeftSideRotate ? "Rotate" : "Hold Still" |
||||||
|
imageSource: controller.orientationCalLeftSideRotate ? "qrc:///qmlimages/VehicleLeftRotate.png" : "qrc:///qmlimages/VehicleLeft.png" |
||||||
|
} |
||||||
|
VehicleRotationCal { |
||||||
|
visible: controller.orientationCalRightSideVisible |
||||||
|
calValid: controller.orientationCalRightSideDone |
||||||
|
calInProgress: controller.orientationCalRightSideInProgress |
||||||
|
calInProgressText: controller.orientationCalRightSideRotate ? "Rotate" : "Hold Still" |
||||||
|
imageSource: "qrc:///qmlimages/VehicleRight.png" |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
Column { |
||||||
|
anchors.leftMargin: ScreenTools.defaultFontPixelWidth |
||||||
|
anchors.left: orientationCalArea.right |
||||||
|
x: parent.width - rotationColumnWidth |
||||||
|
spacing: ScreenTools.defaultFontPixelWidth |
||||||
|
|
||||||
|
Column { |
||||||
|
spacing: ScreenTools.defaultFontPixelWidth |
||||||
|
|
||||||
|
QGCLabel { |
||||||
|
font.pixelSize: sideBarH1PointSize |
||||||
|
text: "Autopilot Orientation" |
||||||
|
} |
||||||
|
|
||||||
|
QGCLabel { |
||||||
|
width: parent.width |
||||||
|
wrapMode: Text.WordWrap |
||||||
|
text: boardRotationText |
||||||
|
} |
||||||
|
|
||||||
|
FactComboBox { |
||||||
|
id: boardRotationCombo |
||||||
|
width: rotationColumnWidth; |
||||||
|
model: rotations |
||||||
|
fact: sens_board_rot |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
Column { |
||||||
|
spacing: ScreenTools.defaultFontPixelWidth |
||||||
|
|
||||||
|
// Compass 0 rotation |
||||||
|
Component { |
||||||
|
id: compass0ComponentLabel2 |
||||||
|
|
||||||
|
QGCLabel { |
||||||
|
font.pixelSize: sideBarH1PointSize |
||||||
|
text: "External Compass Orientation" |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
Component { |
||||||
|
id: compass0ComponentCombo2 |
||||||
|
|
||||||
|
FactComboBox { |
||||||
|
id: compass0RotationCombo |
||||||
|
width: rotationColumnWidth |
||||||
|
model: rotations |
||||||
|
fact: cal_mag0_rot |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
Loader { sourceComponent: showCompass0Rot ? compass0ComponentLabel2 : null } |
||||||
|
Loader { sourceComponent: showCompass0Rot ? compass0ComponentCombo2 : null } |
||||||
|
} |
||||||
|
|
||||||
|
Column { |
||||||
|
spacing: ScreenTools.defaultFontPixelWidth |
||||||
|
|
||||||
|
// Compass 1 rotation |
||||||
|
Component { |
||||||
|
id: compass1ComponentLabel2 |
||||||
|
|
||||||
|
QGCLabel { |
||||||
|
font.pixelSize: sideBarH1PointSize |
||||||
|
text: "External Compass 1 Orientation" |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
Component { |
||||||
|
id: compass1ComponentCombo2 |
||||||
|
|
||||||
|
FactComboBox { |
||||||
|
id: compass1RotationCombo |
||||||
|
width: rotationColumnWidth |
||||||
|
model: rotations |
||||||
|
fact: cal_mag1_rot |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
Loader { sourceComponent: showCompass1Rot ? compass1ComponentLabel2 : null } |
||||||
|
Loader { sourceComponent: showCompass1Rot ? compass1ComponentCombo2 : null } |
||||||
|
} |
||||||
|
|
||||||
|
Column { |
||||||
|
spacing: ScreenTools.defaultFontPixelWidth |
||||||
|
|
||||||
|
// Compass 2 rotation |
||||||
|
Component { |
||||||
|
id: compass2ComponentLabel2 |
||||||
|
|
||||||
|
QGCLabel { |
||||||
|
font.pixelSize: sidebarH1PointSize |
||||||
|
text: "Compass 2 Orientation" |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
Component { |
||||||
|
id: compass2ComponentCombo2 |
||||||
|
|
||||||
|
FactComboBox { |
||||||
|
id: compass1RotationCombo |
||||||
|
width: rotationColumnWidth |
||||||
|
model: rotations |
||||||
|
fact: cal_mag2_rot |
||||||
|
} |
||||||
|
} |
||||||
|
Loader { sourceComponent: showCompass2Rot ? compass2ComponentLabel2 : null } |
||||||
|
Loader { sourceComponent: showCompass2Rot ? compass2ComponentCombo2 : null } |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
} // QGCViewPanel |
||||||
|
} // QGCView |
@ -0,0 +1,469 @@ |
|||||||
|
/*=====================================================================
|
||||||
|
|
||||||
|
QGroundControl Open Source Ground Control Station |
||||||
|
|
||||||
|
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||||
|
|
||||||
|
This file is part of the QGROUNDCONTROL project |
||||||
|
|
||||||
|
QGROUNDCONTROL is free software: you can redistribute it and/or modify |
||||||
|
it under the terms of the GNU General Public License as published by |
||||||
|
the Free Software Foundation, either version 3 of the License, or |
||||||
|
(at your option) any later version. |
||||||
|
|
||||||
|
QGROUNDCONTROL is distributed in the hope that it will be useful, |
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of |
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |
||||||
|
GNU General Public License for more details. |
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License |
||||||
|
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
======================================================================*/ |
||||||
|
|
||||||
|
#include "APMSensorsComponentController.h" |
||||||
|
#include "QGCMAVLink.h" |
||||||
|
#include "UAS.h" |
||||||
|
#include "QGCApplication.h" |
||||||
|
|
||||||
|
#include <QVariant> |
||||||
|
#include <QQmlProperty> |
||||||
|
|
||||||
|
QGC_LOGGING_CATEGORY(APMSensorsComponentControllerLog, "APMSensorsComponentControllerLog") |
||||||
|
|
||||||
|
APMSensorsComponentController::APMSensorsComponentController(void) : |
||||||
|
_statusLog(NULL), |
||||||
|
_progressBar(NULL), |
||||||
|
_compassButton(NULL), |
||||||
|
_accelButton(NULL), |
||||||
|
_nextButton(NULL), |
||||||
|
_cancelButton(NULL), |
||||||
|
_showOrientationCalArea(false), |
||||||
|
_gyroCalInProgress(false), |
||||||
|
_magCalInProgress(false), |
||||||
|
_accelCalInProgress(false), |
||||||
|
_orientationCalDownSideDone(false), |
||||||
|
_orientationCalUpsideDownSideDone(false), |
||||||
|
_orientationCalLeftSideDone(false), |
||||||
|
_orientationCalRightSideDone(false), |
||||||
|
_orientationCalNoseDownSideDone(false), |
||||||
|
_orientationCalTailDownSideDone(false), |
||||||
|
_orientationCalDownSideVisible(false), |
||||||
|
_orientationCalUpsideDownSideVisible(false), |
||||||
|
_orientationCalLeftSideVisible(false), |
||||||
|
_orientationCalRightSideVisible(false), |
||||||
|
_orientationCalNoseDownSideVisible(false), |
||||||
|
_orientationCalTailDownSideVisible(false), |
||||||
|
_orientationCalDownSideInProgress(false), |
||||||
|
_orientationCalUpsideDownSideInProgress(false), |
||||||
|
_orientationCalLeftSideInProgress(false), |
||||||
|
_orientationCalRightSideInProgress(false), |
||||||
|
_orientationCalNoseDownSideInProgress(false), |
||||||
|
_orientationCalTailDownSideInProgress(false), |
||||||
|
_orientationCalDownSideRotate(false), |
||||||
|
_orientationCalUpsideDownSideRotate(false), |
||||||
|
_orientationCalLeftSideRotate(false), |
||||||
|
_orientationCalRightSideRotate(false), |
||||||
|
_orientationCalNoseDownSideRotate(false), |
||||||
|
_orientationCalTailDownSideRotate(false), |
||||||
|
_waitingForCancel(false) |
||||||
|
{ |
||||||
|
|
||||||
|
} |
||||||
|
|
||||||
|
/// Appends the specified text to the status log area in the ui
|
||||||
|
void APMSensorsComponentController::_appendStatusLog(const QString& text) |
||||||
|
{ |
||||||
|
Q_ASSERT(_statusLog); |
||||||
|
|
||||||
|
QVariant returnedValue; |
||||||
|
QVariant varText = text; |
||||||
|
QMetaObject::invokeMethod(_statusLog, |
||||||
|
"append", |
||||||
|
Q_RETURN_ARG(QVariant, returnedValue), |
||||||
|
Q_ARG(QVariant, varText)); |
||||||
|
} |
||||||
|
|
||||||
|
void APMSensorsComponentController::_startLogCalibration(void) |
||||||
|
{ |
||||||
|
_hideAllCalAreas(); |
||||||
|
|
||||||
|
connect(_uas, &UASInterface::textMessageReceived, this, &APMSensorsComponentController::_handleUASTextMessage); |
||||||
|
|
||||||
|
_compassButton->setEnabled(false); |
||||||
|
_accelButton->setEnabled(false); |
||||||
|
_nextButton->setEnabled(true); |
||||||
|
_cancelButton->setEnabled(false); |
||||||
|
} |
||||||
|
|
||||||
|
void APMSensorsComponentController::_startVisualCalibration(void) |
||||||
|
{ |
||||||
|
_compassButton->setEnabled(false); |
||||||
|
_accelButton->setEnabled(false); |
||||||
|
_cancelButton->setEnabled(true); |
||||||
|
|
||||||
|
_resetInternalState(); |
||||||
|
|
||||||
|
_progressBar->setProperty("value", 0); |
||||||
|
} |
||||||
|
|
||||||
|
void APMSensorsComponentController::_resetInternalState(void) |
||||||
|
{ |
||||||
|
_orientationCalDownSideDone = true; |
||||||
|
_orientationCalUpsideDownSideDone = true; |
||||||
|
_orientationCalLeftSideDone = true; |
||||||
|
_orientationCalRightSideDone = true; |
||||||
|
_orientationCalTailDownSideDone = true; |
||||||
|
_orientationCalNoseDownSideDone = true; |
||||||
|
_orientationCalDownSideInProgress = false; |
||||||
|
_orientationCalUpsideDownSideInProgress = false; |
||||||
|
_orientationCalLeftSideInProgress = false; |
||||||
|
_orientationCalRightSideInProgress = false; |
||||||
|
_orientationCalNoseDownSideInProgress = false; |
||||||
|
_orientationCalTailDownSideInProgress = false; |
||||||
|
_orientationCalDownSideRotate = false; |
||||||
|
_orientationCalUpsideDownSideRotate = false; |
||||||
|
_orientationCalLeftSideRotate = false; |
||||||
|
_orientationCalRightSideRotate = false; |
||||||
|
_orientationCalNoseDownSideRotate = false; |
||||||
|
_orientationCalTailDownSideRotate = false; |
||||||
|
|
||||||
|
emit orientationCalSidesRotateChanged(); |
||||||
|
emit orientationCalSidesDoneChanged(); |
||||||
|
emit orientationCalSidesInProgressChanged(); |
||||||
|
} |
||||||
|
|
||||||
|
void APMSensorsComponentController::_stopCalibration(APMSensorsComponentController::StopCalibrationCode code) |
||||||
|
{ |
||||||
|
disconnect(_uas, &UASInterface::textMessageReceived, this, &APMSensorsComponentController::_handleUASTextMessage); |
||||||
|
|
||||||
|
_compassButton->setEnabled(true); |
||||||
|
_accelButton->setEnabled(true); |
||||||
|
_nextButton->setEnabled(false); |
||||||
|
_cancelButton->setEnabled(false); |
||||||
|
|
||||||
|
if (code == StopCalibrationSuccess) { |
||||||
|
_resetInternalState(); |
||||||
|
_progressBar->setProperty("value", 1); |
||||||
|
} else { |
||||||
|
_progressBar->setProperty("value", 0); |
||||||
|
} |
||||||
|
|
||||||
|
_waitingForCancel = false; |
||||||
|
emit waitingForCancelChanged(); |
||||||
|
|
||||||
|
_refreshParams(); |
||||||
|
|
||||||
|
switch (code) { |
||||||
|
case StopCalibrationSuccess: |
||||||
|
_orientationCalAreaHelpText->setProperty("text", "Calibration complete"); |
||||||
|
emit resetStatusTextArea(); |
||||||
|
if (_magCalInProgress) { |
||||||
|
emit setCompassRotations(); |
||||||
|
} |
||||||
|
break; |
||||||
|
|
||||||
|
case StopCalibrationCancelled: |
||||||
|
emit resetStatusTextArea(); |
||||||
|
_hideAllCalAreas(); |
||||||
|
break; |
||||||
|
|
||||||
|
default: |
||||||
|
// Assume failed
|
||||||
|
_hideAllCalAreas(); |
||||||
|
qgcApp()->showMessage("Calibration failed. Calibration log will be displayed."); |
||||||
|
break; |
||||||
|
} |
||||||
|
|
||||||
|
_magCalInProgress = false; |
||||||
|
_accelCalInProgress = false; |
||||||
|
_gyroCalInProgress = false; |
||||||
|
} |
||||||
|
|
||||||
|
void APMSensorsComponentController::calibrateGyro(void) |
||||||
|
{ |
||||||
|
_startLogCalibration(); |
||||||
|
_uas->startCalibration(UASInterface::StartCalibrationGyro); |
||||||
|
} |
||||||
|
|
||||||
|
void APMSensorsComponentController::calibrateCompass(void) |
||||||
|
{ |
||||||
|
_startLogCalibration(); |
||||||
|
_uas->startCalibration(UASInterface::StartCalibrationMag); |
||||||
|
} |
||||||
|
|
||||||
|
void APMSensorsComponentController::calibrateAccel(void) |
||||||
|
{ |
||||||
|
_startLogCalibration(); |
||||||
|
_uas->startCalibration(UASInterface::StartCalibrationAccel); |
||||||
|
} |
||||||
|
|
||||||
|
void APMSensorsComponentController::calibrateLevel(void) |
||||||
|
{ |
||||||
|
_startLogCalibration(); |
||||||
|
_uas->startCalibration(UASInterface::StartCalibrationLevel); |
||||||
|
} |
||||||
|
|
||||||
|
void APMSensorsComponentController::calibrateAirspeed(void) |
||||||
|
{ |
||||||
|
_startLogCalibration(); |
||||||
|
_uas->startCalibration(UASInterface::StartCalibrationAirspeed); |
||||||
|
} |
||||||
|
|
||||||
|
void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId, int severity, QString text) |
||||||
|
{ |
||||||
|
Q_UNUSED(compId); |
||||||
|
Q_UNUSED(severity); |
||||||
|
|
||||||
|
UASInterface* uas = _autopilot->vehicle()->uas(); |
||||||
|
Q_ASSERT(uas); |
||||||
|
if (uasId != uas->getUASID()) { |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
if (text.startsWith("PreArm:") || text.startsWith("EKF") || text.startsWith("Arm") || text.startsWith("Initialising")) { |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
QString anyKey("and press any"); |
||||||
|
if (text.contains(anyKey)) { |
||||||
|
text = text.left(text.indexOf(anyKey)) + "and click Next to continue."; |
||||||
|
} |
||||||
|
|
||||||
|
_appendStatusLog(text); |
||||||
|
qCDebug(APMSensorsComponentControllerLog) << text << severity; |
||||||
|
|
||||||
|
if (text.contains("Calibration successful")) { |
||||||
|
_stopCalibration(StopCalibrationSuccess); |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
if (text.contains("FAILED")) { |
||||||
|
_stopCalibration(StopCalibrationFailed); |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
/*
|
||||||
|
// All calibration messages start with [cal]
|
||||||
|
QString calPrefix("[cal] "); |
||||||
|
if (!text.startsWith(calPrefix)) { |
||||||
|
return; |
||||||
|
} |
||||||
|
text = text.right(text.length() - calPrefix.length()); |
||||||
|
|
||||||
|
QString calStartPrefix("calibration started: "); |
||||||
|
if (text.startsWith(calStartPrefix)) { |
||||||
|
text = text.right(text.length() - calStartPrefix.length()); |
||||||
|
|
||||||
|
_startVisualCalibration(); |
||||||
|
|
||||||
|
text = parts[1]; |
||||||
|
if (text == "accel" || text == "mag" || text == "gyro") { |
||||||
|
// Reset all progress indication
|
||||||
|
_orientationCalDownSideDone = false; |
||||||
|
_orientationCalUpsideDownSideDone = false; |
||||||
|
_orientationCalLeftSideDone = false; |
||||||
|
_orientationCalRightSideDone = false; |
||||||
|
_orientationCalTailDownSideDone = false; |
||||||
|
_orientationCalNoseDownSideDone = false; |
||||||
|
_orientationCalDownSideInProgress = false; |
||||||
|
_orientationCalUpsideDownSideInProgress = false; |
||||||
|
_orientationCalLeftSideInProgress = false; |
||||||
|
_orientationCalRightSideInProgress = false; |
||||||
|
_orientationCalNoseDownSideInProgress = false; |
||||||
|
_orientationCalTailDownSideInProgress = false; |
||||||
|
|
||||||
|
// Reset all visibility
|
||||||
|
_orientationCalDownSideVisible = false; |
||||||
|
_orientationCalUpsideDownSideVisible = false; |
||||||
|
_orientationCalLeftSideVisible = false; |
||||||
|
_orientationCalRightSideVisible = false; |
||||||
|
_orientationCalTailDownSideVisible = false; |
||||||
|
_orientationCalNoseDownSideVisible = false; |
||||||
|
|
||||||
|
_orientationCalAreaHelpText->setProperty("text", "Place your vehicle into one of the Incomplete orientations shown below and hold it still"); |
||||||
|
|
||||||
|
if (text == "accel") { |
||||||
|
_accelCalInProgress = true; |
||||||
|
_orientationCalDownSideVisible = true; |
||||||
|
_orientationCalUpsideDownSideVisible = true; |
||||||
|
_orientationCalLeftSideVisible = true; |
||||||
|
_orientationCalRightSideVisible = true; |
||||||
|
_orientationCalTailDownSideVisible = true; |
||||||
|
_orientationCalNoseDownSideVisible = true; |
||||||
|
} else if (text == "mag") { |
||||||
|
_magCalInProgress = true; |
||||||
|
_orientationCalDownSideVisible = true; |
||||||
|
_orientationCalUpsideDownSideVisible = true; |
||||||
|
_orientationCalLeftSideVisible = true; |
||||||
|
_orientationCalRightSideVisible = true; |
||||||
|
_orientationCalTailDownSideVisible = true; |
||||||
|
_orientationCalNoseDownSideVisible = true; |
||||||
|
} else if (text == "gyro") { |
||||||
|
_gyroCalInProgress = true; |
||||||
|
_orientationCalDownSideVisible = true; |
||||||
|
} else { |
||||||
|
Q_ASSERT(false); |
||||||
|
} |
||||||
|
emit orientationCalSidesDoneChanged(); |
||||||
|
emit orientationCalSidesVisibleChanged(); |
||||||
|
emit orientationCalSidesInProgressChanged(); |
||||||
|
_updateAndEmitShowOrientationCalArea(true); |
||||||
|
} |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
if (text.endsWith("orientation detected")) { |
||||||
|
QString side = text.section(" ", 0, 0); |
||||||
|
qDebug() << "Side started" << side; |
||||||
|
|
||||||
|
if (side == "down") { |
||||||
|
_orientationCalDownSideInProgress = true; |
||||||
|
if (_magCalInProgress) { |
||||||
|
_orientationCalDownSideRotate = true; |
||||||
|
} |
||||||
|
} else if (side == "up") { |
||||||
|
_orientationCalUpsideDownSideInProgress = true; |
||||||
|
if (_magCalInProgress) { |
||||||
|
_orientationCalUpsideDownSideRotate = true; |
||||||
|
} |
||||||
|
} else if (side == "left") { |
||||||
|
_orientationCalLeftSideInProgress = true; |
||||||
|
if (_magCalInProgress) { |
||||||
|
_orientationCalLeftSideRotate = true; |
||||||
|
} |
||||||
|
} else if (side == "right") { |
||||||
|
_orientationCalRightSideInProgress = true; |
||||||
|
if (_magCalInProgress) { |
||||||
|
_orientationCalRightSideRotate = true; |
||||||
|
} |
||||||
|
} else if (side == "front") { |
||||||
|
_orientationCalNoseDownSideInProgress = true; |
||||||
|
if (_magCalInProgress) { |
||||||
|
_orientationCalNoseDownSideRotate = true; |
||||||
|
} |
||||||
|
} else if (side == "back") { |
||||||
|
_orientationCalTailDownSideInProgress = true; |
||||||
|
if (_magCalInProgress) { |
||||||
|
_orientationCalTailDownSideRotate = true; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
if (_magCalInProgress) { |
||||||
|
_orientationCalAreaHelpText->setProperty("text", "Rotate the vehicle continuously as shown in the diagram until marked as Completed"); |
||||||
|
} else { |
||||||
|
_orientationCalAreaHelpText->setProperty("text", "Hold still in the current orientation"); |
||||||
|
} |
||||||
|
|
||||||
|
emit orientationCalSidesInProgressChanged(); |
||||||
|
emit orientationCalSidesRotateChanged(); |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
if (text.endsWith("side done, rotate to a different side")) { |
||||||
|
QString side = text.section(" ", 0, 0); |
||||||
|
qDebug() << "Side finished" << side; |
||||||
|
|
||||||
|
if (side == "down") { |
||||||
|
_orientationCalDownSideInProgress = false; |
||||||
|
_orientationCalDownSideDone = true; |
||||||
|
_orientationCalDownSideRotate = false; |
||||||
|
} else if (side == "up") { |
||||||
|
_orientationCalUpsideDownSideInProgress = false; |
||||||
|
_orientationCalUpsideDownSideDone = true; |
||||||
|
} else if (side == "left") { |
||||||
|
_orientationCalLeftSideInProgress = false; |
||||||
|
_orientationCalLeftSideDone = true; |
||||||
|
_orientationCalLeftSideRotate = false; |
||||||
|
} else if (side == "right") { |
||||||
|
_orientationCalRightSideInProgress = false; |
||||||
|
_orientationCalRightSideDone = true; |
||||||
|
} else if (side == "front") { |
||||||
|
_orientationCalNoseDownSideInProgress = false; |
||||||
|
_orientationCalNoseDownSideDone = true; |
||||||
|
_orientationCalNoseDownSideRotate = false; |
||||||
|
} else if (side == "back") { |
||||||
|
_orientationCalTailDownSideInProgress = false; |
||||||
|
_orientationCalTailDownSideDone = true; |
||||||
|
} |
||||||
|
|
||||||
|
_orientationCalAreaHelpText->setProperty("text", "Place you vehicle into one of the orientations shown below and hold it still"); |
||||||
|
|
||||||
|
emit orientationCalSidesInProgressChanged(); |
||||||
|
emit orientationCalSidesDoneChanged(); |
||||||
|
emit orientationCalSidesRotateChanged(); |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
if (text.startsWith("calibration cancelled")) { |
||||||
|
_stopCalibration(_waitingForCancel ? StopCalibrationCancelled : StopCalibrationFailed); |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
*/ |
||||||
|
} |
||||||
|
|
||||||
|
void APMSensorsComponentController::_refreshParams(void) |
||||||
|
{ |
||||||
|
QStringList fastRefreshList; |
||||||
|
|
||||||
|
fastRefreshList << "COMPASS_OFS_X" << "COMPASS_OFS_X" << "COMPASS_OFS_X" |
||||||
|
<< "INS_ACCOFFS_X" << "INS_ACCOFFS_Y" << "INS_ACCOFFS_Z"; |
||||||
|
foreach (QString paramName, fastRefreshList) { |
||||||
|
_autopilot->refreshParameter(FactSystem::defaultComponentId, paramName); |
||||||
|
} |
||||||
|
|
||||||
|
// Now ask for all to refresh
|
||||||
|
_autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, "COMPASS_"); |
||||||
|
_autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, "INS_"); |
||||||
|
} |
||||||
|
|
||||||
|
bool APMSensorsComponentController::fixedWing(void) |
||||||
|
{ |
||||||
|
switch (_vehicle->vehicleType()) { |
||||||
|
case MAV_TYPE_FIXED_WING: |
||||||
|
case MAV_TYPE_VTOL_DUOROTOR: |
||||||
|
case MAV_TYPE_VTOL_QUADROTOR: |
||||||
|
case MAV_TYPE_VTOL_TILTROTOR: |
||||||
|
case MAV_TYPE_VTOL_RESERVED2: |
||||||
|
case MAV_TYPE_VTOL_RESERVED3: |
||||||
|
case MAV_TYPE_VTOL_RESERVED4: |
||||||
|
case MAV_TYPE_VTOL_RESERVED5: |
||||||
|
return true; |
||||||
|
default: |
||||||
|
return false; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void APMSensorsComponentController::_updateAndEmitShowOrientationCalArea(bool show) |
||||||
|
{ |
||||||
|
_showOrientationCalArea = show; |
||||||
|
emit showOrientationCalAreaChanged(); |
||||||
|
} |
||||||
|
|
||||||
|
void APMSensorsComponentController::_hideAllCalAreas(void) |
||||||
|
{ |
||||||
|
_updateAndEmitShowOrientationCalArea(false); |
||||||
|
} |
||||||
|
|
||||||
|
void APMSensorsComponentController::cancelCalibration(void) |
||||||
|
{ |
||||||
|
// The firmware doesn't allow us to cancel calibration. The best we can do is wait
|
||||||
|
// for it to timeout.
|
||||||
|
_waitingForCancel = true; |
||||||
|
emit waitingForCancelChanged(); |
||||||
|
_cancelButton->setEnabled(false); |
||||||
|
_uas->stopCalibration(); |
||||||
|
} |
||||||
|
|
||||||
|
void APMSensorsComponentController::nextClicked(void) |
||||||
|
{ |
||||||
|
mavlink_message_t msg; |
||||||
|
mavlink_command_ack_t ack; |
||||||
|
|
||||||
|
ack.command = 0; |
||||||
|
ack.result = 1; |
||||||
|
mavlink_msg_command_ack_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &msg, &ack); |
||||||
|
|
||||||
|
_vehicle->sendMessage(msg); |
||||||
|
} |
@ -0,0 +1,175 @@ |
|||||||
|
/*=====================================================================
|
||||||
|
|
||||||
|
QGroundControl Open Source Ground Control Station |
||||||
|
|
||||||
|
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||||
|
|
||||||
|
This file is part of the QGROUNDCONTROL project |
||||||
|
|
||||||
|
QGROUNDCONTROL is free software: you can redistribute it and/or modify |
||||||
|
it under the terms of the GNU General Public License as published by |
||||||
|
the Free Software Foundation, either version 3 of the License, or |
||||||
|
(at your option) any later version. |
||||||
|
|
||||||
|
QGROUNDCONTROL is distributed in the hope that it will be useful, |
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of |
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |
||||||
|
GNU General Public License for more details. |
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License |
||||||
|
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
======================================================================*/ |
||||||
|
|
||||||
|
#ifndef APMSensorsComponentController_H |
||||||
|
#define APMSensorsComponentController_H |
||||||
|
|
||||||
|
#include <QObject> |
||||||
|
|
||||||
|
#include "UASInterface.h" |
||||||
|
#include "FactPanelController.h" |
||||||
|
#include "QGCLoggingCategory.h" |
||||||
|
|
||||||
|
Q_DECLARE_LOGGING_CATEGORY(APMSensorsComponentControllerLog) |
||||||
|
|
||||||
|
/// Sensors Component MVC Controller for SensorsComponent.qml.
|
||||||
|
class APMSensorsComponentController : public FactPanelController |
||||||
|
{ |
||||||
|
Q_OBJECT |
||||||
|
|
||||||
|
public: |
||||||
|
APMSensorsComponentController(void); |
||||||
|
|
||||||
|
Q_PROPERTY(bool fixedWing READ fixedWing CONSTANT) |
||||||
|
|
||||||
|
Q_PROPERTY(QQuickItem* statusLog MEMBER _statusLog) |
||||||
|
Q_PROPERTY(QQuickItem* progressBar MEMBER _progressBar) |
||||||
|
|
||||||
|
Q_PROPERTY(QQuickItem* compassButton MEMBER _compassButton) |
||||||
|
Q_PROPERTY(QQuickItem* accelButton MEMBER _accelButton) |
||||||
|
Q_PROPERTY(QQuickItem* nextButton MEMBER _nextButton) |
||||||
|
Q_PROPERTY(QQuickItem* cancelButton MEMBER _cancelButton) |
||||||
|
Q_PROPERTY(QQuickItem* orientationCalAreaHelpText MEMBER _orientationCalAreaHelpText) |
||||||
|
|
||||||
|
Q_PROPERTY(bool showOrientationCalArea MEMBER _showOrientationCalArea NOTIFY showOrientationCalAreaChanged) |
||||||
|
|
||||||
|
Q_PROPERTY(bool orientationCalDownSideDone MEMBER _orientationCalDownSideDone NOTIFY orientationCalSidesDoneChanged) |
||||||
|
Q_PROPERTY(bool orientationCalUpsideDownSideDone MEMBER _orientationCalUpsideDownSideDone NOTIFY orientationCalSidesDoneChanged) |
||||||
|
Q_PROPERTY(bool orientationCalLeftSideDone MEMBER _orientationCalLeftSideDone NOTIFY orientationCalSidesDoneChanged) |
||||||
|
Q_PROPERTY(bool orientationCalRightSideDone MEMBER _orientationCalRightSideDone NOTIFY orientationCalSidesDoneChanged) |
||||||
|
Q_PROPERTY(bool orientationCalNoseDownSideDone MEMBER _orientationCalNoseDownSideDone NOTIFY orientationCalSidesDoneChanged) |
||||||
|
Q_PROPERTY(bool orientationCalTailDownSideDone MEMBER _orientationCalTailDownSideDone NOTIFY orientationCalSidesDoneChanged) |
||||||
|
|
||||||
|
Q_PROPERTY(bool orientationCalDownSideVisible MEMBER _orientationCalDownSideVisible NOTIFY orientationCalSidesVisibleChanged) |
||||||
|
Q_PROPERTY(bool orientationCalUpsideDownSideVisible MEMBER _orientationCalUpsideDownSideVisible NOTIFY orientationCalSidesVisibleChanged) |
||||||
|
Q_PROPERTY(bool orientationCalLeftSideVisible MEMBER _orientationCalLeftSideVisible NOTIFY orientationCalSidesVisibleChanged) |
||||||
|
Q_PROPERTY(bool orientationCalRightSideVisible MEMBER _orientationCalRightSideVisible NOTIFY orientationCalSidesVisibleChanged) |
||||||
|
Q_PROPERTY(bool orientationCalNoseDownSideVisible MEMBER _orientationCalNoseDownSideVisible NOTIFY orientationCalSidesVisibleChanged) |
||||||
|
Q_PROPERTY(bool orientationCalTailDownSideVisible MEMBER _orientationCalTailDownSideVisible NOTIFY orientationCalSidesVisibleChanged) |
||||||
|
|
||||||
|
Q_PROPERTY(bool orientationCalDownSideInProgress MEMBER _orientationCalDownSideInProgress NOTIFY orientationCalSidesInProgressChanged) |
||||||
|
Q_PROPERTY(bool orientationCalUpsideDownSideInProgress MEMBER _orientationCalUpsideDownSideInProgress NOTIFY orientationCalSidesInProgressChanged) |
||||||
|
Q_PROPERTY(bool orientationCalLeftSideInProgress MEMBER _orientationCalLeftSideInProgress NOTIFY orientationCalSidesInProgressChanged) |
||||||
|
Q_PROPERTY(bool orientationCalRightSideInProgress MEMBER _orientationCalRightSideInProgress NOTIFY orientationCalSidesInProgressChanged) |
||||||
|
Q_PROPERTY(bool orientationCalNoseDownSideInProgress MEMBER _orientationCalNoseDownSideInProgress NOTIFY orientationCalSidesInProgressChanged) |
||||||
|
Q_PROPERTY(bool orientationCalTailDownSideInProgress MEMBER _orientationCalTailDownSideInProgress NOTIFY orientationCalSidesInProgressChanged) |
||||||
|
|
||||||
|
Q_PROPERTY(bool orientationCalDownSideRotate MEMBER _orientationCalDownSideRotate NOTIFY orientationCalSidesRotateChanged) |
||||||
|
Q_PROPERTY(bool orientationCalUpsideDownSideRotate MEMBER _orientationCalUpsideDownSideRotate NOTIFY orientationCalSidesRotateChanged) |
||||||
|
Q_PROPERTY(bool orientationCalLeftSideRotate MEMBER _orientationCalLeftSideRotate NOTIFY orientationCalSidesRotateChanged) |
||||||
|
Q_PROPERTY(bool orientationCalRightSideRotate MEMBER _orientationCalRightSideRotate NOTIFY orientationCalSidesRotateChanged) |
||||||
|
Q_PROPERTY(bool orientationCalNoseDownSideRotate MEMBER _orientationCalNoseDownSideRotate NOTIFY orientationCalSidesRotateChanged) |
||||||
|
Q_PROPERTY(bool orientationCalTailDownSideRotate MEMBER _orientationCalTailDownSideRotate NOTIFY orientationCalSidesRotateChanged) |
||||||
|
|
||||||
|
Q_PROPERTY(bool waitingForCancel MEMBER _waitingForCancel NOTIFY waitingForCancelChanged) |
||||||
|
|
||||||
|
Q_INVOKABLE void calibrateCompass(void); |
||||||
|
Q_INVOKABLE void calibrateGyro(void); |
||||||
|
Q_INVOKABLE void calibrateAccel(void); |
||||||
|
Q_INVOKABLE void calibrateLevel(void); |
||||||
|
Q_INVOKABLE void calibrateAirspeed(void); |
||||||
|
Q_INVOKABLE void cancelCalibration(void); |
||||||
|
Q_INVOKABLE void nextClicked(void); |
||||||
|
|
||||||
|
bool fixedWing(void); |
||||||
|
|
||||||
|
signals: |
||||||
|
void showGyroCalAreaChanged(void); |
||||||
|
void showOrientationCalAreaChanged(void); |
||||||
|
void orientationCalSidesDoneChanged(void); |
||||||
|
void orientationCalSidesVisibleChanged(void); |
||||||
|
void orientationCalSidesInProgressChanged(void); |
||||||
|
void orientationCalSidesRotateChanged(void); |
||||||
|
void resetStatusTextArea(void); |
||||||
|
void waitingForCancelChanged(void); |
||||||
|
void setCompassRotations(void); |
||||||
|
|
||||||
|
private slots: |
||||||
|
void _handleUASTextMessage(int uasId, int compId, int severity, QString text); |
||||||
|
|
||||||
|
private: |
||||||
|
void _startLogCalibration(void); |
||||||
|
void _startVisualCalibration(void); |
||||||
|
void _appendStatusLog(const QString& text); |
||||||
|
void _refreshParams(void); |
||||||
|
void _hideAllCalAreas(void); |
||||||
|
void _resetInternalState(void); |
||||||
|
|
||||||
|
enum StopCalibrationCode { |
||||||
|
StopCalibrationSuccess, |
||||||
|
StopCalibrationFailed, |
||||||
|
StopCalibrationCancelled |
||||||
|
}; |
||||||
|
void _stopCalibration(StopCalibrationCode code); |
||||||
|
|
||||||
|
void _updateAndEmitShowOrientationCalArea(bool show); |
||||||
|
|
||||||
|
QQuickItem* _statusLog; |
||||||
|
QQuickItem* _progressBar; |
||||||
|
QQuickItem* _compassButton; |
||||||
|
QQuickItem* _accelButton; |
||||||
|
QQuickItem* _nextButton; |
||||||
|
QQuickItem* _cancelButton; |
||||||
|
QQuickItem* _orientationCalAreaHelpText; |
||||||
|
|
||||||
|
bool _showGyroCalArea; |
||||||
|
bool _showOrientationCalArea; |
||||||
|
|
||||||
|
bool _gyroCalInProgress; |
||||||
|
bool _magCalInProgress; |
||||||
|
bool _accelCalInProgress; |
||||||
|
|
||||||
|
bool _orientationCalDownSideDone; |
||||||
|
bool _orientationCalUpsideDownSideDone; |
||||||
|
bool _orientationCalLeftSideDone; |
||||||
|
bool _orientationCalRightSideDone; |
||||||
|
bool _orientationCalNoseDownSideDone; |
||||||
|
bool _orientationCalTailDownSideDone; |
||||||
|
|
||||||
|
bool _orientationCalDownSideVisible; |
||||||
|
bool _orientationCalUpsideDownSideVisible; |
||||||
|
bool _orientationCalLeftSideVisible; |
||||||
|
bool _orientationCalRightSideVisible; |
||||||
|
bool _orientationCalNoseDownSideVisible; |
||||||
|
bool _orientationCalTailDownSideVisible; |
||||||
|
|
||||||
|
bool _orientationCalDownSideInProgress; |
||||||
|
bool _orientationCalUpsideDownSideInProgress; |
||||||
|
bool _orientationCalLeftSideInProgress; |
||||||
|
bool _orientationCalRightSideInProgress; |
||||||
|
bool _orientationCalNoseDownSideInProgress; |
||||||
|
bool _orientationCalTailDownSideInProgress; |
||||||
|
|
||||||
|
bool _orientationCalDownSideRotate; |
||||||
|
bool _orientationCalUpsideDownSideRotate; |
||||||
|
bool _orientationCalLeftSideRotate; |
||||||
|
bool _orientationCalRightSideRotate; |
||||||
|
bool _orientationCalNoseDownSideRotate; |
||||||
|
bool _orientationCalTailDownSideRotate; |
||||||
|
|
||||||
|
bool _waitingForCancel; |
||||||
|
|
||||||
|
static const int _supportedFirmwareCalVersion = 2; |
||||||
|
}; |
||||||
|
|
||||||
|
#endif |
@ -0,0 +1,47 @@ |
|||||||
|
import QtQuick 2.2 |
||||||
|
import QtQuick.Controls 1.2 |
||||||
|
import QtQuick.Controls.Styles 1.2 |
||||||
|
|
||||||
|
import QGroundControl.FactSystem 1.0 |
||||||
|
import QGroundControl.FactControls 1.0 |
||||||
|
import QGroundControl.Controls 1.0 |
||||||
|
import QGroundControl.Palette 1.0 |
||||||
|
|
||||||
|
/* |
||||||
|
IMPORTANT NOTE: Any changes made here must also be made to SensorsComponentSummary.qml |
||||||
|
*/ |
||||||
|
|
||||||
|
FactPanel { |
||||||
|
id: panel |
||||||
|
anchors.fill: parent |
||||||
|
color: qgcPal.windowShadeDark |
||||||
|
|
||||||
|
QGCPalette { id: qgcPal; colorGroupEnabled: enabled } |
||||||
|
FactPanelController { id: controller; factPanel: panel } |
||||||
|
|
||||||
|
property Fact ins_accoffs_x: controller.getParameterFact(-1, "INS_ACCOFFS_X") |
||||||
|
property Fact ins_accoffs_y: controller.getParameterFact(-1, "INS_ACCOFFS_Y") |
||||||
|
property Fact ins_accoffs_z: controller.getParameterFact(-1, "INS_ACCOFFS_Z") |
||||||
|
|
||||||
|
property Fact compass_ofs_x: controller.getParameterFact(-1, "COMPASS_OFS_X") |
||||||
|
property Fact compass_ofs_y: controller.getParameterFact(-1, "COMPASS_OFS_Y") |
||||||
|
property Fact compass_ofs_z: controller.getParameterFact(-1, "COMPASS_OFS_Z") |
||||||
|
|
||||||
|
property bool accelCalNeeded: ins_accoffs_x.value == 0 && ins_accoffs_y.value == 0 && ins_accoffs_z.value == 0 |
||||||
|
property bool compassCalNeeded: compass_ofs_x.value == 0 && compass_ofs_y.value == 0 && compass_ofs_y.value == 0 |
||||||
|
|
||||||
|
Column { |
||||||
|
anchors.fill: parent |
||||||
|
anchors.margins: 8 |
||||||
|
|
||||||
|
VehicleSummaryRow { |
||||||
|
labelText: "Compass:" |
||||||
|
valueText: compassCalNeeded ? "Setup required" : "Ready" |
||||||
|
} |
||||||
|
|
||||||
|
VehicleSummaryRow { |
||||||
|
labelText: "Accelerometer:" |
||||||
|
valueText: accelCalNeeded ? "Setup required" : "Ready" |
||||||
|
} |
||||||
|
} |
||||||
|
} |
Loading…
Reference in new issue