MAVLinkInspectorController.h 11.9 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17
/****************************************************************************
 *
 *   (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.
 *
 ****************************************************************************/

#pragma once

#include "MAVLinkProtocol.h"
#include "Vehicle.h"

#include <QObject>
#include <QString>
#include <QDebug>
18 19
#include <QVariantList>
#include <QtCharts/QAbstractSeries>
20

21 22
Q_DECLARE_LOGGING_CATEGORY(MAVLinkInspectorLog)

23 24 25
QT_CHARTS_USE_NAMESPACE

class QGCMAVLinkMessage;
26
class MAVLinkChartController;
27 28
class MAVLinkInspectorController;

29 30 31
//-----------------------------------------------------------------------------
class QGCMAVLinkMessageField : public QObject {
    Q_OBJECT
32
public:
33 34 35 36 37 38
    Q_PROPERTY(QString          name        READ name       CONSTANT)
    Q_PROPERTY(QString          label       READ label      CONSTANT)
    Q_PROPERTY(QString          type        READ type       CONSTANT)
    Q_PROPERTY(QString          value       READ value      NOTIFY valueChanged)
    Q_PROPERTY(bool             selectable  READ selectable NOTIFY selectableChanged)
    Q_PROPERTY(QAbstractSeries* series      READ series     NOTIFY seriesChanged)
39

40
    QGCMAVLinkMessageField(QGCMAVLinkMessage* parent, QString name, QString type);
41

42 43 44 45 46 47 48 49 50 51 52 53 54 55
    QString         name            () { return _name;  }
    QString         label           ();
    QString         type            () { return _type;  }
    QString         value           () { return _value; }
    bool            selectable      () { return _selectable; }
    bool            selected        () { return _pSeries != nullptr; }
    QAbstractSeries*series          () { return _pSeries; }
    QList<QPointF>* values          () { return &_values;}
    qreal           rangeMin        () { return _rangeMin; }
    qreal           rangeMax        () { return _rangeMax; }

    void            setSelectable   (bool sel);
    void            updateValue     (QString newValue, qreal v);

56
    void            addSeries       (MAVLinkChartController* chart, QAbstractSeries* series);
57
    void            delSeries       ();
Gus Grubba's avatar
Gus Grubba committed
58
    void            updateSeries    ();
59 60

signals:
61 62 63
    void            seriesChanged       ();
    void            selectableChanged   ();
    void            valueChanged        ();
64 65

private:
66 67 68
    QString     _type;
    QString     _name;
    QString     _value;
69 70 71 72
    bool        _selectable = true;
    int         _dataIndex  = 0;
    qreal       _rangeMin   = 0;
    qreal       _rangeMax   = 0;
73 74 75

    QAbstractSeries*    _pSeries = nullptr;
    QGCMAVLinkMessage*  _msg     = nullptr;
76
    MAVLinkChartController*      _chart   = nullptr;
77
    QList<QPointF>      _values;
78 79 80 81 82
};

//-----------------------------------------------------------------------------
class QGCMAVLinkMessage : public QObject {
    Q_OBJECT
83
public:
Gus Grubba's avatar
Gus Grubba committed
84 85 86 87
    Q_PROPERTY(quint32              id          READ id         NOTIFY indexChanged)
    Q_PROPERTY(quint32              cid         READ cid        NOTIFY indexChanged)
    Q_PROPERTY(QString              name        READ name       NOTIFY indexChanged)
    Q_PROPERTY(qreal                messageHz   READ messageHz  NOTIFY freqChanged)
88
    Q_PROPERTY(quint64              count       READ count      NOTIFY messageChanged)
Gus Grubba's avatar
Gus Grubba committed
89
    Q_PROPERTY(QmlObjectListModel*  fields      READ fields     NOTIFY indexChanged)
90
    Q_PROPERTY(bool                 selected    READ selected   NOTIFY selectedChanged)
91

92
    QGCMAVLinkMessage(QObject* parent, mavlink_message_t* message);
93

Gus Grubba's avatar
Gus Grubba committed
94 95
    quint32             id          () { return _message.msgid;  }
    quint8              cid         () { return _message.compid; }
96
    QString             name        () { return _name;  }
Gus Grubba's avatar
Gus Grubba committed
97
    qreal               messageHz   () { return _messageHz; }
98
    quint64             count       () { return _count; }
Gus Grubba's avatar
Gus Grubba committed
99
    quint64             lastCount   () { return _lastCount; }
100
    QmlObjectListModel* fields      () { return &_fields; }
101
    bool                selected    () { return _selected; }
102

103
    void                select      ();
104
    void                update      (mavlink_message_t* message);
Gus Grubba's avatar
Gus Grubba committed
105
    void                updateFreq  ();
106 107 108

signals:
    void messageChanged             ();
Gus Grubba's avatar
Gus Grubba committed
109 110
    void freqChanged                ();
    void indexChanged               ();
111
    void selectedChanged            ();
112 113 114 115

private:
    QmlObjectListModel  _fields;
    QString             _name;
Gus Grubba's avatar
Gus Grubba committed
116
    qreal               _messageHz  = 0.0;
117
    uint64_t            _count      = 0;
Gus Grubba's avatar
Gus Grubba committed
118
    uint64_t            _lastCount  = 0;
119
    mavlink_message_t   _message;   //-- List of QGCMAVLinkMessageField
120
    bool                _selected   = false;
121 122 123 124 125
};

