Browse Source

Merge pull request #5277 from DonLakeFlyer/APMMissingCal

ArduPilot: Support perflight barometer/airspeed calibration
QGC4.4
Don Gagne 8 years ago committed by GitHub
parent
commit
45b7136ea8
  1. 184
      src/AutoPilotPlugins/APM/APMSensorsComponent.qml
  2. 28
      src/AutoPilotPlugins/APM/APMSensorsComponentController.cc
  3. 13
      src/AutoPilotPlugins/APM/APMSensorsComponentController.h
  4. 1
      src/AutoPilotPlugins/Common/RadioComponent.qml
  5. 182
      src/AutoPilotPlugins/PX4/SensorsComponent.qml
  6. 5
      src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.cc
  7. 2
      src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.h
  8. 5
      src/FirmwarePlugin/FirmwarePlugin.cc
  9. 4
      src/FirmwarePlugin/FirmwarePlugin.h
  10. 5
      src/Vehicle/Vehicle.cc
  11. 2
      src/Vehicle/Vehicle.h

184
src/AutoPilotPlugins/APM/APMSensorsComponent.qml

@ -30,10 +30,9 @@ SetupPage { @@ -30,10 +30,9 @@ SetupPage {
Component {
id: sensorsPageComponent
RowLayout {
width: availableWidth
height: availableHeight
spacing: ScreenTools.defaultFontPixelWidth / 2
Item {
width: availableWidth
height: availableHeight
// Help text which is shown both in the status text area prior to pressing a cal button and in the
// pre-calibration dialog.
@ -74,10 +73,13 @@ SetupPage { @@ -74,10 +73,13 @@ SetupPage {
readonly property int _calTypeCompass: 1 ///< Calibrate compass
readonly property int _calTypeAccel: 2 ///< Calibrate accel
readonly property int _calTypeSet: 3 ///< Set orientations only
readonly property int _buttonWidth: ScreenTools.defaultFontPixelWidth * 15
property bool _orientationsDialogShowCompass: true
property string _orientationDialogHelp: orientationHelpSet
property int _orientationDialogCalType
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property real _margins: ScreenTools.defaultFontPixelHeight / 2
function showOrientationsDialog(calType) {
var dialogTitle
@ -117,14 +119,8 @@ SetupPage { @@ -117,14 +119,8 @@ SetupPage {
factPanel: sensorsPage.viewPanel
statusLog: statusTextArea
progressBar: progressBar
compassButton: compassButton
accelButton: accelButton
compassMotButton: motorInterferenceButton
levelButton: levelHorizonButton
calibratePressureButton: calibratePressureButton
nextButton: nextButton
cancelButton: cancelButton
setOrientationsButton: setOrientationsButton
orientationCalAreaHelpText: orientationCalAreaHelpText
property var rgCompassCalFitness: [ controller.compass1CalFitness, controller.compass2CalFitness, controller.compass3CalFitness ]
@ -152,6 +148,10 @@ SetupPage { @@ -152,6 +148,10 @@ SetupPage {
break
}
}
onSetAllCalButtonsEnabled: {
buttonColumn.enabled = enabled
}
}
Component.onCompleted: {
@ -462,112 +462,122 @@ SetupPage { @@ -462,112 +462,122 @@ SetupPage {
anchors.left: parent.left
anchors.right: parent.right
wrapMode: Text.WordWrap
text: qsTr("Pressure calibration will set the depth to zero at the current pressure reading.")
text: _helpText
readonly property string _altText: _activeVehicle.sub ? qsTr("depth") : qsTr("altitude")
readonly property string _helpText: qsTr("Pressure calibration will set the %1 to zero at the current pressure reading. %2").arg(_altText).arg(_helpTextFW)
readonly property string _helpTextFW: _activeVehicle.fixedWing ? qsTr("Cover airspeed sensor for calibration.") : ""
}
} // QGCViewDialog
} // Component - calibratePressureDialogComponent
/// Left button column
Column {
spacing: ScreenTools.defaultFontPixelHeight / 2
Layout.alignment: Qt.AlignLeft | Qt.AlignTop
QGCFlickable {
id: buttonFlickable
anchors.left: parent.left
anchors.top: parent.top
anchors.bottom: parent.bottom
width: _buttonWidth
contentHeight: nextCancelColumn.y + nextCancelColumn.height + _margins
readonly property int buttonWidth: ScreenTools.defaultFontPixelWidth * 15
// Calibration button column - Calibratin buttons are kept in a separate column from Next/Cancel buttons
// so we can enable/disable them all as a group
Column {
id: buttonColumn
spacing: _margins
Layout.alignment: Qt.AlignLeft | Qt.AlignTop
IndicatorButton {
id: accelButton
width: parent.buttonWidth
text: qsTr("Accelerometer")
indicatorGreen: !accelCalNeeded
IndicatorButton {
width: _buttonWidth
text: qsTr("Accelerometer")
indicatorGreen: !accelCalNeeded
onClicked: showOrientationsDialog(_calTypeAccel)
}
onClicked: showOrientationsDialog(_calTypeAccel)
}
IndicatorButton {
width: _buttonWidth
text: qsTr("Compass")
indicatorGreen: !compassCalNeeded
IndicatorButton {
id: compassButton
width: parent.buttonWidth
text: qsTr("Compass")
indicatorGreen: !compassCalNeeded
onClicked: {
if (controller.accelSetupNeeded) {
showMessage(qsTr("Calibrate Compass"), qsTr("Accelerometer must be calibrated prior to Compass."), StandardButton.Ok)
} else {
showOrientationsDialog(_calTypeCompass)
onClicked: {
if (controller.accelSetupNeeded) {
showMessage(qsTr("Calibrate Compass"), qsTr("Accelerometer must be calibrated prior to Compass."), StandardButton.Ok)
} else {
showOrientationsDialog(_calTypeCompass)
}
}
}
}
QGCButton {
id: levelHorizonButton
width: parent.buttonWidth
text: _levelHorizonText
QGCButton {
width: _buttonWidth
text: _levelHorizonText
readonly property string _levelHorizonText: qsTr("Level Horizon")
readonly property string _levelHorizonText: qsTr("Level Horizon")
onClicked: {
if (controller.accelSetupNeeded) {
showMessage(_levelHorizonText, qsTr("Accelerometer must be calibrated prior to Level Horizon."), StandardButton.Ok)
} else {
showDialog(levelHorizonDialogComponent, _levelHorizonText, qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
onClicked: {
if (controller.accelSetupNeeded) {
showMessage(_levelHorizonText, qsTr("Accelerometer must be calibrated prior to Level Horizon."), StandardButton.Ok)
} else {
showDialog(levelHorizonDialogComponent, _levelHorizonText, qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
}
}
}
}
QGCButton {
id: calibratePressureButton
width: parent.buttonWidth
text: _calibratePressureText
visible: _activeVehicle ? _activeVehicle.supportsCalibratePressure : false
QGCButton {
width: _buttonWidth
text: _calibratePressureText
onClicked: showDialog(calibratePressureDialogComponent, _calibratePressureText, qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
readonly property string _calibratePressureText: qsTr("Calibrate Pressure")
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
onClicked: {
showDialog(calibratePressureDialogComponent, _calibratePressureText, qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
readonly property string _calibratePressureText: _activeVehicle.fixedWing ? qsTr("Cal Baro/Airspeed") : qsTr("Calibrate Pressure")
}
}
QGCButton {
id: motorInterferenceButton
width: parent.buttonWidth
text: qsTr("CompassMot")
visible: _activeVehicle ? _activeVehicle.supportsMotorInterference : false
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
QGCButton {
width: _buttonWidth
text: qsTr("CompassMot")
visible: _activeVehicle ? _activeVehicle.supportsMotorInterference : false
onClicked: showDialog(compassMotDialogComponent, qsTr("CompassMot - Compass Motor Interference Calibration"), qgcView.showDialogFullWidth, StandardButton.Cancel | StandardButton.Ok)
}
onClicked: showDialog(compassMotDialogComponent, qsTr("CompassMot - Compass Motor Interference Calibration"), qgcView.showDialogFullWidth, StandardButton.Cancel | StandardButton.Ok)
}
QGCButton {
id: nextButton
width: parent.buttonWidth
text: qsTr("Next")
enabled: false
onClicked: controller.nextClicked()
}
QGCButton {
width: _buttonWidth
text: qsTr("Sensor Settings")
onClicked: showOrientationsDialog(_calTypeSet)
}
} // Column - Cal Buttons
QGCButton {
id: cancelButton
width: parent.buttonWidth
text: qsTr("Cancel")
enabled: false
onClicked: controller.cancelCalibration()
}
Column {
id: nextCancelColumn
anchors.topMargin: buttonColumn.spacing
anchors.top: buttonColumn.bottom
anchors.left: buttonColumn.left
spacing: buttonColumn.spacing
QGCButton {
id: nextButton
width: _buttonWidth
text: qsTr("Next")
enabled: false
onClicked: controller.nextClicked()
}
QGCButton {
id: setOrientationsButton
width: parent.buttonWidth
text: qsTr("Sensor Settings")
onClicked: showOrientationsDialog(_calTypeSet)
QGCButton {
id: cancelButton
width: _buttonWidth
text: qsTr("Cancel")
enabled: false
onClicked: controller.cancelCalibration()
}
}
} // Column - Buttons
} // QGCFlickable - buttons
/// Right column - cal area
Column {
anchors.leftMargin: _margins
anchors.top: parent.top
anchors.bottom: parent.bottom
Layout.fillWidth: true
anchors.left: buttonFlickable.right
anchors.right: parent.right
ProgressBar {
id: progressBar

28
src/AutoPilotPlugins/APM/APMSensorsComponentController.cc

@ -27,14 +27,8 @@ APMSensorsComponentController::APMSensorsComponentController(void) @@ -27,14 +27,8 @@ APMSensorsComponentController::APMSensorsComponentController(void)
: _sensorsComponent(NULL)
, _statusLog(NULL)
, _progressBar(NULL)
, _compassButton(NULL)
, _accelButton(NULL)
, _compassMotButton(NULL)
, _levelButton(NULL)
, _calibratePressureButton(NULL)
, _nextButton(NULL)
, _cancelButton(NULL)
, _setOrientationsButton(NULL)
, _showOrientationCalArea(false)
, _calTypeInProgress(CalTypeNone)
, _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);
_compassButton->setEnabled(false);
_accelButton->setEnabled(false);
_compassMotButton->setEnabled(false);
_levelButton->setEnabled(false);
_calibratePressureButton->setEnabled(false);
_setOrientationsButton->setEnabled(false);
emit setAllCalButtonsEnabled(false);
if (_calTypeInProgress == CalTypeAccel || _calTypeInProgress == CalTypeCompassMot) {
_nextButton->setEnabled(true);
}
@ -124,13 +113,9 @@ void APMSensorsComponentController::_startLogCalibration(void) @@ -124,13 +113,9 @@ void APMSensorsComponentController::_startLogCalibration(void)
void APMSensorsComponentController::_startVisualCalibration(void)
{
_compassButton->setEnabled(false);
_accelButton->setEnabled(false);
_compassMotButton->setEnabled(false);
_levelButton->setEnabled(false);
_calibratePressureButton->setEnabled(false);
_setOrientationsButton->setEnabled(false);
emit setAllCalButtonsEnabled(false);
_cancelButton->setEnabled(true);
_nextButton->setEnabled(false);
_resetInternalState();
@ -169,12 +154,7 @@ void APMSensorsComponentController::_stopCalibration(APMSensorsComponentControll @@ -169,12 +154,7 @@ void APMSensorsComponentController::_stopCalibration(APMSensorsComponentControll
disconnect(_uas, &UASInterface::textMessageReceived, this, &APMSensorsComponentController::_handleUASTextMessage);
_compassButton->setEnabled(true);
_accelButton->setEnabled(true);
_compassMotButton->setEnabled(true);
_levelButton->setEnabled(true);
_calibratePressureButton->setEnabled(true);
_setOrientationsButton->setEnabled(true);
emit setAllCalButtonsEnabled(true);
_nextButton->setEnabled(false);
_cancelButton->setEnabled(false);

13
src/AutoPilotPlugins/APM/APMSensorsComponentController.h

@ -34,14 +34,8 @@ public: @@ -34,14 +34,8 @@ public:
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* compassMotButton MEMBER _compassMotButton)
Q_PROPERTY(QQuickItem* levelButton MEMBER _levelButton)
Q_PROPERTY(QQuickItem* calibratePressureButton MEMBER _calibratePressureButton)
Q_PROPERTY(QQuickItem* nextButton MEMBER _nextButton)
Q_PROPERTY(QQuickItem* cancelButton MEMBER _cancelButton)
Q_PROPERTY(QQuickItem* setOrientationsButton MEMBER _setOrientationsButton)
Q_PROPERTY(QQuickItem* orientationCalAreaHelpText MEMBER _orientationCalAreaHelpText)
Q_PROPERTY(bool compassSetupNeeded READ compassSetupNeeded NOTIFY setupNeededChanged)
@ -135,6 +129,7 @@ signals: @@ -135,6 +129,7 @@ signals:
void compass1CalFitnessChanged(double compass1CalFitness);
void compass2CalFitnessChanged(double compass2CalFitness);
void compass3CalFitnessChanged(double compass3CalFitness);
void setAllCalButtonsEnabled(bool enabled);
private slots:
void _handleUASTextMessage(int uasId, int compId, int severity, QString text);
@ -168,14 +163,8 @@ private: @@ -168,14 +163,8 @@ private:
QQuickItem* _statusLog;
QQuickItem* _progressBar;
QQuickItem* _compassButton;
QQuickItem* _accelButton;
QQuickItem* _compassMotButton;
QQuickItem* _levelButton;
QQuickItem* _calibratePressureButton;
QQuickItem* _nextButton;
QQuickItem* _cancelButton;
QQuickItem* _setOrientationsButton;
QQuickItem* _orientationCalAreaHelpText;
bool _showOrientationCalArea;

1
src/AutoPilotPlugins/Common/RadioComponent.qml

@ -418,7 +418,6 @@ SetupPage { @@ -418,7 +418,6 @@ SetupPage {
QGCButton {
text: qsTr("Copy Trims")
visible: QGroundControl.multiVehicleManager.activeVehicle.px4Firmware
onClicked: showDialog(copyTrimsDialogComponent, dialogTitle, radioPage.showDialogDefaultWidth, StandardButton.Ok | StandardButton.Cancel)
}

182
src/AutoPilotPlugins/PX4/SensorsComponent.qml

@ -106,8 +106,10 @@ SetupPage { @@ -106,8 +106,10 @@ SetupPage {
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
property bool _sensorsHaveFixedOrientation: QGroundControl.corePlugin.options.sensorsHaveFixedOrientation
property bool _wifiReliableForCalibration: QGroundControl.corePlugin.options.wifiReliableForCalibration
property bool _sensorsHaveFixedOrientation: QGroundControl.corePlugin.options.sensorsHaveFixedOrientation
property bool _wifiReliableForCalibration: QGroundControl.corePlugin.options.wifiReliableForCalibration
property int _buttonWidth: ScreenTools.defaultFontPixelWidth * 15
SensorsComponentController {
id: controller
@ -332,107 +334,113 @@ SetupPage { @@ -332,107 +334,113 @@ SetupPage {
} // QGCViewDialog
} // Component - setOrientationsDialogComponent
Column {
id: buttonColumn
spacing: ScreenTools.defaultFontPixelHeight / 2
readonly property int buttonWidth: ScreenTools.defaultFontPixelWidth * 15
IndicatorButton {
id: compassButton
width: parent.buttonWidth
text: qsTr("Compass")
indicatorGreen: cal_mag0_id.value != 0
visible: QGroundControl.corePlugin.options.showSensorCalibrationCompass
onClicked: {
preCalibrationDialogType = "compass"
preCalibrationDialogHelp = compassHelp
showDialog(preCalibrationDialogComponent, qsTr("Calibrate Compass"), sensorsPage.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
QGCFlickable {
id: buttonFlickable
anchors.top: parent.top
anchors.bottom: parent.bottom
width: _buttonWidth
contentHeight: buttonColumn.height + buttonColumn.spacing
Column {
id: buttonColumn
spacing: ScreenTools.defaultFontPixelHeight / 2
IndicatorButton {
id: compassButton
width: _buttonWidth
text: qsTr("Compass")
indicatorGreen: cal_mag0_id.value != 0
visible: QGroundControl.corePlugin.options.showSensorCalibrationCompass
onClicked: {
preCalibrationDialogType = "compass"
preCalibrationDialogHelp = compassHelp
showDialog(preCalibrationDialogComponent, qsTr("Calibrate Compass"), sensorsPage.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
}
}
}
IndicatorButton {
id: gyroButton
width: parent.buttonWidth
text: qsTr("Gyroscope")
indicatorGreen: cal_gyro0_id.value != 0
visible: QGroundControl.corePlugin.options.showSensorCalibrationGyro
onClicked: {
preCalibrationDialogType = "gyro"
preCalibrationDialogHelp = gyroHelp
showDialog(preCalibrationDialogComponent, qsTr("Calibrate Gyro"), sensorsPage.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
IndicatorButton {
id: gyroButton
width: _buttonWidth
text: qsTr("Gyroscope")
indicatorGreen: cal_gyro0_id.value != 0
visible: QGroundControl.corePlugin.options.showSensorCalibrationGyro
onClicked: {
preCalibrationDialogType = "gyro"
preCalibrationDialogHelp = gyroHelp
showDialog(preCalibrationDialogComponent, qsTr("Calibrate Gyro"), sensorsPage.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
}
}
}
IndicatorButton {
id: accelButton
width: parent.buttonWidth
text: qsTr("Accelerometer")
indicatorGreen: cal_acc0_id.value != 0
visible: QGroundControl.corePlugin.options.showSensorCalibrationAccel
onClicked: {
preCalibrationDialogType = "accel"
preCalibrationDialogHelp = accelHelp
showDialog(preCalibrationDialogComponent, qsTr("Calibrate Accelerometer"), sensorsPage.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
IndicatorButton {
id: accelButton
width: _buttonWidth
text: qsTr("Accelerometer")
indicatorGreen: cal_acc0_id.value != 0
visible: QGroundControl.corePlugin.options.showSensorCalibrationAccel
onClicked: {
preCalibrationDialogType = "accel"
preCalibrationDialogHelp = accelHelp
showDialog(preCalibrationDialogComponent, qsTr("Calibrate Accelerometer"), sensorsPage.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
}
}
}
IndicatorButton {
id: levelButton
width: parent.buttonWidth
text: qsTr("Level Horizon")
indicatorGreen: sens_board_x_off.value != 0 || sens_board_y_off != 0 | sens_board_z_off != 0
enabled: cal_acc0_id.value != 0 && cal_gyro0_id.value != 0
visible: QGroundControl.corePlugin.options.showSensorCalibrationLevel
onClicked: {
preCalibrationDialogType = "level"
preCalibrationDialogHelp = levelHelp
showDialog(preCalibrationDialogComponent, qsTr("Level Horizon"), sensorsPage.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
IndicatorButton {
id: levelButton
width: _buttonWidth
text: qsTr("Level Horizon")
indicatorGreen: sens_board_x_off.value != 0 || sens_board_y_off != 0 | sens_board_z_off != 0
enabled: cal_acc0_id.value != 0 && cal_gyro0_id.value != 0
visible: QGroundControl.corePlugin.options.showSensorCalibrationLevel
onClicked: {
preCalibrationDialogType = "level"
preCalibrationDialogHelp = levelHelp
showDialog(preCalibrationDialogComponent, qsTr("Level Horizon"), sensorsPage.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
}
}
}
IndicatorButton {
id: airspeedButton
width: parent.buttonWidth
text: qsTr("Airspeed")
visible: (controller.vehicle.fixedWing || controller.vehicle.vtol) && controller.getParameterFact(-1, "CBRK_AIRSPD_CHK").value != 162128 && QGroundControl.corePlugin.options.showSensorCalibrationAirspeed
indicatorGreen: sens_dpres_off.value != 0
onClicked: {
preCalibrationDialogType = "airspeed"
preCalibrationDialogHelp = airspeedHelp
showDialog(preCalibrationDialogComponent, qsTr("Calibrate Airspeed"), sensorsPage.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
IndicatorButton {
id: airspeedButton
width: _buttonWidth
text: qsTr("Airspeed")
visible: (controller.vehicle.fixedWing || controller.vehicle.vtol) && controller.getParameterFact(-1, "CBRK_AIRSPD_CHK").value != 162128 && QGroundControl.corePlugin.options.showSensorCalibrationAirspeed
indicatorGreen: sens_dpres_off.value != 0
onClicked: {
preCalibrationDialogType = "airspeed"
preCalibrationDialogHelp = airspeedHelp
showDialog(preCalibrationDialogComponent, qsTr("Calibrate Airspeed"), sensorsPage.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
}
}
}
QGCButton {
id: cancelButton
width: parent.buttonWidth
text: qsTr("Cancel")
enabled: false
onClicked: controller.cancelCalibration()
}
QGCButton {
id: cancelButton
width: _buttonWidth
text: qsTr("Cancel")
enabled: false
onClicked: controller.cancelCalibration()
}
QGCButton {
id: setOrientationsButton
width: parent.buttonWidth
text: qsTr("Set Orientations")
visible: !_sensorsHaveFixedOrientation
QGCButton {
id: setOrientationsButton
width: _buttonWidth
text: qsTr("Set Orientations")
visible: !_sensorsHaveFixedOrientation
onClicked: {
setOrientationsDialogShowBoardOrientation = true
showDialog(setOrientationsDialogComponent, qsTr("Set Orientations"), sensorsPage.showDialogDefaultWidth, StandardButton.Ok)
onClicked: {
setOrientationsDialogShowBoardOrientation = true
showDialog(setOrientationsDialogComponent, qsTr("Set Orientations"), sensorsPage.showDialogDefaultWidth, StandardButton.Ok)
}
}
}
} // Column - Buttons
} // Column - Buttons
} // QGCFLickable - Buttons
Column {
anchors.leftMargin: ScreenTools.defaultFontPixelWidth / 2
anchors.left: buttonColumn.right
anchors.left: buttonFlickable.right
anchors.right: parent.right
anchors.top: parent.top
anchors.bottom: parent.bottom

5
src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.cc

@ -132,11 +132,6 @@ bool ArduSubFirmwarePlugin::supportsJSButton(void) @@ -132,11 +132,6 @@ bool ArduSubFirmwarePlugin::supportsJSButton(void)
return true;
}
bool ArduSubFirmwarePlugin::supportsCalibratePressure(void)
{
return true;
}
bool ArduSubFirmwarePlugin::supportsMotorInterference(void)
{
return false;

2
src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.h

@ -79,8 +79,6 @@ public: @@ -79,8 +79,6 @@ public:
bool supportsJSButton(void);
bool supportsCalibratePressure(void);
bool supportsMotorInterference(void);
QString brandImageIndoor(const Vehicle* vehicle) const { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImageSub"); }

5
src/FirmwarePlugin/FirmwarePlugin.cc

@ -139,11 +139,6 @@ bool FirmwarePlugin::supportsRadio(void) @@ -139,11 +139,6 @@ bool FirmwarePlugin::supportsRadio(void)
return true;
}
bool FirmwarePlugin::supportsCalibratePressure(void)
{
return false;
}
bool FirmwarePlugin::supportsMotorInterference(void)
{
return true;

4
src/FirmwarePlugin/FirmwarePlugin.h

@ -170,10 +170,6 @@ public: @@ -170,10 +170,6 @@ public:
/// to be assigned via parameters in firmware. Default is false.
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
/// (CompassMot). Default is true.
virtual bool supportsMotorInterference(void);

5
src/Vehicle/Vehicle.cc

@ -1964,11 +1964,6 @@ bool Vehicle::supportsJSButton(void) const @@ -1964,11 +1964,6 @@ bool Vehicle::supportsJSButton(void) const
return _firmwarePlugin->supportsJSButton();
}
bool Vehicle::supportsCalibratePressure(void) const
{
return _firmwarePlugin->supportsCalibratePressure();
}
bool Vehicle::supportsMotorInterference(void) const
{
return _firmwarePlugin->supportsMotorInterference();

2
src/Vehicle/Vehicle.h

@ -282,7 +282,6 @@ public: @@ -282,7 +282,6 @@ public:
Q_PROPERTY(bool supportsThrottleModeCenterZero READ supportsThrottleModeCenterZero CONSTANT)
Q_PROPERTY(bool supportsJSButton READ supportsJSButton 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 autoDisconnect MEMBER _autoDisconnect NOTIFY autoDisconnectChanged)
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 supportsRadio(void) const;
bool supportsJSButton(void) const;
bool supportsCalibratePressure(void) const;
bool supportsMotorInterference(void) const;
void setGuidedMode(bool guidedMode);

Loading…
Cancel
Save