Commit d9c2a2aa authored by Don Gagne's avatar Don Gagne

Add resetAllParameterToDefaults api

parent d63457c5
...@@ -97,6 +97,15 @@ bool AutoPilotPlugin::setupComplete(void) ...@@ -97,6 +97,15 @@ bool AutoPilotPlugin::setupComplete(void)
return _setupComplete; return _setupComplete;
} }
void AutoPilotPlugin::resetAllParametersToDefaults(void)
{
mavlink_message_t msg;
MAVLinkProtocol* mavlink = MAVLinkProtocol::instance();
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _uas->getUASID(), 0, MAV_CMD_PREFLIGHT_STORAGE, 0, 2, -1, 0, 0, 0, 0, 0);
_uas->sendMessage(msg);
}
void AutoPilotPlugin::refreshAllParameters(void) void AutoPilotPlugin::refreshAllParameters(void)
{ {
_getParameterLoader()->refreshAllParameters(); _getParameterLoader()->refreshAllParameters();
......
...@@ -63,6 +63,9 @@ public: ...@@ -63,6 +63,9 @@ public:
Q_PROPERTY(bool setupComplete READ setupComplete NOTIFY setupCompleteChanged) Q_PROPERTY(bool setupComplete READ setupComplete NOTIFY setupCompleteChanged)
Q_PROPERTY(bool armed READ armed NOTIFY armedChanged) Q_PROPERTY(bool armed READ armed NOTIFY armedChanged)
/// Reset all parameters to their default values
Q_INVOKABLE void resetAllParametersToDefaults(void);
/// Re-request the full set of parameters from the autopilot /// Re-request the full set of parameters from the autopilot
Q_INVOKABLE void refreshAllParameters(void); Q_INVOKABLE void refreshAllParameters(void);
......
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