ParameterManager.h 10.4 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8 9
 *
 * 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
{
    Q_OBJECT
33

34 35
public:
    /// @param uas Uas which this set of facts is associated with
36
    ParameterManager(Vehicle* vehicle);
37

38 39 40
    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)
41
    Q_PROPERTY(bool     pendingWrites       READ pendingWrites      NOTIFY pendingWritesChanged)        ///< true: There are still pending write updates against the vehicle
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
    /// Request a refresh on the specific parameter
59
    void refreshParameter(int componentId, const QString& paramName);
60

61 62
    /// Request a refresh on all parameters that begin with the specified prefix
    void refreshParametersPrefix(int componentId, const QString& namePrefix);
63 64 65

    void resetAllParametersToDefaults();
    void resetAllToVehicleConfiguration();
66

67
    /// Returns true if the specifed parameter exists
Gus Grubba's avatar
Gus Grubba committed
68 69
    ///     @param componentId: Component id or FactSystem::defaultComponentId
    ///     @param name: Parameter name
70
    bool parameterExists(int componentId, const QString& paramName);
71

72 73 74
    /// Returns all parameter names
    QStringList parameterNames(int componentId);

75 76
    /// 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.
Gus Grubba's avatar
Gus Grubba committed
77 78
    ///     @param componentId: Component id or FactSystem::defaultComponentId
    ///     @param name: Parameter name
79
    Fact* getParameter(int componentId, const QString& paramName);
80

81 82 83
    int  getComponentId(const QString& category);
    QString getComponentCategory(int componentId);
    const QMap<QString, QMap<QString, QStringList> >& getComponentCategoryMap(int componentId);
84

85 86
    /// Returns error messages from loading
    QString readParametersFromStream(QTextStream& stream);
87

88
    void writeParametersToStream(QTextStream& stream);
89 90 91 92

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

93 94
    bool pendingWrites(void);

95 96
    Vehicle* vehicle(void) { return _vehicle; }

97
signals:
98 99 100 101
    void parametersReadyChanged     (bool parametersReady);
    void missingParametersChanged   (bool missingParameters);
    void loadProgressChanged        (float value);
    void pendingWritesChanged       (bool pendingWrites);
102

103
protected:
104 105
    Vehicle*            _vehicle;
    MAVLinkProtocol*    _mavlink;
106

107 108 109 110 111
    void _parameterUpdate       (int vehicleId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value);
    void _valueUpdated          (const QVariant& value);
    void _waitingParamTimeout   (void);
    void _tryCacheLookup        (void);
    void _initialRequestTimeout (void);
dogmaphobic's avatar
dogmaphobic committed
112

113
private:
114
    static QVariant         _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false);
115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131

    int     _actualComponentId                  (int componentId);
    void    _setupComponentCategoryMap          (int componentId);
    void    _setupDefaultComponentCategoryMap   (void);
    void    _readParameterRaw                   (int componentId, const QString& paramName, int paramIndex);
    void    _writeParameterRaw                  (int componentId, const QString& paramName, const QVariant& value);
    void    _writeLocalParamCache               (int vehicleId, int componentId);
    void    _tryCacheHashLoad                   (int vehicleId, int componentId, QVariant hash_value);
    void    _loadMetaData                       (void);
    void    _clearMetaData                      (void);
    void    _addMetaDataToDefaultComponent      (void);
    QString _remapParamNameToVersion            (const QString& paramName);
    void    _loadOfflineEditingParams           (void);
    QString _logVehiclePrefix                   (int componentId);
    void    _setLoadProgress                    (double loadProgress);
    bool    _fillIndexBatchQueue                (bool waitingParamTimeout);
    void    _updateProgressBar                  (void);
132

133 134
    MAV_PARAM_TYPE _factTypeToMavType(FactMetaData::ValueType_t factType);
    FactMetaData::ValueType_t _mavTypeToFactType(MAV_PARAM_TYPE mavType);
135
    void _checkInitialLoadComplete(void);
136

137
    /// First mapping is by component id
138
    /// Second mapping is parameter name, to Fact* in QVariant
139
    QMap<int, QVariantMap>            _mapParameterName2Variant;
140

141 142 143 144
    // List of category map of component parameters
    typedef QMap<QString, QMap<QString, QStringList>>   ComponentCategoryMapType; //<Key: category, Value: Map< Key: group, Value: parameter names list >>
    QMap<int, ComponentCategoryMapType>                 _componentCategoryMaps;
    QHash<QString, int>                                 _componentCategoryHash;
145

146
    double      _loadProgress;                  ///< Parameter load progess, [0.0,1.0]
147 148
    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
149
    bool        _initialLoadComplete;           ///< true: Initial load of all parameters complete, whether successful or not
150 151
    bool        _waitingForDefaultComponent;    ///< true: last chance wait for default component params
    bool        _saveRequired;                  ///< true: _saveToEEPROM should be called
152
    bool        _metaDataAddedToFacts;          ///< true: FactMetaData has been adde to the default component facts
Don Gagne's avatar
Don Gagne committed
153
    bool        _logReplay;                     ///< true: running with log replay link
154 155
    QString     _versionParam;                  ///< Parameter which contains parameter set version
    int         _parameterSetMajorVersion;      ///< Version for parameter set, -1 if not known
156

157 158 159 160 161 162 163
    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
164
    // Wait counts from previous parameter update cycle
165 166 167 168 169 170 171
    int _prevWaitingReadParamIndexCount;
    int _prevWaitingReadParamNameCount;
    int _prevWaitingWriteParamNameCount;

    bool _readParamIndexProgressActive =    false;
    bool _readParamNameProgressActive =     false;
    bool _writeParamProgressActive =        false;
Don Gagne's avatar
Don Gagne committed
172

173 174 175 176 177
    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)
178

179 180 181
    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

182 183 184 185 186
    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
187

188 189 190
    int _totalParamCount;                       ///< Number of parameters across all components
    int _waitingWriteParamBatchCount = 0;       ///< Number of parameters which are batched up waiting on write responses
    int _waitingReadParamNameBatchCount = 0;    ///< Number of parameters which are batched up waiting on read responses
191

192
    QTimer _initialRequestTimeoutTimer;
193
    QTimer _waitingParamTimeoutTimer;
194

195
    QMutex _dataMutex;
196

197
    Fact _defaultFact;   ///< Used to return default fact, when parameter not found
198

199 200 201 202
    static const char* _jsonParametersKey;
    static const char* _jsonCompIdKey;
    static const char* _jsonParamNameKey;
    static const char* _jsonParamValueKey;
203
};