ParameterLoader.h 7.94 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30
/*=====================================================================
 
 QGroundControl Open Source Ground Control Station
 
 (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 
 This file is part of the QGROUNDCONTROL project
 
 QGROUNDCONTROL is free software: you can redistribute it and/or modify
 it under the terms of the GNU General Public License as published by
 the Free Software Foundation, either version 3 of the License, or
 (at your option) any later version.
 
 QGROUNDCONTROL is distributed in the hope that it will be useful,
 but WITHOUT ANY WARRANTY; without even the implied warranty of
 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 GNU General Public License for more details.
 
 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
 
 ======================================================================*/

#ifndef PARAMETERLOADER_H
#define PARAMETERLOADER_H

#include <QObject>
#include <QMap>
#include <QXmlStreamReader>
#include <QLoggingCategory>
31
#include <QMutex>
Don Gagne's avatar
Don Gagne committed
32
#include <QDir>
33 34

#include "FactSystem.h"
35 36
#include "MAVLinkProtocol.h"
#include "AutoPilotPlugin.h"
37
#include "QGCMAVLink.h"
38
#include "Vehicle.h"
39 40 41 42

/// @file
///     @author Don Gagne <don@thegagnes.com>

43
Q_DECLARE_LOGGING_CATEGORY(ParameterLoaderVerboseLog)
44 45 46 47 48 49 50 51

/// Connects to Parameter Manager to load/update Facts
class ParameterLoader : public QObject
{
    Q_OBJECT
    
public:
    /// @param uas Uas which this set of facts is associated with
52
    ParameterLoader(Vehicle* vehicle);
53 54
    
    ~ParameterLoader();
55

56 57 58
    /// @return Directory of parameter caches
    static QDir parameterCacheDir();

59
    /// @return Location of parameter cache file
60
    static QString parameterCacheFile(int uasId, int componentId);
61 62 63
    
    /// Returns true if the full set of facts are ready
    bool parametersAreReady(void) { return _parametersReady; }
64

65
    /// Re-request the full set of parameters from the autopilot
dogmaphobic's avatar
dogmaphobic committed
66
    void refreshAllParameters(uint8_t componentID = MAV_COMP_ID_ALL);
67

68 69 70 71 72 73
    /// 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);
    
74 75 76 77 78
    /// Returns true if the specifed parameter exists
    bool parameterExists(int			componentId,    ///< fact component, -1=default component
						 const QString& name);          ///< fact name
	
	/// Returns all parameter names
Don Gagne's avatar
Don Gagne committed
79
	QStringList parameterNames(int componentId);
80 81
    
    /// Returns the specified Fact.
nopeppermint's avatar
nopeppermint committed
82
    /// WARNING: Will assert if parameter does not exists. If that possibily exists, check for existence first with
83
    /// parameterExists.
84 85 86
    Fact* getFact(int               componentId,    ///< fact component, -1=default component
                  const QString&    name);          ///< fact name
    
87 88
    const QMap<int, QMap<QString, QStringList> >& getGroupMap(void);
    
89 90 91
    /// Returns error messages from loading
    QString readParametersFromStream(QTextStream& stream);
    
92
    void writeParametersToStream(QTextStream &stream);
93 94 95 96 97 98 99 100 101 102 103 104 105

    /// 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
    static QString parameterMetaDataFile(MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion);

    /// 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);
106 107 108
    
signals:
    /// Signalled when the full set of facts are ready
109
    void parametersReady(bool missingParameters);
110 111 112 113 114 115

    /// Signalled to update progress of full parameter list request
    void parameterListProgress(float value);
    
    /// Signalled to ourselves in order to get call on our own thread
    void restartWaitingParamTimer(void);
116 117
    
protected:
118 119
    Vehicle*            _vehicle;
    MAVLinkProtocol*    _mavlink;
120
    
121
    void _parameterUpdate(int uasId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value);
122
    void _valueUpdated(const QVariant& value);
123 124
    void _restartWaitingParamTimer(void);
    void _waitingParamTimeout(void);
125
    void _tryCacheLookup(void);
126
    void _initialRequestTimeout(void);
dogmaphobic's avatar
dogmaphobic committed
127

128 129 130 131
private:
    static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false);
    int _actualComponentId(int componentId);
    void _determineDefaultComponentId(void);
132
    void _setupGroupMap(void);
133 134
    void _readParameterRaw(int componentId, const QString& paramName, int paramIndex);
    void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value);
135 136
    void _writeLocalParamCache(int uasId, int componentId);
    void _tryCacheHashLoad(int uasId, int componentId, QVariant hash_value);
137
    void _addMetaDataToAll(void);
138

139 140 141
    MAV_PARAM_TYPE _factTypeToMavType(FactMetaData::ValueType_t factType);
    FactMetaData::ValueType_t _mavTypeToFactType(MAV_PARAM_TYPE mavType);
    void _saveToEEPROM(void);
142
    void _checkInitialLoadComplete(void);
143 144

    LinkInterface* _dedicatedLink; ///< Parameter protocol stays on this link
145
    
146
    /// First mapping is by component id
147
    /// Second mapping is parameter name, to Fact* in QVariant
148
    QMap<int, QVariantMap>            _mapParameterName2Variant;
149

150
    QMap<int, QMap<int, QString> >    _mapParameterId2Name;
151
    
152 153 154 155
    /// First mapping is by component id
    /// Second mapping is group name, to Fact
    QMap<int, QMap<QString, QStringList> > _mapGroup2ParameterName;
    
156 157 158 159 160 161 162 163 164
    bool        _parametersReady;           ///< true: full set of parameters correctly loaded
    bool        _initialLoadComplete;       ///< true: Initial load of all parameters complete, whether succesful or not
    bool        _saveRequired;              ///< true: _saveToEEPROM should be called
    int         _defaultComponentId;
    QString     _defaultComponentIdParam;   ///< Parameter which identifies default component
    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

165
    static const int _maxInitialLoadRetry = 10;                  ///< Maximum a retries on initial index based load
166 167 168 169 170 171
    
    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
172 173 174
    
    int _totalParamCount;   ///< Number of parameters across all components
    
175
    QTimer _initialRequestTimeoutTimer;
176 177 178
    QTimer _waitingParamTimeoutTimer;
    
    QMutex _dataMutex;
Don Gagne's avatar
Don Gagne committed
179 180
    
    static Fact _defaultFact;   ///< Used to return default fact, when parameter not found
181 182

    static const char* _cachedMetaDataFilePrefix;
183 184
};

185
#endif