Commit 59be6d63 authored by DonLakeFlyer's avatar DonLakeFlyer

Support preflight barometer calibration

parent 21090040
...@@ -27,14 +27,8 @@ APMSensorsComponentController::APMSensorsComponentController(void) ...@@ -27,14 +27,8 @@ APMSensorsComponentController::APMSensorsComponentController(void)
: _sensorsComponent(NULL) : _sensorsComponent(NULL)
, _statusLog(NULL) , _statusLog(NULL)
, _progressBar(NULL) , _progressBar(NULL)
, _compassButton(NULL)
, _accelButton(NULL)
, _compassMotButton(NULL)
, _levelButton(NULL)
, _calibratePressureButton(NULL)
, _nextButton(NULL) , _nextButton(NULL)
, _cancelButton(NULL) , _cancelButton(NULL)
, _setOrientationsButton(NULL)
, _showOrientationCalArea(false) , _showOrientationCalArea(false)
, _calTypeInProgress(CalTypeNone) , _calTypeInProgress(CalTypeNone)
, _orientationCalDownSideDone(false) , _orientationCalDownSideDone(false)
...@@ -110,12 +104,7 @@ void APMSensorsComponentController::_startLogCalibration(void) ...@@ -110,12 +104,7 @@ void APMSensorsComponentController::_startLogCalibration(void)
connect(_uas, &UASInterface::textMessageReceived, this, &APMSensorsComponentController::_handleUASTextMessage); connect(_uas, &UASInterface::textMessageReceived, this, &APMSensorsComponentController::_handleUASTextMessage);
_compassButton->setEnabled(false); emit setAllCalButtonsEnabled(false);
_accelButton->setEnabled(false);
_compassMotButton->setEnabled(false);
_levelButton->setEnabled(false);
_calibratePressureButton->setEnabled(false);
_setOrientationsButton->setEnabled(false);
if (_calTypeInProgress == CalTypeAccel || _calTypeInProgress == CalTypeCompassMot) { if (_calTypeInProgress == CalTypeAccel || _calTypeInProgress == CalTypeCompassMot) {
_nextButton->setEnabled(true); _nextButton->setEnabled(true);
} }
...@@ -124,13 +113,9 @@ void APMSensorsComponentController::_startLogCalibration(void) ...@@ -124,13 +113,9 @@ void APMSensorsComponentController::_startLogCalibration(void)
void APMSensorsComponentController::_startVisualCalibration(void) void APMSensorsComponentController::_startVisualCalibration(void)
{ {
_compassButton->setEnabled(false); emit setAllCalButtonsEnabled(false);
_accelButton->setEnabled(false);
_compassMotButton->setEnabled(false);
_levelButton->setEnabled(false);
_calibratePressureButton->setEnabled(false);
_setOrientationsButton->setEnabled(false);
_cancelButton->setEnabled(true); _cancelButton->setEnabled(true);
_nextButton->setEnabled(false);
_resetInternalState(); _resetInternalState();
...@@ -169,12 +154,7 @@ void APMSensorsComponentController::_stopCalibration(APMSensorsComponentControll ...@@ -169,12 +154,7 @@ void APMSensorsComponentController::_stopCalibration(APMSensorsComponentControll
disconnect(_uas, &UASInterface::textMessageReceived, this, &APMSensorsComponentController::_handleUASTextMessage); disconnect(_uas, &UASInterface::textMessageReceived, this, &APMSensorsComponentController::_handleUASTextMessage);
_compassButton->setEnabled(true); emit setAllCalButtonsEnabled(true);
_accelButton->setEnabled(true);
_compassMotButton->setEnabled(true);
_levelButton->setEnabled(true);
_calibratePressureButton->setEnabled(true);
_setOrientationsButton->setEnabled(true);
_nextButton->setEnabled(false); _nextButton->setEnabled(false);
_cancelButton->setEnabled(false); _cancelButton->setEnabled(false);
......
...@@ -34,14 +34,8 @@ public: ...@@ -34,14 +34,8 @@ public:
Q_PROPERTY(QQuickItem* statusLog MEMBER _statusLog) Q_PROPERTY(QQuickItem* statusLog MEMBER _statusLog)
Q_PROPERTY(QQuickItem* progressBar MEMBER _progressBar) Q_PROPERTY(QQuickItem* progressBar MEMBER _progressBar)
Q_PROPERTY(QQuickItem* compassButton MEMBER _compassButton)
Q_PROPERTY(QQuickItem* accelButton MEMBER _accelButton)
Q_PROPERTY(QQuickItem* compassMotButton MEMBER _compassMotButton)
Q_PROPERTY(QQuickItem* levelButton MEMBER _levelButton)
Q_PROPERTY(QQuickItem* calibratePressureButton MEMBER _calibratePressureButton)
Q_PROPERTY(QQuickItem* nextButton MEMBER _nextButton) Q_PROPERTY(QQuickItem* nextButton MEMBER _nextButton)
Q_PROPERTY(QQuickItem* cancelButton MEMBER _cancelButton) Q_PROPERTY(QQuickItem* cancelButton MEMBER _cancelButton)
Q_PROPERTY(QQuickItem* setOrientationsButton MEMBER _setOrientationsButton)
Q_PROPERTY(QQuickItem* orientationCalAreaHelpText MEMBER _orientationCalAreaHelpText) Q_PROPERTY(QQuickItem* orientationCalAreaHelpText MEMBER _orientationCalAreaHelpText)
Q_PROPERTY(bool compassSetupNeeded READ compassSetupNeeded NOTIFY setupNeededChanged) Q_PROPERTY(bool compassSetupNeeded READ compassSetupNeeded NOTIFY setupNeededChanged)
...@@ -135,6 +129,7 @@ signals: ...@@ -135,6 +129,7 @@ signals:
void compass1CalFitnessChanged(double compass1CalFitness); void compass1CalFitnessChanged(double compass1CalFitness);
void compass2CalFitnessChanged(double compass2CalFitness); void compass2CalFitnessChanged(double compass2CalFitness);
void compass3CalFitnessChanged(double compass3CalFitness); void compass3CalFitnessChanged(double compass3CalFitness);
void setAllCalButtonsEnabled(bool enabled);
private slots: private slots:
void _handleUASTextMessage(int uasId, int compId, int severity, QString text); void _handleUASTextMessage(int uasId, int compId, int severity, QString text);
...@@ -168,14 +163,8 @@ private: ...@@ -168,14 +163,8 @@ private:
QQuickItem* _statusLog; QQuickItem* _statusLog;
QQuickItem* _progressBar; QQuickItem* _progressBar;
QQuickItem* _compassButton;
QQuickItem* _accelButton;
QQuickItem* _compassMotButton;
QQuickItem* _levelButton;
QQuickItem* _calibratePressureButton;
QQuickItem* _nextButton; QQuickItem* _nextButton;
QQuickItem* _cancelButton; QQuickItem* _cancelButton;
QQuickItem* _setOrientationsButton;
QQuickItem* _orientationCalAreaHelpText; QQuickItem* _orientationCalAreaHelpText;
bool _showOrientationCalArea; bool _showOrientationCalArea;
......
...@@ -418,7 +418,6 @@ SetupPage { ...@@ -418,7 +418,6 @@ SetupPage {
QGCButton { QGCButton {
text: qsTr("Copy Trims") text: qsTr("Copy Trims")
visible: QGroundControl.multiVehicleManager.activeVehicle.px4Firmware
onClicked: showDialog(copyTrimsDialogComponent, dialogTitle, radioPage.showDialogDefaultWidth, StandardButton.Ok | StandardButton.Cancel) onClicked: showDialog(copyTrimsDialogComponent, dialogTitle, radioPage.showDialogDefaultWidth, StandardButton.Ok | StandardButton.Cancel)
} }
......
...@@ -132,11 +132,6 @@ bool ArduSubFirmwarePlugin::supportsJSButton(void) ...@@ -132,11 +132,6 @@ bool ArduSubFirmwarePlugin::supportsJSButton(void)
return true; return true;
} }
bool ArduSubFirmwarePlugin::supportsCalibratePressure(void)
{
return true;
}
bool ArduSubFirmwarePlugin::supportsMotorInterference(void) bool ArduSubFirmwarePlugin::supportsMotorInterference(void)
{ {
return false; return false;
......
...@@ -79,8 +79,6 @@ public: ...@@ -79,8 +79,6 @@ public:
bool supportsJSButton(void); bool supportsJSButton(void);
bool supportsCalibratePressure(void);
bool supportsMotorInterference(void); bool supportsMotorInterference(void);
QString brandImageIndoor(const Vehicle* vehicle) const { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImageSub"); } QString brandImageIndoor(const Vehicle* vehicle) const { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImageSub"); }
......
...@@ -139,11 +139,6 @@ bool FirmwarePlugin::supportsRadio(void) ...@@ -139,11 +139,6 @@ bool FirmwarePlugin::supportsRadio(void)
return true; return true;
} }
bool FirmwarePlugin::supportsCalibratePressure(void)
{
return false;
}
bool FirmwarePlugin::supportsMotorInterference(void) bool FirmwarePlugin::supportsMotorInterference(void)
{ {
return true; return true;
......
...@@ -170,10 +170,6 @@ public: ...@@ -170,10 +170,6 @@ public:
/// to be assigned via parameters in firmware. Default is false. /// to be assigned via parameters in firmware. Default is false.
virtual bool supportsJSButton(void); virtual bool supportsJSButton(void);
/// Returns true if the firmware supports calibrating the pressure sensor so the altitude will read
/// zero at the current pressure. Default is false.
virtual bool supportsCalibratePressure(void);
/// Returns true if the firmware supports calibrating motor interference offsets for the compass /// Returns true if the firmware supports calibrating motor interference offsets for the compass
/// (CompassMot). Default is true. /// (CompassMot). Default is true.
virtual bool supportsMotorInterference(void); virtual bool supportsMotorInterference(void);
......
...@@ -1959,11 +1959,6 @@ bool Vehicle::supportsJSButton(void) const ...@@ -1959,11 +1959,6 @@ bool Vehicle::supportsJSButton(void) const
return _firmwarePlugin->supportsJSButton(); return _firmwarePlugin->supportsJSButton();
} }
bool Vehicle::supportsCalibratePressure(void) const
{
return _firmwarePlugin->supportsCalibratePressure();
}
bool Vehicle::supportsMotorInterference(void) const bool Vehicle::supportsMotorInterference(void) const
{ {
return _firmwarePlugin->supportsMotorInterference(); return _firmwarePlugin->supportsMotorInterference();
......
...@@ -282,7 +282,6 @@ public: ...@@ -282,7 +282,6 @@ public:
Q_PROPERTY(bool supportsThrottleModeCenterZero READ supportsThrottleModeCenterZero CONSTANT) Q_PROPERTY(bool supportsThrottleModeCenterZero READ supportsThrottleModeCenterZero CONSTANT)
Q_PROPERTY(bool supportsJSButton READ supportsJSButton CONSTANT) Q_PROPERTY(bool supportsJSButton READ supportsJSButton CONSTANT)
Q_PROPERTY(bool supportsRadio READ supportsRadio CONSTANT) Q_PROPERTY(bool supportsRadio READ supportsRadio CONSTANT)
Q_PROPERTY(bool supportsCalibratePressure READ supportsCalibratePressure CONSTANT)
Q_PROPERTY(bool supportsMotorInterference READ supportsMotorInterference CONSTANT) Q_PROPERTY(bool supportsMotorInterference READ supportsMotorInterference CONSTANT)
Q_PROPERTY(bool autoDisconnect MEMBER _autoDisconnect NOTIFY autoDisconnectChanged) Q_PROPERTY(bool autoDisconnect MEMBER _autoDisconnect NOTIFY autoDisconnectChanged)
Q_PROPERTY(QString prearmError READ prearmError WRITE setPrearmError NOTIFY prearmErrorChanged) Q_PROPERTY(QString prearmError READ prearmError WRITE setPrearmError NOTIFY prearmErrorChanged)
...@@ -519,7 +518,6 @@ public: ...@@ -519,7 +518,6 @@ public:
bool supportsThrottleModeCenterZero(void) const; bool supportsThrottleModeCenterZero(void) const;
bool supportsRadio(void) const; bool supportsRadio(void) const;
bool supportsJSButton(void) const; bool supportsJSButton(void) const;
bool supportsCalibratePressure(void) const;
bool supportsMotorInterference(void) const; bool supportsMotorInterference(void) const;
void setGuidedMode(bool guidedMode); void setGuidedMode(bool guidedMode);
......
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