Skip to content

Commit

Permalink
Simple factory calibration button implemented in QGC.
Browse files Browse the repository at this point in the history
  • Loading branch information
batinkov authored and bkueng committed Oct 7, 2021
1 parent a86d14c commit 377293f
Show file tree
Hide file tree
Showing 5 changed files with 51 additions and 0 deletions.
27 changes: 27 additions & 0 deletions src/AutoPilotPlugins/PX4/SensorsComponentController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,8 @@ SensorsComponentController::SensorsComponentController(void)
, _unknownFirmwareVersion (false)
, _waitingForCancel (false)
{
connect(_vehicle, &Vehicle::sensorsParametersResetAck, this, &SensorsComponentController::_handleParametersReset);

}

bool SensorsComponentController::usingUDPLink(void)
Expand Down Expand Up @@ -493,3 +495,28 @@ void SensorsComponentController::cancelCalibration(void)
_cancelButton->setEnabled(false);
_vehicle->stopCalibration();
}

void SensorsComponentController::_handleParametersReset(bool success)
{
if (success) {
qgcApp()->showAppMessage(tr("Reset successful"));

QTimer::singleShot(1000, this, [this]() {
_refreshParams();
});
}
else {
qgcApp()->showAppMessage(tr("Reset failed"));
}
}

void SensorsComponentController::resetFactoryParameters()
{
auto compId = _vehicle->defaultComponentId();

_vehicle->sendMavCommand(compId,
MAV_CMD_PREFLIGHT_STORAGE,
true, // showError
3, // Reset factory parameters
-1); // Don't do anything with mission storage
}
2 changes: 2 additions & 0 deletions src/AutoPilotPlugins/PX4/SensorsComponentController.h
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,7 @@ class SensorsComponentController : public FactPanelController
Q_INVOKABLE void calibrateAirspeed(void);
Q_INVOKABLE void cancelCalibration(void);
Q_INVOKABLE bool usingUDPLink(void);
Q_INVOKABLE void resetFactoryParameters();

signals:
void showGyroCalAreaChanged(void);
Expand All @@ -96,6 +97,7 @@ class SensorsComponentController : public FactPanelController

private slots:
void _handleUASTextMessage(int uasId, int compId, int severity, QString text);
void _handleParametersReset(bool success);

private:
void _startLogCalibration(void);
Expand Down
15 changes: 15 additions & 0 deletions src/AutoPilotPlugins/PX4/SensorsSetup.qml
Original file line number Diff line number Diff line change
Expand Up @@ -623,6 +623,21 @@ Item {
}
}
}

QGCButton {
text: qsTr("Factory reset")
width: _buttonWidth

anchors {
right: orientationCalArea.left
rightMargin: ScreenTools.defaultFontPixelWidth/2
bottom: orientationCalArea.bottom
}

onClicked: {
controller.resetFactoryParameters()
}
}
}
}
}
5 changes: 5 additions & 0 deletions src/Vehicle/Vehicle.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2984,6 +2984,11 @@ void Vehicle::_handleCommandAck(mavlink_message_t& message)
}
}

if (ack.command == MAV_CMD_PREFLIGHT_STORAGE) {
auto result = (ack.result == MAV_RESULT_ACCEPTED);
emit sensorsParametersResetAck(result);
}

#if !defined(NO_ARDUPILOT_DIALECT)
if (ack.command == MAV_CMD_FLASH_BOOTLOADER && ack.result == MAV_RESULT_ACCEPTED) {
qgcApp()->showAppMessage(tr("Bootloader flash succeeded"));
Expand Down
2 changes: 2 additions & 0 deletions src/Vehicle/Vehicle.h
Original file line number Diff line number Diff line change
Expand Up @@ -930,6 +930,8 @@ public slots:
void isROIEnabledChanged ();
void initialConnectComplete ();

void sensorsParametersResetAck (bool success);

private slots:
void _mavlinkMessageReceived (LinkInterface* link, mavlink_message_t message);
void _sendMessageMultipleNext ();
Expand Down

0 comments on commit 377293f

Please sign in to comment.