UASParameterCommsMgr.h 4.31 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12
#ifndef UASPARAMETERCOMMSMGR_H
#define UASPARAMETERCOMMSMGR_H

#include <QObject>
#include <QMap>
#include <QTimer>
#include <QVariant>
#include <QVector>

class UASInterface;
class UASParameterDataModel;

tstellanova's avatar
tstellanova committed
13 14


15 16 17
class UASParameterCommsMgr : public QObject
{
    Q_OBJECT
tstellanova's avatar
tstellanova committed
18 19


20 21
public:
    explicit UASParameterCommsMgr(QObject *parent = 0, UASInterface* uas = NULL);
22 23
    ~UASParameterCommsMgr();

tstellanova's avatar
tstellanova committed
24 25 26 27 28 29 30
    typedef enum ParamCommsStatusLevel {
        ParamCommsStatusLevel_OK = 0,
        ParamCommsStatusLevel_Warning = 2,
        ParamCommsStatusLevel_Error = 4,
        ParamCommsStatusLevel_Count
    } ParamCommsStatusLevel_t;

31 32 33 34 35

protected:
    /** @brief Activate / deactivate parameter retransmission */
    virtual void setRetransmissionGuardEnabled(bool enabled);

tstellanova's avatar
tstellanova committed
36 37 38 39
    virtual void setParameterStatusMsg(const QString& msg, ParamCommsStatusLevel_t level=ParamCommsStatusLevel_OK);

    /** @brief Load settings that control eg retransmission timeouts */
    void loadParamCommsSettings();
40

41 42 43 44 45 46 47
    /** @brief clear transmissionMissingPackets and transmissionMissingWriteAckPackets */
    void clearRetransmissionLists();

    void resendReadWriteRequests();

    void emitParameterChanged(int compId, const QString& key, QVariant& value);

48 49 50
signals:
    void parameterChanged(int component, QString parameter, QVariant value);
    void parameterChanged(int component, int parameterIndex, QVariant value);
tstellanova's avatar
tstellanova committed
51
    void parameterValueConfirmed(int uas, int component,int paramCount, int paramId, QString parameter, QVariant value);
52

tstellanova's avatar
tstellanova committed
53 54 55
    /** @brief We have received a complete list of all parameters onboard the MAV */
    void parameterListUpToDate();

56 57 58
    void parameterUpdateRequested(int component, const QString& parameter);
    void parameterUpdateRequestedById(int componentId, int paramId);

tstellanova's avatar
tstellanova committed
59
    /** @brief We updated the parameter status message */
60
    void parameterStatusMsgUpdated(QString msg, int level);
61 62

public slots:
tstellanova's avatar
tstellanova committed
63 64 65 66 67 68
    /** @brief  Iterate through all components, through all pending parameters and send them to UAS */
    virtual void sendPendingParameters();

    /** @brief  Write the current onboard parameters from transient RAM into persistent storage, e.g. EEPROM or harddisk */
    virtual void writeParamsToPersistentStorage();

69 70
    /** @brief Write one parameter to the MAV */
    virtual void setParameter(int component, QString parameterName, QVariant value);
tstellanova's avatar
tstellanova committed
71

72 73
    /** @brief Request list of parameters from MAV */
    virtual void requestParameterList();
74

75 76 77 78 79 80
    /** @brief Check for missing parameters */
    virtual void retransmissionGuardTick();

    /** @brief Request a single parameter update by name */
    virtual void requestParameterUpdate(int component, const QString& parameter);

81 82 83
    /** @brief Request an update of RC parameters */
    virtual void requestRcCalibrationParamsUpdate();

tstellanova's avatar
tstellanova committed
84 85
    virtual void receivedParameterUpdate(int uas, int compId, int paramCount, int paramId, QString paramName, QVariant value);

tstellanova's avatar
tstellanova committed
86 87 88
//protected slots:
//    void receivedParameterChange(int uas, int component, QString parameterName, QVariant value);
//    void receivedParameterListChange(int uas, int component, int parameterCount, int parameterId, QString parameterName, QVariant value);
tstellanova's avatar
tstellanova committed
89

90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107
protected:

    UASInterface* mav;   ///< The MAV we're talking to

    UASParameterDataModel* paramDataModel;

    // Communications management
    QVector<bool> receivedParamsList; ///< Successfully received parameters
    QMap<int, QList<int>* > transmissionMissingPackets; ///< Missing packets
    QMap<int, QMap<QString, QVariant>* > transmissionMissingWriteAckPackets; ///< Missing write ACK packets
    bool transmissionListMode;       ///< Currently requesting list
    QMap<int, bool> transmissionListSizeKnown;  ///< List size initialized?
    bool transmissionActive;         ///< Missing packets, working on list?
    quint64 transmissionTimeout;     ///< Timeout
    QTimer retransmissionTimer;      ///< Timer handling parameter retransmission
    int retransmissionTimeout; ///< Retransmission request timeout, in milliseconds
    int rewriteTimeout; ///< Write request timeout, in milliseconds
    int retransmissionBurstRequestSize; ///< Number of packets requested for retransmission per burst
108
    quint64 listRecvTimeout;     ///< How long to wait for first parameter list response before re-requesting
109 110 111 112 113 114 115 116

    // Status
    QString parameterStatusMsg;

};
    

#endif // UASPARAMETERCOMMSMGR_H