//-----------------------------------------------------------------------------
class QGCMAVLinkVehicle : public QObject {
    Q_OBJECT
126
public:
Gus Grubba's avatar
Gus Grubba committed
127 128
    Q_PROPERTY(quint8               id              READ id             CONSTANT)
    Q_PROPERTY(QmlObjectListModel*  messages        READ messages       NOTIFY messagesChanged)
129 130
    Q_PROPERTY(QList<int>           compIDs         READ compIDs        NOTIFY compIDsChanged)
    Q_PROPERTY(QStringList          compIDsStr      READ compIDsStr     NOTIFY compIDsChanged)
131 132 133

    QGCMAVLinkVehicle(QObject* parent, quint8 id);

Gus Grubba's avatar
Gus Grubba committed
134 135
    quint8              id              () { return _id; }
    QmlObjectListModel* messages        () { return &_messages; }
136 137
    QList<int>          compIDs         () { return _compIDs; }
    QStringList         compIDsStr      () { return _compIDsStr; }
138

Gus Grubba's avatar
Gus Grubba committed
139 140
    QGCMAVLinkMessage*  findMessage     (uint32_t id, uint8_t cid);
    void                append          (QGCMAVLinkMessage* message);
141 142

signals:
Gus Grubba's avatar
Gus Grubba committed
143
    void messagesChanged                ();
144 145 146 147
    void compIDsChanged                 ();

private:
    void _checkCompID                   (QGCMAVLinkMessage *message);
148 149 150

private:
    quint8              _id;
151 152 153
    QList<int>          _compIDs;
    QStringList         _compIDsStr;
    QmlObjectListModel  _messages;      //-- List of QGCMAVLinkMessage
154 155 156
};

//-----------------------------------------------------------------------------
157
class MAVLinkChartController : public QObject {
158 159
    Q_OBJECT
public:
160
    MAVLinkChartController(MAVLinkInspectorController* parent);
161

162 163 164 165 166 167 168 169 170 171
    Q_PROPERTY(QVariantList chartFields         READ chartFields            NOTIFY chartFieldsChanged)
    Q_PROPERTY(QDateTime    rangeXMin           READ rangeXMin              NOTIFY rangeXMinChanged)
    Q_PROPERTY(QDateTime    rangeXMax           READ rangeXMax              NOTIFY rangeXMaxChanged)
    Q_PROPERTY(qreal        rangeYMin           READ rangeYMin              NOTIFY rangeYMinChanged)
    Q_PROPERTY(qreal        rangeYMax           READ rangeYMax              NOTIFY rangeYMaxChanged)

    Q_PROPERTY(quint32      rangeYIndex         READ rangeYIndex            WRITE setRangeYIndex    NOTIFY rangeYIndexChanged)
    Q_PROPERTY(quint32      rangeXIndex         READ rangeXIndex            WRITE setRangeXIndex    NOTIFY rangeXIndexChanged)

    Q_INVOKABLE void        addSeries           (QGCMAVLinkMessageField* field, QAbstractSeries* series);
172 173
    Q_INVOKABLE void        delSeries           (QGCMAVLinkMessageField* field);

174 175 176 177 178 179 180 181 182 183 184 185
    Q_INVOKABLE MAVLinkInspectorController* controller() { return _controller; }

    QVariantList            chartFields         () { return _chartFields; }
    QDateTime               rangeXMin           () { return _rangeXMin;   }
    QDateTime               rangeXMax           () { return _rangeXMax;   }
    qreal                   rangeYMin           () { return _rangeYMin;   }
    qreal                   rangeYMax           () { return _rangeYMax;   }
    quint32                 rangeXIndex         () { return _rangeXIndex; }
    quint32                 rangeYIndex         () { return _rangeYIndex; }

