ParameterLoader.h 6.76 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 43

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

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

/// 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
53
    ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL);
54 55
    
    ~ParameterLoader();
56

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

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

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

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

    /// 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);
104 105
    
protected:
106 107 108
    AutoPilotPlugin*    _autopilot;
    Vehicle*            _vehicle;
    MAVLinkProtocol*    _mavlink;
109
    
110
    void _parameterUpdate(int uasId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value);
111
    void _valueUpdated(const QVariant& value);
112 113
    void _restartWaitingParamTimer(void);
    void _waitingParamTimeout(void);
114
    void _tryCacheLookup(void);
115
    void _initialRequestTimeout(void);
dogmaphobic's avatar
dogmaphobic committed
116

117 118 119 120
private:
    static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false);
    int _actualComponentId(int componentId);
    void _determineDefaultComponentId(void);
121
    void _setupGroupMap(void);
122 123
    void _readParameterRaw(int componentId, const QString& paramName, int paramIndex);
    void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value);
124 125
    void _writeLocalParamCache(int uasId, int componentId);
    void _tryCacheHashLoad(int uasId, int componentId, QVariant hash_value);
126

127 128 129
    MAV_PARAM_TYPE _factTypeToMavType(FactMetaData::ValueType_t factType);
    FactMetaData::ValueType_t _mavTypeToFactType(MAV_PARAM_TYPE mavType);
    void _saveToEEPROM(void);
130
    void _checkInitialLoadComplete(void);
131 132

    LinkInterface* _dedicatedLink; ///< Parameter protocol stays on this link
133
    
134
    /// First mapping is by component id
135
    /// Second mapping is parameter name, to Fact* in QVariant
136 137
    QMap<int, QVariantMap>            _mapParameterName2Variant;
    QMap<int, QMap<int, QString> >    _mapParameterId2Name;
138
    
139 140 141 142
    /// First mapping is by component id
    /// Second mapping is group name, to Fact
    QMap<int, QMap<QString, QStringList> > _mapGroup2ParameterName;
    
143 144
    bool _parametersReady;      ///< true: full set of parameters correctly loaded
    bool _initialLoadComplete;  ///< true: Initial load of all parameters complete, whether succesful or not
145
    bool _saveRequired;         ///< true: _saveToEEPROM should be called
146 147
    int _defaultComponentId;
    QString _defaultComponentIdParam;
148
    
149
    static const int _maxInitialLoadRetry = 10;                  ///< Maximum a retries on initial index based load
150 151 152 153 154 155
    
    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
156 157 158
    
    int _totalParamCount;   ///< Number of parameters across all components
    
159
    QTimer _initialRequestTimeoutTimer;
160 161 162
    QTimer _waitingParamTimeoutTimer;
    
    QMutex _dataMutex;
Don Gagne's avatar
Don Gagne committed
163 164
    
    static Fact _defaultFact;   ///< Used to return default fact, when parameter not found
165 166
};

167
#endif