ParameterManager.h 10.7 KB
Newer Older
1 2 3 4 5 6 7 8 9
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

10
#pragma once
11 12 13 14 15

#include <QObject>
#include <QMap>
#include <QXmlStreamReader>
#include <QLoggingCategory>
16
#include <QMutex>
Don Gagne's avatar
Don Gagne committed
17
#include <QDir>
18
#include <QJsonObject>
19 20

#include "FactSystem.h"
21 22
#include "MAVLinkProtocol.h"
#include "AutoPilotPlugin.h"
23
#include "QGCMAVLink.h"
24
#include "Vehicle.h"
25

26 27
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose1Log)
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose2Log)
28
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerDebugCacheFailureLog)
29

30
class ParameterManager : public QObject
31 32 33 34 35
{
    Q_OBJECT
    
public:
    /// @param uas Uas which this set of facts is associated with
36 37
    ParameterManager    (Vehicle* vehicle);
    ~ParameterManager   ();
38

39 40 41
    Q_PROPERTY(bool     parametersReady     READ parametersReady    NOTIFY parametersReadyChanged)      ///< true: Parameters are ready for use
    Q_PROPERTY(bool     missingParameters   READ missingParameters  NOTIFY missingParametersChanged)    ///< true: Parameters are missing from firmware response, false: all parameters received from firmware
    Q_PROPERTY(double   loadProgress        READ loadProgress       NOTIFY loadProgressChanged)
42

43 44 45
    bool parametersReady    (void) const { return _parametersReady; }
    bool missingParameters  (void) const { return _missingParameters; }
    double loadProgress     (void) const { return _loadProgress; }
46

47 48 49
    /// @return Directory of parameter caches
    static QDir parameterCacheDir();

50
    /// @return Location of parameter cache file
51
    static QString parameterCacheFile(int vehicleId, int componentId);
Don Gagne's avatar
Don Gagne committed
52 53

    QList<int> componentIds(void);
54 55
    
    /// Re-request the full set of parameters from the autopilot
dogmaphobic's avatar
dogmaphobic committed
56
    void refreshAllParameters(uint8_t componentID = MAV_COMP_ID_ALL);
57

58 59 60 61 62 63
    /// Request a refresh on the specific parameter
    void refreshParameter(int componentId, const QString& name);
    
    /// Request a refresh on all parameters that begin with the specified prefix
    void refreshParametersPrefix(int componentId, const QString& namePrefix);
    
64 65
    void resetAllParametersToDefaults(void);

66
    /// Returns true if the specifed parameter exists
67 68 69 70
    ///     @param componentId Component id or FactSystem::defaultComponentId
    ///     @param name Parameter name
    bool parameterExists(int componentId, const QString& name);

71
	/// Returns all parameter names
Don Gagne's avatar
Don Gagne committed
72
	QStringList parameterNames(int componentId);
73
    
74 75 76 77 78
    /// Returns the specified Parameter. Returns a default empty fact is parameter does not exists. Also will pop
    /// a missing parameter error to user if parameter does not exist.
    ///     @param componentId Component id or FactSystem::defaultComponentId
    ///     @param name Parameter name
    Fact* getParameter(int componentId, const QString& name);
79
    
Don Gagne's avatar
Don Gagne committed
80
    const QMap<QString, QMap<QString, QStringList> >& getDefaultComponentCategoryMap(void);
81
    
82 83 84
    /// Returns error messages from loading
    QString readParametersFromStream(QTextStream& stream);
    
85
    void writeParametersToStream(QTextStream &stream);
86 87 88 89 90 91 92 93 94

    /// Returns the version number for the parameter set, -1 if not known
    int parameterSetVersion(void) { return _parameterSetMajorVersion; }

    /// Returns the newest available parameter meta data file (from cache or internal) for the specified information.
    ///     @param wantedMajorVersion Major version you are looking for
    ///     @param[out] majorVersion Major version for found meta data
    ///     @param[out] minorVersion Minor version for found meta data
    /// @return Meta data file name of best match, emptyString is none found
95
    static QString parameterMetaDataFile(Vehicle* vehicle, MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion);
96 97 98

    /// If this file is newer than anything in the cache, cache it as the latest version
    static void cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType);
Don Gagne's avatar
Don Gagne committed
99

100 101 102 103 104 105 106 107 108 109 110 111 112
    /// Saves the specified param set to the json object.
    ///     @param componentId Component id which contains params, MAV_COMP_ID_ALL to save all components
    ///     @param paramsToSave List of params names to save, empty to save all for component
    ///     @param saveObject Json object to save to
    void saveToJson(int componentId, const QStringList& paramsToSave, QJsonObject& saveObject);

    /// Load a parameter set from json
    ///     @param json Json object to load from
    ///     @param required true: no parameters in object will generate error
    ///     @param errorString Error string if return is false
    /// @return true: success, false: failure (errorString set)
    bool loadFromJson(const QJsonObject& json, bool required, QString& errorString);

113 114
    Vehicle* vehicle(void) { return _vehicle; }

115
signals:
116 117
    void parametersReadyChanged(bool parametersReady);
    void missingParametersChanged(bool missingParameters);
118
    void loadProgressChanged(float value);
119 120
    
protected:
121 122
    Vehicle*            _vehicle;
    MAVLinkProtocol*    _mavlink;
123
    
124
    void _parameterUpdate(int vehicleId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value);
125
    void _valueUpdated(const QVariant& value);
126
    void _waitingParamTimeout(void);
127
    void _tryCacheLookup(void);
128
    void _initialRequestTimeout(void);
dogmaphobic's avatar
dogmaphobic committed
129