    void                    setRangeXIndex      (quint32 t);
    void                    setRangeYIndex      (quint32 r);
186
    void                    updateXRange        ();
187
    void                    updateYRange        ();
188 189

signals:
190 191 192 193 194 195 196
    void chartFieldsChanged ();
    void rangeXMinChanged   ();
    void rangeXMaxChanged   ();
    void rangeYMinChanged   ();
    void rangeYMaxChanged   ();
    void rangeYIndexChanged ();
    void rangeXIndexChanged ();
197

198
private slots:
199
    void _refreshSeries     ();
200 201

private:
202 203 204 205 206 207 208 209 210 211
    QTimer              _updateSeriesTimer;
    QDateTime           _rangeXMin;
    QDateTime           _rangeXMax;
    qreal               _rangeYMin           = 0;
    qreal               _rangeYMax           = 1;
    quint32             _rangeXIndex         = 0;                    ///< 5 Seconds
    quint32             _rangeYIndex         = 0;                    ///< Auto Range
    QVariantList        _chartFields;
    MAVLinkInspectorController* _controller  = nullptr;
};
212

213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236
//-----------------------------------------------------------------------------
class MAVLinkInspectorController : public QObject
{
    Q_OBJECT
public:
    MAVLinkInspectorController();
    ~MAVLinkInspectorController();

    Q_PROPERTY(QStringList          vehicleNames        READ vehicleNames           NOTIFY vehiclesChanged)
    Q_PROPERTY(QmlObjectListModel*  vehicles            READ vehicles               NOTIFY vehiclesChanged)
    Q_PROPERTY(QmlObjectListModel*  charts              READ charts                 NOTIFY chartsChanged)
    Q_PROPERTY(QGCMAVLinkVehicle*   activeVehicle       READ activeVehicle          NOTIFY activeVehiclesChanged)
    Q_PROPERTY(QStringList          timeScales          READ timeScales             NOTIFY timeScalesChanged)
    Q_PROPERTY(QStringList          rangeList           READ rangeList              NOTIFY rangeListChanged)

    Q_INVOKABLE MAVLinkChartController* createChart     ();
    Q_INVOKABLE void                    deleteChart     (MAVLinkChartController* chart);

    QmlObjectListModel*             vehicles            () { return &_vehicles;     }
    QmlObjectListModel*             charts              () { return &_charts;       }
    QGCMAVLinkVehicle*              activeVehicle       () { return _activeVehicle; }
    QStringList                     vehicleNames        () { return _vehicleNames;  }
    QStringList                     timeScales          ();
    QStringList                     rangeList           ();
Gus Grubba's avatar
Gus Grubba committed
237 238 239 240 241 242 243 244

    class TimeScale_st : public QObject {
    public:
        TimeScale_st(QObject* parent, const QString& l, uint32_t t);
        QString     label;
        uint32_t    timeScale;
    };

245 246 247 248 249 250 251
    class Range_st : public QObject {
    public:
        Range_st(QObject* parent, const QString& l, qreal r);
        QString     label;
        qreal       range;
    };

252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273
    const QList<TimeScale_st*>&     timeScaleSt         () { return _timeScaleSt; }
    const QList<Range_st*>&         rangeSt             () { return _rangeSt; }

signals:
    void vehiclesChanged            ();
    void chartsChanged              ();
    void activeVehiclesChanged      ();
    void timeScalesChanged          ();
    void rangeListChanged           ();

private slots:
    void _receiveMessage            (LinkInterface* link, mavlink_message_t message);
    void _vehicleAdded              (Vehicle* vehicle);
    void _vehicleRemoved            (Vehicle* vehicle);
    void _setActiveVehicle          (Vehicle* vehicle);
    void _refreshFrequency          ();

private:
    QGCMAVLinkVehicle* _findVehicle (uint8_t id);

private:

274 275 276
    int                 _selectedSystemID       = 0;                    ///< Currently selected system
    int                 _selectedComponentID    = 0;                    ///< Currently selected component
    QStringList         _timeScales;
277
    QStringList         _rangeList;
278
    QGCMAVLinkVehicle*  _activeVehicle          = nullptr;
Gus Grubba's avatar
Gus Grubba committed
279
    QTimer              _updateFrequencyTimer;
280
    QStringList         _vehicleNames;
281
    QmlObjectListModel  _vehicles;                                      ///< List of QGCMAVLinkVehicle
282
    QmlObjectListModel  _charts;                                        ///< List of MAVLinkCharts
Gus Grubba's avatar
Gus Grubba committed
283
    QList<TimeScale_st*>_timeScaleSt;
284
    QList<Range_st*>    _rangeSt;
285

286
};