Unverified Commit 77863043 authored by Gus Grubba's avatar Gus Grubba Committed by GitHub

Merge pull request #6079 from mavlink/pr-plugin-control

Finer control for plugins
parents 67118103 0790eb2a
...@@ -202,16 +202,16 @@ protected: ...@@ -202,16 +202,16 @@ protected:
virtual void _setCameraMode (CameraMode mode); virtual void _setCameraMode (CameraMode mode);
protected slots: protected slots:
void _initWhenReady (); virtual void _initWhenReady ();
void _requestCameraSettings (); virtual void _requestCameraSettings ();
void _requestAllParameters (); virtual void _requestAllParameters ();
void _requestParamUpdates (); virtual void _requestParamUpdates ();
void _requestCaptureStatus (); virtual void _requestCaptureStatus ();
void _requestStorageInfo (); virtual void _requestStorageInfo ();
void _downloadFinished (); virtual void _downloadFinished ();
void _mavCommandResult (int vehicleId, int component, int command, int result, bool noReponseFromVehicle); virtual void _mavCommandResult (int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
void _dataReady (QByteArray data); virtual void _dataReady (QByteArray data);
void _paramDone (); virtual void _paramDone ();
private: private:
bool _handleLocalization (QByteArray& bytes); bool _handleLocalization (QByteArray& bytes);
......
...@@ -34,19 +34,19 @@ signals: ...@@ -34,19 +34,19 @@ signals:
void camerasChanged (); void camerasChanged ();
protected slots: protected slots:
void _vehicleReady (bool ready); virtual void _vehicleReady (bool ready);
void _mavlinkMessageReceived (const mavlink_message_t& message); virtual void _mavlinkMessageReceived (const mavlink_message_t& message);
protected: protected:
QGCCameraControl* _findCamera (int id); virtual QGCCameraControl* _findCamera (int id);
void _requestCameraInfo (int compID); virtual void _requestCameraInfo (int compID);
void _handleHeartbeat (const mavlink_message_t& message); virtual void _handleHeartbeat (const mavlink_message_t& message);
void _handleCameraInfo (const mavlink_message_t& message); virtual void _handleCameraInfo (const mavlink_message_t& message);
void _handleStorageInfo (const mavlink_message_t& message); virtual void _handleStorageInfo (const mavlink_message_t& message);
void _handleCameraSettings (const mavlink_message_t& message); virtual void _handleCameraSettings (const mavlink_message_t& message);
void _handleParamAck (const mavlink_message_t& message); virtual void _handleParamAck (const mavlink_message_t& message);
void _handleParamValue (const mavlink_message_t& message); virtual void _handleParamValue (const mavlink_message_t& message);
void _handleCaptureStatus (const mavlink_message_t& message); virtual void _handleCaptureStatus (const mavlink_message_t& message);
protected: protected:
Vehicle* _vehicle; Vehicle* _vehicle;
......
...@@ -345,6 +345,22 @@ void PlanMasterController::loadFromFile(const QString& filename) ...@@ -345,6 +345,22 @@ void PlanMasterController::loadFromFile(const QString& filename)
} }
} }
QJsonDocument PlanMasterController::saveToJson()
{
QJsonObject planJson;
QJsonObject missionJson;
QJsonObject fenceJson;
QJsonObject rallyJson;
JsonHelper::saveQGCJsonFileHeader(planJson, _planFileType, _planFileVersion);
_missionController.save(missionJson);
_geoFenceController.save(fenceJson);
_rallyPointController.save(rallyJson);
planJson[_jsonMissionObjectKey] = missionJson;
planJson[_jsonGeoFenceObjectKey] = fenceJson;
planJson[_jsonRallyPointsObjectKey] = rallyJson;
return QJsonDocument(planJson);
}
void PlanMasterController::saveToFile(const QString& filename) void PlanMasterController::saveToFile(const QString& filename)
{ {
if (filename.isEmpty()) { if (filename.isEmpty()) {
...@@ -361,20 +377,7 @@ void PlanMasterController::saveToFile(const QString& filename) ...@@ -361,20 +377,7 @@ void PlanMasterController::saveToFile(const QString& filename)
if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) { if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
qgcApp()->showMessage(tr("Plan save error %1 : %2").arg(filename).arg(file.errorString())); qgcApp()->showMessage(tr("Plan save error %1 : %2").arg(filename).arg(file.errorString()));
} else { } else {
QJsonObject planJson; QJsonDocument saveDoc = saveToJson();
QJsonObject missionJson;
QJsonObject fenceJson;
QJsonObject rallyJson;
JsonHelper::saveQGCJsonFileHeader(planJson, _planFileType, _planFileVersion);
_missionController.save(missionJson);
_geoFenceController.save(fenceJson);
_rallyPointController.save(rallyJson);
planJson[_jsonMissionObjectKey] = missionJson;
planJson[_jsonGeoFenceObjectKey] = fenceJson;
planJson[_jsonRallyPointsObjectKey] = rallyJson;
QJsonDocument saveDoc(planJson);
file.write(saveDoc.toJson()); file.write(saveDoc.toJson());
} }
......
...@@ -80,6 +80,8 @@ public: ...@@ -80,6 +80,8 @@ public:
QStringList saveNameFilters (void) const; QStringList saveNameFilters (void) const;
QStringList saveKmlFilters (void) const; QStringList saveKmlFilters (void) const;
QJsonDocument saveToJson ();
Vehicle* controllerVehicle(void) { return _controllerVehicle; } Vehicle* controllerVehicle(void) { return _controllerVehicle; }
Vehicle* managerVehicle(void) { return _managerVehicle; } Vehicle* managerVehicle(void) { return _managerVehicle; }
......
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