130 131 132
private:
    static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false);
    int _actualComponentId(int componentId);
Don Gagne's avatar
Don Gagne committed
133
    void _setupDefaultComponentCategoryMap(void);
134 135
    void _readParameterRaw(int componentId, const QString& paramName, int paramIndex);
    void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value);
136 137
    void _writeLocalParamCache(int vehicleId, int componentId);
    void _tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value);
138 139
    void _loadMetaData(void);
    void _clearMetaData(void);
140
    void _addMetaDataToDefaultComponent(void);
141
    QString _remapParamNameToVersion(const QString& paramName);
142
    void _loadOfflineEditingParams(void);
143
    QString _logVehiclePrefix(int componentId);
144
    void _setLoadProgress(double loadProgress);
145
    bool _fillIndexBatchQueue(bool waitingParamTimeout);
146

147 148
    MAV_PARAM_TYPE _factTypeToMavType(FactMetaData::ValueType_t factType);
    FactMetaData::ValueType_t _mavTypeToFactType(MAV_PARAM_TYPE mavType);
149
    void _checkInitialLoadComplete(void);
150

151
    /// First mapping is by component id
152
    /// Second mapping is parameter name, to Fact* in QVariant
153
    QMap<int, QVariantMap>            _mapParameterName2Variant;
154

155
    // Category map of default component parameters
Don Gagne's avatar
Don Gagne committed
156
    QMap<QString /* category */, QMap<QString /* group */, QStringList /* parameter names */> > _defaultComponentCategoryMap;
157
    
158
    double      _loadProgress;                  ///< Parameter load progess, [0.0,1.0]
159 160
    bool        _parametersReady;               ///< true: parameter load complete
    bool        _missingParameters;             ///< true: parameter missing from initial load
Ricardo de Almeida Gonzaga's avatar
Ricardo de Almeida Gonzaga committed
161
    bool        _initialLoadComplete;           ///< true: Initial load of all parameters complete, whether successful or not
162 163
    bool        _waitingForDefaultComponent;    ///< true: last chance wait for default component params
    bool        _saveRequired;                  ///< true: _saveToEEPROM should be called
164
    bool        _metaDataAddedToFacts;          ///< true: FactMetaData has been adde to the default component facts
Don Gagne's avatar
Don Gagne committed
165
    bool        _logReplay;                     ///< true: running with log replay link
166 167 168
    QString     _versionParam;                  ///< Parameter which contains parameter set version
    int         _parameterSetMajorVersion;      ///< Version for parameter set, -1 if not known
    QObject*    _parameterMetaData;             ///< Opaque data from FirmwarePlugin::loadParameterMetaDataCall
169

170 171 172 173 174 175 176
    typedef QPair<int /* FactMetaData::ValueType_t */, QVariant /* Fact::rawValue */> ParamTypeVal;
    typedef QMap<QString /* parameter name */, ParamTypeVal> CacheMapName2ParamTypeVal;

    QMap<int /* component id */, bool>                                              _debugCacheCRC; ///< true: debug cache crc failure
    QMap<int /* component id */, CacheMapName2ParamTypeVal>                         _debugCacheMap;
    QMap<int /* component id */, QMap<QString /* param name */, bool /* seen */>>   _debugCacheParamSeen;

Don Gagne's avatar
Don Gagne committed
177 178 179 180 181
    // Wait counts from previous parameter update cycle
    int         _prevWaitingReadParamIndexCount;
    int         _prevWaitingReadParamNameCount;
    int         _prevWaitingWriteParamNameCount;

182 183 184 185 186
    static const int    _maxInitialRequestListRetry = 4;        ///< Maximum retries for request list
    int                 _initialRequestRetryCount;              ///< Current retry count for request list
    static const int    _maxInitialLoadRetrySingleParam = 5;    ///< Maximum retries for initial index based load of a single param
    static const int    _maxReadWriteRetry = 5;                 ///< Maximum retries read/write
    bool                _disableAllRetries;                     ///< true: Don't retry any requests (used for testing)
187

188 189 190
    bool        _indexBatchQueueActive; ///< true: we are actively batching re-requests for missing index base params, false: index based re-request has not yet started
    QList<int>  _indexBatchQueue;       ///< The current queue of index re-requests

191 192 193 194 195
    QMap<int, int>                  _paramCountMap;             ///< Key: Component id, Value: count of parameters in this component
    QMap<int, QMap<int, int> >      _waitingReadParamIndexMap;  ///< Key: Component id, Value: Map { Key: parameter index still waiting for, Value: retry count }
    QMap<int, QMap<QString, int> >  _waitingReadParamNameMap;   ///< Key: Component id, Value: Map { Key: parameter name still waiting for, Value: retry count }
    QMap<int, QMap<QString, int> >  _waitingWriteParamNameMap;  ///< Key: Component id, Value: Map { Key: parameter name still waiting for, Value: retry count }
    QMap<int, QList<int> >          _failedReadParamIndexMap;   ///< Key: Component id, Value: failed parameter index
196

197 198
    int _totalParamCount;   ///< Number of parameters across all components
    
199
    QTimer _initialRequestTimeoutTimer;
200 201 202
    QTimer _waitingParamTimeoutTimer;
    
    QMutex _dataMutex;
Don Gagne's avatar
Don Gagne committed
203
    
204
    Fact _defaultFact;   ///< Used to return default fact, when parameter not found
205 206

    static const char* _cachedMetaDataFilePrefix;
207 208 209 210
    static const char* _jsonParametersKey;
    static const char* _jsonCompIdKey;
    static const char* _jsonParamNameKey;
    static const char* _jsonParamValueKey;
211
};