机器人地面站-[QGroundControl源码解析]-[6]-[AnalysizeView2]

发布于:2022-12-09 ⋅ 阅读:(637) ⋅ 点赞:(0)

目录

前言

一.MAVLinkInspectorController

二.MavlinkConsoleController

总结


前言

上篇讲解了该文件夹下的5个类来处理日志下载,日志解析,图像标注的工作。本篇我们来看mavlink开头的两个类。看下他们是干什么。首先要了解下mavlink,其实也是一种数据协议,有协议头,消息体组成,我之前已经预习过了,不了解这个协议的朋友应该先去做一个大致了解,非常重要。下面开始介绍代码。

一.MAVLinkInspectorController

这个类篇幅很长,读起来也很吃力,因为没有实际设备能对比界面来理解,所以我只能先讲下我的个人理解。分析头文件,里面有多个类,第一个类是QGCMAVLinkMessageField,我认为这个类应该是mavlink消息的字段,字段也是字面理解,我觉得理解成一个mavlink的消息项目更准确些,该字段有名称,标签,类型,数值,能否选择 图表下标 图像等属性,所以我认为这个类标所代表的mavlink字段应该能标识常规数据类型以及图表类型。

第二个类是QGCMAVLinkMessage,我认为这指代一个mavlink消息,该类中有一个list属性存储QGCMAVLinkMessageField,也就是说消息中包含消息字段,这样理解感觉就通顺了些,除了这个属性,该类还有di,cid,名称,频率,数量,消息中的字段是否被选中,该消息是否选中等这些属性。

第三个类是QGCMAVLinkSystem,通过后边的分析我认为这个类对应的是vehicle,后边会看到通过vehicle的id获取system的操作,于是该类应该是指代vehivle的mavlink消息系统。该类除了id属性,还有一个list来存储第二个类QGCMAVLinkMessage,还有一个list存储compid,同样有是否被选中的属性。

第四个类是MAVLinkChartController,该类应该是专为图表而生,其中的属性和操作也大都是更新图表和图像操作。

第五个类是MAVLinkInspectorController,该类为最后的界面展示提供逻辑,其中有list来存储QGCMAVLinkSystem还有list存储MAVLinkChartController,还提供了一些系统和图表发生变化时的相应方法。

下面我们来看代码,代码篇幅较长。

/****************************************************************************
 *
 * (c) 2009-2020 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.
 *
 ****************************************************************************/

/// @file
/// @brief MAVLink message inspector and charting controller
/// MAVLink消息检查器和制图控制器
/// @author Gus Grubba <gus@auterion.com>

#pragma once

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

#include <QObject>
#include <QString>
#include <QDebug>
#include <QVariantList>
#include <QtCharts/QAbstractSeries>

//为MAVLinkInspectorLog创建方法
Q_DECLARE_LOGGING_CATEGORY(MAVLinkInspectorLog)

//qchart画图必须要写的
QT_CHARTS_USE_NAMESPACE

//一些类的提前声明,这样可以避免在头文件中include 从而避免头文件的之间的交叉引用
class QGCMAVLinkMessage;
class QGCMAVLinkSystem;
class MAVLinkChartController;
class MAVLinkInspectorController;

//-----------------------------------------------------------------------------
/// MAVLink message field
/// MAVLink消息的字段
class QGCMAVLinkMessageField : public QObject {
    Q_OBJECT
public:
    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(int              chartIndex  READ chartIndex CONSTANT) //图的下标
    Q_PROPERTY(QAbstractSeries* series      READ series     NOTIFY seriesChanged) //图像区域

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

    QString         name            () { return _name;  }
    QString         label           ();
    QString         type            () { return _type;  }
    QString         value           () { return _value; }
    bool            selectable      () const{ return _selectable; }
    bool            selected        () { return _pSeries != nullptr; } //选择与否
    QAbstractSeries*series          () { return _pSeries; }
    QList<QPointF>* values          () { return &_values;}
    qreal           rangeMin        () const{ return _rangeMin; }
    qreal           rangeMax        () const{ return _rangeMax; }
    int             chartIndex      ();

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

    void            addSeries       (MAVLinkChartController* chart, QAbstractSeries* series);
    void            delSeries       ();
    void            updateSeries    ();

signals:
    void            seriesChanged       ();
    void            selectableChanged   ();
    void            valueChanged        ();

private:
    QString     _type;
    QString     _name;
    QString     _value;
    bool        _selectable = true;
    int         _dataIndex  = 0;
    qreal       _rangeMin   = 0;
    qreal       _rangeMax   = 0;

    QAbstractSeries*    _pSeries = nullptr;
    QGCMAVLinkMessage*  _msg     = nullptr;
    MAVLinkChartController*      _chart   = nullptr;
    QList<QPointF>      _values;
};

//-----------------------------------------------------------------------------
/// MAVLink message
class QGCMAVLinkMessage : public QObject {
    Q_OBJECT
public:
    Q_PROPERTY(quint32              id              READ id             CONSTANT) //id
    Q_PROPERTY(quint32              cid             READ cid            CONSTANT) //cid 二级id?
    Q_PROPERTY(QString              name            READ name           CONSTANT) //名称
    Q_PROPERTY(qreal                messageHz       READ messageHz      NOTIFY freqChanged)  //消息频率
    Q_PROPERTY(quint64              count           READ count          NOTIFY countChanged) //数量
    Q_PROPERTY(QmlObjectListModel*  fields          READ fields         CONSTANT) //字段列表
    Q_PROPERTY(bool                 fieldSelected   READ fieldSelected  NOTIFY fieldSelectedChanged) //字段是否被选择
    Q_PROPERTY(bool                 selected        READ selected       NOTIFY selectedChanged) //是否被选择

    QGCMAVLinkMessage   (QObject* parent, mavlink_message_t* message);
    ~QGCMAVLinkMessage  ();

    quint32             id              () const{ return _message.msgid;  }
    quint8              cid             () const{ return _message.compid; }
    QString             name            () { return _name;  }
    qreal               messageHz       () const{ return _messageHz; }
    quint64             count           () const{ return _count; }
    quint64             lastCount       () const{ return _lastCount; }
    QmlObjectListModel* fields          () { return &_fields; }
    bool                fieldSelected   () const{ return _fieldSelected; }
    bool                selected        () const{ return _selected; }

    void                updateFieldSelection();
    void                update          (mavlink_message_t* message);
    void                updateFreq      ();
    void                setSelected     (bool sel);

signals:
    void countChanged                   ();
    void freqChanged                    ();
    void fieldSelectedChanged           ();
    void selectedChanged                ();

private:
    void _updateFields(void);

    QmlObjectListModel  _fields;
    QString             _name;
    qreal               _messageHz      = 0.0;
    uint64_t            _count          = 1;
    uint64_t            _lastCount      = 0;
    mavlink_message_t   _message;
    bool                _fieldSelected  = false;
    bool                _selected       = false;
};

//-----------------------------------------------------------------------------
/// Vehicle MAVLink message belongs to
/// 设备的MAVLink消息属于此
class QGCMAVLinkSystem : public QObject {
    Q_OBJECT
public:
    Q_PROPERTY(quint8               id              READ id                                 CONSTANT)  //id
    Q_PROPERTY(QmlObjectListModel*  messages        READ messages                           CONSTANT)  //消息
    Q_PROPERTY(QList<int>           compIDs         READ compIDs                            NOTIFY compIDsChanged)  //列表存储compIDs 还不清楚什么意思
    Q_PROPERTY(QStringList          compIDsStr      READ compIDsStr                         NOTIFY compIDsChanged)  //字符串列表
    Q_PROPERTY(int                  selected        READ selected       WRITE setSelected   NOTIFY selectedChanged) //是否被选中

    QGCMAVLinkSystem   (QObject* parent, quint8 id);
    ~QGCMAVLinkSystem  ();

    quint8              id              () const{ return _id; }
    QmlObjectListModel* messages        () { return &_messages; }
    QList<int>          compIDs         () { return _compIDs; }
    QStringList         compIDsStr      () { return _compIDsStr; }
    int                 selected        () const{ return _selected; }

    void                setSelected     (int sel);
    QGCMAVLinkMessage*  findMessage     (uint32_t id, uint8_t cid);  //查找消息
    int                 findMessage     (QGCMAVLinkMessage* message); //查找消息
    void                append          (QGCMAVLinkMessage* message); //添加消息

signals:
    void compIDsChanged                 ();
    void selectedChanged                ();

private:
    void _checkCompID                   (QGCMAVLinkMessage *message);
    void _resetSelection                ();

private:
    quint8              _id;
    QList<int>          _compIDs;
    QStringList         _compIDsStr;
    QmlObjectListModel  _messages;      //-- List of QGCMAVLinkMessage
    int                 _selected = 0;
};

//-----------------------------------------------------------------------------
/// MAVLink message charting controller
/// MAVLink消息图表控制器
class MAVLinkChartController : public QObject {
    Q_OBJECT
public:
    MAVLinkChartController(MAVLinkInspectorController* parent, int index);

    Q_PROPERTY(QVariantList chartFields         READ chartFields            NOTIFY chartFieldsChanged)  //图表列表
    Q_PROPERTY(QDateTime    rangeXMin           READ rangeXMin              NOTIFY rangeXMinChanged)    //x轴范围
    Q_PROPERTY(QDateTime    rangeXMax           READ rangeXMax              NOTIFY rangeXMaxChanged)
    Q_PROPERTY(qreal        rangeYMin           READ rangeYMin              NOTIFY rangeYMinChanged)    //y轴范围
    Q_PROPERTY(qreal        rangeYMax           READ rangeYMax              NOTIFY rangeYMaxChanged)
    Q_PROPERTY(int          chartIndex          READ chartIndex             CONSTANT)                   //图像下标

    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); //添加图
    Q_INVOKABLE void        delSeries           (QGCMAVLinkMessageField* field); //删除图

    Q_INVOKABLE MAVLinkInspectorController* controller() { return _controller; }

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

    void                    setRangeXIndex      (quint32 t);
    void                    setRangeYIndex      (quint32 r);
    void                    updateXRange        ();
    void                    updateYRange        ();

signals:
    void chartFieldsChanged ();
    void rangeXMinChanged   ();
    void rangeXMaxChanged   ();
    void rangeYMinChanged   ();
    void rangeYMaxChanged   ();
    void rangeYIndexChanged ();
    void rangeXIndexChanged ();

private slots:
    void _refreshSeries     ();

private:
    QTimer              _updateSeriesTimer;
    QDateTime           _rangeXMin;
    QDateTime           _rangeXMax;
    int                 _index               = 0;
    qreal               _rangeYMin           = 0;
    qreal               _rangeYMax           = 1;
    quint32             _rangeXIndex         = 0;                    ///< 5 Seconds
    quint32             _rangeYIndex         = 0;                    ///< Auto Range
    QVariantList        _chartFields;
    MAVLinkInspectorController* _controller  = nullptr;
};

//-----------------------------------------------------------------------------
/// MAVLink message inspector controller (provides the logic for UI display)
/// MAVLink消息检查器控制器(为UI显示提供逻辑)
class MAVLinkInspectorController : public QObject
{
    Q_OBJECT
public:
    MAVLinkInspectorController();
    ~MAVLinkInspectorController();

    Q_PROPERTY(QStringList          systemNames     READ systemNames    NOTIFY systemsChanged)  //系统名称
    Q_PROPERTY(QmlObjectListModel*  systems         READ systems       NOTIFY systemsChanged)   //系统列表
    Q_PROPERTY(QmlObjectListModel*  charts          READ charts         NOTIFY chartsChanged)   //图表列表
    Q_PROPERTY(QGCMAVLinkSystem*    activeSystem    READ activeSystem   NOTIFY activeSystemChanged) //mavlink系统
    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); //删除图表
    Q_INVOKABLE void                    setActiveSystem (int systemId); //设置系统激活

    QmlObjectListModel* systems     () { return &_systems;     }  //系统列表
    QmlObjectListModel* charts      () { return &_charts;       } //图表列表
    QGCMAVLinkSystem*   activeSystem() { return _activeSystem; }  //激活的系统
    QStringList         systemNames () { return _systemNames;  }  //系统名称
    QStringList         timeScales  ();
    QStringList         rangeList   ();

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

    class Range_st : public QObject {
    public:
        Range_st(QObject* parent, const QString& l, qreal r);
        QString     label;
        qreal       range;
    };

    const QList<TimeScale_st*>&     timeScaleSt         () { return _timeScaleSt; }
    const QList<Range_st*>&         rangeSt             () { return _rangeSt; }

signals:
    void systemsChanged     ();
    void chartsChanged      ();
    void activeSystemChanged();
    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:
    QGCMAVLinkSystem* _findVehicle (uint8_t id);

private:

    int                 _selectedSystemID       = 0;        ///< Currently selected system 当前选择的系统
    int                 _selectedComponentID    = 0;        ///< Currently selected component  当前选择的组件
    QStringList         _timeScales;
    QStringList         _rangeList;
    QGCMAVLinkSystem*   _activeSystem           = nullptr;
    QTimer              _updateFrequencyTimer;
    QStringList         _systemNames;
    QmlObjectListModel  _systems;                           ///< List of QGCMAVLinkSystem
    QmlObjectListModel  _charts;                            ///< List of MAVLinkCharts
    QList<TimeScale_st*>_timeScaleSt;
    QList<Range_st*>    _rangeSt;

};

cc文件

/****************************************************************************
 *
 * (c) 2009-2020 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.
 *
 ****************************************************************************/

#include "MAVLinkInspectorController.h"
#include "QGCApplication.h"
#include "MultiVehicleManager.h"
#include <QtCharts/QLineSeries>

QGC_LOGGING_CATEGORY(MAVLinkInspectorLog, "MAVLinkInspectorLog")

QT_CHARTS_USE_NAMESPACE

Q_DECLARE_METATYPE(QAbstractSeries*)

#define UPDATE_FREQUENCY (1000 / 15)    // 15Hz

//-----------------------------------------------------------------------------
QGCMAVLinkMessageField::QGCMAVLinkMessageField(QGCMAVLinkMessage *parent, QString name, QString type)
    : QObject(parent)
    , _type(type)
    , _name(name)
    , _msg(parent)
{
    qCDebug(MAVLinkInspectorLog) << "Field:" << name << type;
}

//-----------------------------------------------------------------------------
//添加图表
void QGCMAVLinkMessageField::addSeries(MAVLinkChartController* chart, QAbstractSeries* series)
{
    if(!_pSeries) {
        _chart = chart;
        _pSeries = series;
        emit seriesChanged();
        _dataIndex = 0;
        _msg->updateFieldSelection();
    }
}

//-----------------------------------------------------------------------------
//删除图表
void QGCMAVLinkMessageField::delSeries()
{
    if(_pSeries) {
        _values.clear();
        QLineSeries* lineSeries = static_cast<QLineSeries*>(_pSeries);
        lineSeries->replace(_values);
        _pSeries = nullptr;
        _chart   = nullptr;
        emit seriesChanged();
        _msg->updateFieldSelection();
    }
}

//-----------------------------------------------------------------------------
QString QGCMAVLinkMessageField::label()
{
    //-- Label is message name + field name
    return QString(_msg->name() + ": " + _name);
}

//-----------------------------------------------------------------------------
void
QGCMAVLinkMessageField::setSelectable(bool sel)
{
    if(_selectable != sel) {
        _selectable = sel;
        emit selectableChanged();
    }
}

//-----------------------------------------------------------------------------
int
QGCMAVLinkMessageField::chartIndex()
{
    if(_chart)
        return _chart->chartIndex();
    return 0;
}

//-----------------------------------------------------------------------------
void QGCMAVLinkMessageField::updateValue(QString newValue, qreal v)
{
    if(_value != newValue) {
        _value = newValue;
        emit valueChanged();
    }
    if(_pSeries && _chart) {
        int count = _values.count();
        //-- Arbitrary limit of 1 minute of data at 50Hz for now 目前在50Hz下任意限制1分钟的数据
        // 设置点的坐标横轴是时间毫秒纵轴是v,如果_dataindex超过count了则从头开始更新
        if(count < (50 * 60)) {
            QPointF p(QGC::bootTimeMilliseconds(), v);
            _values.append(p);
        } else {
            if(_dataIndex >= count) _dataIndex = 0;
            _values[_dataIndex].setX(QGC::bootTimeMilliseconds());
            _values[_dataIndex].setY(v);
            _dataIndex++;
        }
        //-- Auto Range
        if(_chart->rangeYIndex() == 0) {
            qreal vmin  = std::numeric_limits<qreal>::max();
            qreal vmax  = std::numeric_limits<qreal>::min();
            //找到_values中y的最大值最小值
            for(int i = 0; i < _values.count(); i++) {
                qreal v = _values[i].y();
                if(vmax < v) vmax = v;
                if(vmin > v) vmin = v;
            }
            bool changed = false;
            //设置_rangeMin和_rangeMax
            if(std::abs(_rangeMin - vmin) > 0.000001) {
                _rangeMin = vmin;
                changed = true;
            }
            if(std::abs(_rangeMax - vmax) > 0.000001) {
                _rangeMax = vmax;
                changed = true;
            }
            if(changed) {
                //如果范围有变化就更新y的范围
                _chart->updateYRange();
            }
        }
    }
}

//-----------------------------------------------------------------------------
void QGCMAVLinkMessageField::updateSeries()
{
    int count = _values.count();
    if (count > 1) {
        QList<QPointF> s;
        //申请count大小的空间
        s.reserve(count);
        int idx = _dataIndex;
        //将_values的值复制给s从_dataIndex开始,如果到末尾了则从0开始复制
        for(int i = 0; i < count; i++, idx++) {
            if(idx >= count) idx = 0;
            QPointF p(_values[idx]);
            s.append(p);
        }
        //交给图表替换数据
        QLineSeries* lineSeries = static_cast<QLineSeries*>(_pSeries);
        lineSeries->replace(s);
    }
}

//-----------------------------------------------------------------------------
/**
MAVPACKED(
typedef struct __mavlink_message {
    uint16_t checksum;      ///< sent at end of packet 在数据包结束时发送
    uint8_t magic;          ///< protocol magic marker 协议magic标记
    uint8_t len;            ///< Length of payload 有效载荷
    uint8_t incompat_flags; ///< flags that must be understood 不兼容的标记
    uint8_t compat_flags;   ///< flags that can be ignored if not understood 兼容的标记
    uint8_t seq;            ///< Sequence of packet //包序列
    uint8_t sysid;          ///< ID of message sender system/aircraft 发送系统ID /飞机ID
    uint8_t compid;         ///< ID of the message sender component 消息发送方组件的ID
    uint32_t msgid:24;      ///< ID of message in payload 有效负载中的消息ID
    uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
    uint8_t ck[2];          ///< incoming checksum bytes 输入的校验和字节
    uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN]; 签名
}) mavlink_message_t;



note that in this structure the order of fields is the order  注意,在这个结构中,字段的顺序就是xml中的顺序 线序不是必须的
in the XML file, not necessary the wire order
typedef struct __mavlink_message_info {
    uint32_t msgid;                                        // message ID 消息id
    const char *name;                                      // name of the message 消息名称
    unsigned num_fields;                                   // how many fields in this message 消息中有多少字段
    mavlink_field_info_t fields[MAVLINK_MAX_FIELDS];       // field information 字段信息
} mavlink_message_info_t;

*/

QGCMAVLinkMessage::QGCMAVLinkMessage(QObject *parent, mavlink_message_t* message)
    : QObject(parent)
{
    //消息赋值
    _message = *message;

    //通过message得到mavlink_message_info_t
    const mavlink_message_info_t* msgInfo = mavlink_get_message_info(message);
    if (!msgInfo) {
        qCWarning(MAVLinkInspectorLog) << QStringLiteral("QGCMAVLinkMessage NULL msgInfo msgid(%1)").arg(message->msgid);
        return;
    }
    _name = QString(msgInfo->name);
    //新的mavlink消息
    qCDebug(MAVLinkInspectorLog) << "New Message:" << _name;

    //遍历mavlink消息所有字段
    for (unsigned int i = 0; i < msgInfo->num_fields; ++i) {
        QString type = QString("?");
        switch (msgInfo->fields[i].type) {
            case MAVLINK_TYPE_CHAR:     type = QString("char");     break;
            case MAVLINK_TYPE_UINT8_T:  type = QString("uint8_t");  break;
            case MAVLINK_TYPE_INT8_T:   type = QString("int8_t");   break;
            case MAVLINK_TYPE_UINT16_T: type = QString("uint16_t"); break;
            case MAVLINK_TYPE_INT16_T:  type = QString("int16_t");  break;
            case MAVLINK_TYPE_UINT32_T: type = QString("uint32_t"); break;
            case MAVLINK_TYPE_INT32_T:  type = QString("int32_t");  break;
            case MAVLINK_TYPE_FLOAT:    type = QString("float");    break;
            case MAVLINK_TYPE_DOUBLE:   type = QString("double");   break;
            case MAVLINK_TYPE_UINT64_T: type = QString("uint64_t"); break;
            case MAVLINK_TYPE_INT64_T:  type = QString("int64_t");  break;
        }
        //构建QGCMAVLinkMessageField mavlink字段信息
        QGCMAVLinkMessageField* f = new QGCMAVLinkMessageField(this, msgInfo->fields[i].name, type);
        _fields.append(f);
    }
}

//-----------------------------------------------------------------------------
QGCMAVLinkMessage::~QGCMAVLinkMessage()
{
    _fields.clearAndDeleteContents();
}

//-----------------------------------------------------------------------------
//更新字段的选择状态
void QGCMAVLinkMessage::updateFieldSelection()
{
    bool sel = false;
    for (int i = 0; i < _fields.count(); ++i) {
        QGCMAVLinkMessageField* f = qobject_cast<QGCMAVLinkMessageField*>(_fields.get(i));
        if(f) {
            if(f->selected()) {
                sel = true;
                break;
            }
        }
    }
    if(sel != _fieldSelected) {
        _fieldSelected = sel;
        emit fieldSelectedChanged();
    }
}

//-----------------------------------------------------------------------------
void QGCMAVLinkMessage::updateFreq()
{
    quint64 msgCount = _count - _lastCount;
    _messageHz = (0.2 * _messageHz) + (0.8 * msgCount);
    _lastCount = _count;
    emit freqChanged();
}

//设置选中与否
void QGCMAVLinkMessage::setSelected(bool sel)
{
    if (_selected != sel) {
        _selected = sel;
        _updateFields();
        emit selectedChanged();
    }
}

//-----------------------------------------------------------------------------
//更新QGCMAVLinkMessage
void QGCMAVLinkMessage::update(mavlink_message_t* message)
{
    _count++;
    _message = *message;

    if (_selected) {
        // Don't update field info unless selected to reduce perf hit of message processing
        // 除非被选中,否则不要更新字段信息,以降低消息处理的性能
        _updateFields();
    }
    emit countChanged();
}

//更新字段
void QGCMAVLinkMessage::_updateFields(void)
{
    //获取mavlink_message_info_t
    const mavlink_message_info_t* msgInfo = mavlink_get_message_info(&_message);
    if (!msgInfo) {
        qWarning() << QStringLiteral("QGCMAVLinkMessage::update NULL msgInfo msgid(%1)").arg(_message.msgid);
        return;
    }
    //验证字段数目是是否统一
    if(_fields.count() != static_cast<int>(msgInfo->num_fields)) {
        qWarning() << QStringLiteral("QGCMAVLinkMessage::update msgInfo field count mismatch msgid(%1)").arg(_message.msgid);
        return;
    }

    //获取消息体
    uint8_t* m = reinterpret_cast<uint8_t*>(&_message.payload64[0]);
    //遍历每个字段
    for (unsigned int i = 0; i < msgInfo->num_fields; ++i) {
        QGCMAVLinkMessageField* f = qobject_cast<QGCMAVLinkMessageField*>(_fields.get(static_cast<int>(i)));
        if(f) {
            //得到线的偏移
            const unsigned int offset = msgInfo->fields[i].wire_offset;
            //得到数组长度
            const unsigned int array_length = msgInfo->fields[i].array_length;
            //得到数组缓存长度 255+2+7
            static const unsigned int array_buffer_length = (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_CHECKSUM_BYTES + 7);
            //根据type做操作
            switch (msgInfo->fields[i].type) {
            case MAVLINK_TYPE_CHAR:
                //设置可选性为false
                f->setSelectable(false);
                //如果数组长度大于0
                if (array_length > 0) {
                    char* str = reinterpret_cast<char*>(m + offset);
                    // Enforce null termination 实施零终止
                    str[array_length - 1] = '\0';
                    //转为str
                    QString v(str);
                    //触发字段值的更新信号
                    f->updateValue(v, 0);
                } else {
                    // Single char
                    char b = *(reinterpret_cast<char*>(m + offset));
                    QString v(b);
                    f->updateValue(v, 0);
                }
                break;
            case MAVLINK_TYPE_UINT8_T:
                if (array_length > 0) {
                    uint8_t* nums = m + offset;
                    QString tmp("%1, ");
                    QString string;
                    for (unsigned int j = 0; j < array_length - 1; ++j) {
                        string += tmp.arg(nums[j]);
                    }
                    string += QString::number(nums[array_length - 1]);
                    f->updateValue(string, static_cast<qreal>(nums[0]));
                } else {
                    // Single value
                    uint8_t u = *(m + offset);
                    f->updateValue(QString::number(u), static_cast<qreal>(u));
                }
                break;
            case MAVLINK_TYPE_INT8_T:
                if (array_length > 0) {
                    int8_t* nums = reinterpret_cast<int8_t*>(m + offset);
                    QString tmp("%1, ");
                    QString string;
                    for (unsigned int j = 0; j < array_length - 1; ++j) {
                        string += tmp.arg(nums[j]);
                    }
                    string += QString::number(nums[array_length - 1]);
                    f->updateValue(string, static_cast<qreal>(nums[0]));
                } else {
                    // Single value
                    int8_t n = *(reinterpret_cast<int8_t*>(m + offset));
                    f->updateValue(QString::number(n), static_cast<qreal>(n));
                }
                break;
            case MAVLINK_TYPE_UINT16_T:
                if (array_length > 0) {
                    uint16_t nums[array_buffer_length / sizeof(uint16_t)];
                    memcpy(nums, m + offset,  sizeof(uint16_t) * array_length);
                    QString tmp("%1, ");
                    QString string;
                    for (unsigned int j = 0; j < array_length - 1; ++j) {
                        string += tmp.arg(nums[j]);
                    }
                    string += QString::number(nums[array_length - 1]);
                    f->updateValue(string, static_cast<qreal>(nums[0]));
                } else {
                    // Single value
                    uint16_t n;
                    memcpy(&n, m + offset, sizeof(uint16_t));
                    f->updateValue(QString::number(n), static_cast<qreal>(n));
                }
                break;
            case MAVLINK_TYPE_INT16_T:
                if (array_length > 0) {
                    int16_t nums[array_buffer_length / sizeof(int16_t)];
                    memcpy(nums, m + offset,  sizeof(int16_t) * array_length);
                    QString tmp("%1, ");
                    QString string;
                    for (unsigned int j = 0; j < array_length - 1; ++j) {
                        string += tmp.arg(nums[j]);
                    }
                    string += QString::number(nums[array_length - 1]);
                    f->updateValue(string, static_cast<qreal>(nums[0]));
                } else {
                    // Single value
                    int16_t n;
                    memcpy(&n, m + offset, sizeof(int16_t));
                    f->updateValue(QString::number(n), static_cast<qreal>(n));
                }
                break;
            case MAVLINK_TYPE_UINT32_T:
                if (array_length > 0) {
                    uint32_t nums[array_buffer_length / sizeof(uint32_t)];
                    memcpy(nums, m + offset,  sizeof(uint32_t) * array_length);
                    QString tmp("%1, ");
                    QString string;
                    for (unsigned int j = 0; j < array_length - 1; ++j) {
                        string += tmp.arg(nums[j]);
                    }
                    string += QString::number(nums[array_length - 1]);
                    f->updateValue(string, static_cast<qreal>(nums[0]));
                } else {
                    // Single value
                    uint32_t n;
                    memcpy(&n, m + offset, sizeof(uint32_t));
                    //-- Special case
                    if(_message.msgid == MAVLINK_MSG_ID_SYSTEM_TIME) {
                        QDateTime d = QDateTime::fromMSecsSinceEpoch(static_cast<qint64>(n),Qt::UTC,0);
                        f->updateValue(d.toString("HH:mm:ss"), static_cast<qreal>(n));
                    } else {
                        f->updateValue(QString::number(n), static_cast<qreal>(n));
                    }
                }
                break;
            case MAVLINK_TYPE_INT32_T:
                if (array_length > 0) {
                    int32_t nums[array_buffer_length / sizeof(int32_t)];
                    memcpy(nums, m + offset,  sizeof(int32_t) * array_length);
                    QString tmp("%1, ");
                    QString string;
                    for (unsigned int j = 0; j < array_length - 1; ++j) {
                        string += tmp.arg(nums[j]);
                    }
                    string += QString::number(nums[array_length - 1]);
                    f->updateValue(string, static_cast<qreal>(nums[0]));
                } else {
                    // Single value
                    int32_t n;
                    memcpy(&n, m + offset, sizeof(int32_t));
                    f->updateValue(QString::number(n), static_cast<qreal>(n));
                }
                break;
            case MAVLINK_TYPE_FLOAT:
                if (array_length > 0) {
                    float nums[array_buffer_length / sizeof(float)];
                    memcpy(nums, m + offset,  sizeof(float) * array_length);
                    QString tmp("%1, ");
                    QString string;
                    for (unsigned int j = 0; j < array_length - 1; ++j) {
                       string += tmp.arg(static_cast<double>(nums[j]));
                    }
                    string += QString::number(static_cast<double>(nums[array_length - 1]));
                    f->updateValue(string, static_cast<qreal>(nums[0]));
                } else {
                    // Single value
                    float fv;
                    memcpy(&fv, m + offset, sizeof(float));
                    f->updateValue(QString::number(static_cast<double>(fv)), static_cast<qreal>(fv));
                }
                break;
            case MAVLINK_TYPE_DOUBLE:
                if (array_length > 0) {
                    double nums[array_buffer_length / sizeof(double)];
                    memcpy(nums, m + offset,  sizeof(double) * array_length);
                    QString tmp("%1, ");
                    QString string;
                    for (unsigned int j = 0; j < array_length - 1; ++j) {
                        string += tmp.arg(nums[j]);
                    }
                    string += QString::number(static_cast<double>(nums[array_length - 1]));
                    f->updateValue(string, static_cast<qreal>(nums[0]));
                } else {
                    // Single value
                    double d;
                    memcpy(&d, m + offset, sizeof(double));
                    f->updateValue(QString::number(d), static_cast<qreal>(d));
                }
                break;
            case MAVLINK_TYPE_UINT64_T:
                if (array_length > 0) {
                    uint64_t nums[array_buffer_length / sizeof(uint64_t)];
                    memcpy(nums, m + offset,  sizeof(uint64_t) * array_length);
                    QString tmp("%1, ");
                    QString string;
                    for (unsigned int j = 0; j < array_length - 1; ++j) {
                        string += tmp.arg(nums[j]);
                    }
                    string += QString::number(nums[array_length - 1]);
                    f->updateValue(string, static_cast<qreal>(nums[0]));
                } else {
                    // Single value
                    uint64_t n;
                    memcpy(&n, m + offset, sizeof(uint64_t));
                    //-- Special case
                    if(_message.msgid == MAVLINK_MSG_ID_SYSTEM_TIME) {
                        QDateTime d = QDateTime::fromMSecsSinceEpoch(n/1000,Qt::UTC,0);
                        f->updateValue(d.toString("yyyy MM dd HH:mm:ss"), static_cast<qreal>(n));
                    } else {
                        f->updateValue(QString::number(n), static_cast<qreal>(n));
                    }
                }
                break;
            case MAVLINK_TYPE_INT64_T:
                if (array_length > 0) {
                    int64_t nums[array_buffer_length / sizeof(int64_t)];
                    memcpy(nums, m + offset,  sizeof(int64_t) * array_length);
                    QString tmp("%1, ");
                    QString string;
                    for (unsigned int j = 0; j < array_length - 1; ++j) {
                        string += tmp.arg(nums[j]);
                    }
                    string += QString::number(nums[array_length - 1]);
                    f->updateValue(string, static_cast<qreal>(nums[0]));
                } else {
                    // Single value
                    int64_t n;
                    memcpy(&n, m + offset, sizeof(int64_t));
                    f->updateValue(QString::number(n), static_cast<qreal>(n));
                }
                break;
            }
        }
    }
}

//-----------------------------------------------------------------------------
//QGCMAVLinkSystem
QGCMAVLinkSystem::QGCMAVLinkSystem(QObject* parent, quint8 id)
    : QObject(parent)
    , _id(id)
{
    qCDebug(MAVLinkInspectorLog) << "New Vehicle:" << id;
}

//-----------------------------------------------------------------------------
QGCMAVLinkSystem::~QGCMAVLinkSystem()
{
    _messages.clearAndDeleteContents();
}

//-----------------------------------------------------------------------------
//找到消息
QGCMAVLinkMessage* QGCMAVLinkSystem::findMessage(uint32_t id, uint8_t cid)
{
    for(int i = 0; i < _messages.count(); i++) {
        QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(_messages.get(i));
        if(m) {
            if(m->id() == id && m->cid() == cid) {
                return m;
            }
        }
    }
    return nullptr;
}

//-----------------------------------------------------------------------------
int QGCMAVLinkSystem::findMessage(QGCMAVLinkMessage* message)
{
    for(int i = 0; i < _messages.count(); i++) {
        QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(_messages.get(i));
        if(m && m == message) {
            return i;
        }
    }
    return -1;
}

//-----------------------------------------------------------------------------
//重置
void QGCMAVLinkSystem::_resetSelection()
{
    for(int i = 0; i < _messages.count(); i++) {
        QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(_messages.get(i));
        if(m && m->selected()) {
            m->setSelected(false);
            emit m->selectedChanged();
        }
    }
}

//-----------------------------------------------------------------------------
//设置选中
void QGCMAVLinkSystem::setSelected(int sel)
{
    if(sel < _messages.count()) {
        _selected = sel;
        emit selectedChanged();
        _resetSelection();
        QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(_messages.get(sel));
        if(m && !m->selected()) {
            m->setSelected(true);
            emit m->selectedChanged();
        }
    }
}

//-----------------------------------------------------------------------------
//QGCMAVLinkMessage消息的一个排序 按照name排序
static bool messages_sort(QObject* a, QObject* b)
{
    QGCMAVLinkMessage* aa = qobject_cast<QGCMAVLinkMessage*>(a);
    QGCMAVLinkMessage* bb = qobject_cast<QGCMAVLinkMessage*>(b);
    if(!aa || !bb) return false;
    if(aa->name() == bb->name())
        return aa->name() < bb->name();
    return aa->name() < bb->name();
}

//-----------------------------------------------------------------------------
//添加消息
void QGCMAVLinkSystem::append(QGCMAVLinkMessage* message)
{
    //-- Save selected message
    QGCMAVLinkMessage* selectedMsg = nullptr;
    if(_messages.count()) {
        selectedMsg = qobject_cast<QGCMAVLinkMessage*>(_messages.get(_selected));
    } else {
        //-- First message
        message->setSelected(true);
    }
    _messages.append(message);
    //-- Sort messages by id and then cid 按id和cid排序消息
    if (_messages.count() > 0) {
        _messages.beginReset();
        //std的srot方法创两个迭代器指针和排序方法
        std::sort(_messages.objectList()->begin(), _messages.objectList()->end(), messages_sort);
        _messages.endReset();
        _checkCompID(message);
    }
    //-- Remember selected message 记录当前选择的消息
    if(selectedMsg) {
        int idx = findMessage(selectedMsg);
        if(idx >= 0) {
            _selected = idx;
            emit selectedChanged();
        }
    }
}

//-----------------------------------------------------------------------------
void QGCMAVLinkSystem::_checkCompID(QGCMAVLinkMessage* message)
{
    if(_compIDsStr.isEmpty()) {
        _compIDsStr << tr("Comp All");
    }
    if(!_compIDs.contains(static_cast<int>(message->cid()))) {
        int cid = static_cast<int>(message->cid());
        _compIDs.append(cid);
        _compIDsStr << tr("Comp %1").arg(cid);
        emit compIDsChanged();
    }
}

//-----------------------------------------------------------------------------
MAVLinkChartController::MAVLinkChartController(MAVLinkInspectorController *parent, int index)
    : QObject(parent)
    , _index(index)
    , _controller(parent)
{
    //每隔一定时间更新图
    connect(&_updateSeriesTimer, &QTimer::timeout, this, &MAVLinkChartController::_refreshSeries);
    //更新x范围
    updateXRange();
}

//-----------------------------------------------------------------------------
void MAVLinkChartController::setRangeYIndex(quint32 r)
{
    if(r < static_cast<quint32>(_controller->rangeSt().count())) {
        _rangeYIndex = r;
        qreal range = _controller->rangeSt()[static_cast<int>(r)]->range;
        emit rangeYIndexChanged();
        //-- If not Auto, use defined range
        if(_rangeYIndex > 0) {
            _rangeYMin = -range;
            emit rangeYMinChanged();
            _rangeYMax = range;
            emit rangeYMaxChanged();
        }
    }
}

//-----------------------------------------------------------------------------
void MAVLinkChartController::setRangeXIndex(quint32 t)
{
    _rangeXIndex = t;
    emit rangeXIndexChanged();
    updateXRange();
}

//-----------------------------------------------------------------------------
void MAVLinkChartController::updateXRange()
{
    if(_rangeXIndex < static_cast<quint32>(_controller->timeScaleSt().count())) {
        qint64 t = static_cast<qint64>(QGC::bootTimeMilliseconds());
        _rangeXMax = QDateTime::fromMSecsSinceEpoch(t);
        _rangeXMin = QDateTime::fromMSecsSinceEpoch(t - _controller->timeScaleSt()[static_cast<int>(_rangeXIndex)]->timeScale);
        emit rangeXMinChanged();
        emit rangeXMaxChanged();
    }
}

//-----------------------------------------------------------------------------
void MAVLinkChartController::updateYRange()
{
    if(_chartFields.count()) {
        qreal vmin  = std::numeric_limits<qreal>::max();
        qreal vmax  = std::numeric_limits<qreal>::min();
        for(int i = 0; i < _chartFields.count(); i++) {
            QObject* object = qvariant_cast<QObject*>(_chartFields.at(i));
            QGCMAVLinkMessageField* pField = qobject_cast<QGCMAVLinkMessageField*>(object);
            if(pField) {
                if(vmax < pField->rangeMax()) vmax = pField->rangeMax();
                if(vmin > pField->rangeMin()) vmin = pField->rangeMin();
            }
        }
        if(std::abs(_rangeYMin - vmin) > 0.000001) {
            _rangeYMin = vmin;
            emit rangeYMinChanged();
        }
        if(std::abs(_rangeYMax - vmax) > 0.000001) {
            _rangeYMax = vmax;
            emit rangeYMaxChanged();
        }
    }
}

//-----------------------------------------------------------------------------
void MAVLinkChartController::_refreshSeries()
{
    updateXRange();
    for(int i = 0; i < _chartFields.count(); i++) {
        QObject* object = qvariant_cast<QObject*>(_chartFields.at(i));
        QGCMAVLinkMessageField* pField = qobject_cast<QGCMAVLinkMessageField*>(object);
        if(pField) {
            pField->updateSeries();
        }
    }
}

//-----------------------------------------------------------------------------
void MAVLinkChartController::addSeries(QGCMAVLinkMessageField* field, QAbstractSeries* series)
{
    if(field && series) {
        QVariant f = QVariant::fromValue(field);
        for(int i = 0; i < _chartFields.count(); i++) {
            if(_chartFields.at(i) == f) {
                return;
            }
        }
        _chartFields.append(f);
        field->addSeries(this, series);
        emit chartFieldsChanged();
        _updateSeriesTimer.start(UPDATE_FREQUENCY);
    }
}

//-----------------------------------------------------------------------------
void
MAVLinkChartController::delSeries(QGCMAVLinkMessageField* field)
{
    if(field) {
        field->delSeries();
        QVariant f = QVariant::fromValue(field);
        for(int i = 0; i < _chartFields.count(); i++) {
            if(_chartFields.at(i) == f) {
                _chartFields.removeAt(i);
                emit chartFieldsChanged();
                if(_chartFields.count() == 0) {
                    updateXRange();
                    _updateSeriesTimer.stop();
                }
                return;
            }
        }
    }
}

//-----------------------------------------------------------------------------
// MAVLinkInspectorController 构造函数
MAVLinkInspectorController::MAVLinkInspectorController()
{
    //获取MultiVehicleManager
    MultiVehicleManager* multiVehicleManager = qgcApp()->toolbox()->multiVehicleManager();
    //绑定vehicleAdded和vehicleRemoved信号
    connect(multiVehicleManager, &MultiVehicleManager::vehicleAdded,   this, &MAVLinkInspectorController::_vehicleAdded);
    connect(multiVehicleManager, &MultiVehicleManager::vehicleRemoved, this, &MAVLinkInspectorController::_vehicleRemoved);
    //获取MAVLinkProtocol
    MAVLinkProtocol* mavlinkProtocol = qgcApp()->toolbox()->mavlinkProtocol();
    //绑定新消息接收信号和时间信号
    connect(mavlinkProtocol, &MAVLinkProtocol::messageReceived, this, &MAVLinkInspectorController::_receiveMessage);
    connect(&_updateFrequencyTimer, &QTimer::timeout, this, &MAVLinkInspectorController::_refreshFrequency);
    _updateFrequencyTimer.start(1000);
    //获取MultiVehicleManager
    MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager();
    //绑定当前激活设备改变的信号
    connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkInspectorController::_setActiveVehicle);
    //构造_timeScaleSt 插入 5 10 30 60 四个值
    _timeScaleSt.append(new TimeScale_st(this, tr("5 Sec"),   5 * 1000));
    _timeScaleSt.append(new TimeScale_st(this, tr("10 Sec"), 10 * 1000));
    _timeScaleSt.append(new TimeScale_st(this, tr("30 Sec"), 30 * 1000));
    _timeScaleSt.append(new TimeScale_st(this, tr("60 Sec"), 60 * 1000));
    emit timeScalesChanged();
    //构造_rangeSt
    _rangeSt.append(new Range_st(this, tr("Auto"),    0));
    _rangeSt.append(new Range_st(this, tr("10,000"),  10000));
    _rangeSt.append(new Range_st(this, tr("1,000"),   1000));
    _rangeSt.append(new Range_st(this, tr("100"),     100));
    _rangeSt.append(new Range_st(this, tr("10"),      10));
    _rangeSt.append(new Range_st(this, tr("1"),       1));
    _rangeSt.append(new Range_st(this, tr("0.1"),     0.1));
    _rangeSt.append(new Range_st(this, tr("0.01"),    0.01));
    _rangeSt.append(new Range_st(this, tr("0.001"),   0.001));
    _rangeSt.append(new Range_st(this, tr("0.0001"),  0.0001));
    emit rangeListChanged();
}

//-----------------------------------------------------------------------------
MAVLinkInspectorController::~MAVLinkInspectorController()
{
    _charts.clearAndDeleteContents();
    _systems.clearAndDeleteContents();
}

//----------------------------------------------------------------------------------------
//获取_timeScales所有的label
QStringList MAVLinkInspectorController::timeScales()
{
    if(!_timeScales.count()) {
        for(int i = 0; i < _timeScaleSt.count(); i++) {
            _timeScales << _timeScaleSt[i]->label;
        }
    }
    return _timeScales;
}

//----------------------------------------------------------------------------------------
//获取_rangeSt所有的label
QStringList MAVLinkInspectorController::rangeList()
{
    if(!_rangeList.count()) {
        for(int i = 0; i < _rangeSt.count(); i++) {
            _rangeList << _rangeSt[i]->label;
        }
    }
    return _rangeList;
}

//----------------------------------------------------------------------------------------
//设置当前激活的设备
void MAVLinkInspectorController::_setActiveVehicle(Vehicle* vehicle)
{
    if(vehicle) {
        //根据设备找到QGCMAVLinkSystem
        QGCMAVLinkSystem* v = _findVehicle(static_cast<uint8_t>(vehicle->id()));
        if(v) {
            _activeSystem = v;
        } else {
            _activeSystem = nullptr;
        }
    } else {
        _activeSystem = nullptr;
    }
    emit activeSystemChanged();
}

//-----------------------------------------------------------------------------
QGCMAVLinkSystem* MAVLinkInspectorController::_findVehicle(uint8_t id)
{
    for(int i = 0; i < _systems.count(); i++) {
        QGCMAVLinkSystem* v = qobject_cast<QGCMAVLinkSystem*>(_systems.get(i));
        if(v) {
            if(v->id() == id) {
                return v;
            }
        }
    }
    return nullptr;
}

//-----------------------------------------------------------------------------
void MAVLinkInspectorController::_refreshFrequency()
{
    for(int i = 0; i < _systems.count(); i++) {
        QGCMAVLinkSystem* v = qobject_cast<QGCMAVLinkSystem*>(_systems.get(i));
        if(v) {
            for(int i = 0; i < v->messages()->count(); i++) {
                QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(v->messages()->get(i));
                if(m) {
                    m->updateFreq();
                }
            }
        }
    }
}

//-----------------------------------------------------------------------------
// 添加vehicle
void MAVLinkInspectorController::_vehicleAdded(Vehicle* vehicle)
{
    QGCMAVLinkSystem* v = _findVehicle(static_cast<uint8_t>(vehicle->id()));
    if(v) {
        v->messages()->clearAndDeleteContents();
    } else {
        v = new QGCMAVLinkSystem(this, static_cast<uint8_t>(vehicle->id()));
        _systems.append(v);
        _systemNames.append(tr("System %1").arg(vehicle->id()));
    }
    emit systemsChanged();
}

//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::_vehicleRemoved(Vehicle* vehicle)
{
    QGCMAVLinkSystem* v = _findVehicle(static_cast<uint8_t>(vehicle->id()));
    if(v) {
        v->deleteLater();
        _systems.removeOne(v);
        QString vs = tr("System %1").arg(vehicle->id());
        _systemNames.removeOne(vs);
        emit systemsChanged();
    }
}

//-----------------------------------------------------------------------------
//接收消息
void MAVLinkInspectorController::_receiveMessage(LinkInterface*, mavlink_message_t message)
{
    QGCMAVLinkMessage* m = nullptr;
    QGCMAVLinkSystem* v = _findVehicle(message.sysid);
    if(!v) {
        v = new QGCMAVLinkSystem(this, message.sysid);
        _systems.append(v);
        _systemNames.append(tr("System %1").arg(message.sysid));
        emit systemsChanged();
        if(!_activeSystem) {
            _activeSystem = v;
            emit activeSystemChanged();
        }
    } else {
        m = v->findMessage(message.msgid, message.compid);
    }
    //如果之前没有这条消息
    if(!m) {
        m = new QGCMAVLinkMessage(this, &message);
        v->append(m);
    } else {
        m->update(&message);
    }
}

//-----------------------------------------------------------------------------
MAVLinkChartController*
MAVLinkInspectorController::createChart()
{
    MAVLinkChartController* pChart = new MAVLinkChartController(this, _charts.count());
    QQmlEngine::setObjectOwnership(pChart, QQmlEngine::CppOwnership);
    _charts.append(pChart);
    emit chartsChanged();
    return pChart;
}

//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::deleteChart(MAVLinkChartController* chart)
{
    if(chart) {
        for(int i = 0; i < _charts.count(); i++) {
            MAVLinkChartController* c = qobject_cast<MAVLinkChartController*>(_charts.get(i));
            if(c && c == chart) {
                _charts.removeOne(c);
                delete c;
                break;
            }
        }
        emit chartsChanged();
    }
}

//-----------------------------------------------------------------------------
MAVLinkInspectorController::TimeScale_st::TimeScale_st(QObject* parent, const QString& l, uint32_t t)
    : QObject(parent)
    , label(l)
    , timeScale(t)
{
}

//-----------------------------------------------------------------------------
MAVLinkInspectorController::Range_st::Range_st(QObject* parent, const QString& l, qreal r)
    : QObject(parent)
    , label(l)
    , range(r)
{
}

void MAVLinkInspectorController::setActiveSystem(int systemId)
{
    QGCMAVLinkSystem* v = _findVehicle(systemId);
    if (v != _activeSystem) {
        _activeSystem = v;
        emit activeSystemChanged();
    }
}

二.MavlinkConsoleController

该类主要处理一个mavlink控制台界面。主要操作就是通过串口发送命令和接收命令,并且处理历史命令的查询,文字格式的转换。上代码。

/****************************************************************************
 *
 *   (c) 2009-2017 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 "QmlObjectListModel.h"
#include "QGCPalette.h"
#include "Fact.h"
#include "FactMetaData.h"
#include <QObject>
#include <QString>
#include <QMetaObject>
#include <QStringListModel>

// Fordward decls
class Vehicle;

/// Controller for MavlinkConsole.qml.
/// MavlinkConsole.qml控制器。
class MavlinkConsoleController : public QStringListModel
{
    Q_OBJECT

public:
    MavlinkConsoleController();
    virtual ~MavlinkConsoleController();

    Q_INVOKABLE void sendCommand(QString command); //设置命令行

    Q_INVOKABLE QString historyUp(const QString& current); //上一个历史命令
    Q_INVOKABLE QString historyDown(const QString& current); //下一个历史命令

    /**
     * Get clipboard data and if it has N lines, execute first N-1 commands 获取剪贴板数据,如果它有N行,则先执行N-1个命令
     * @param command_pre prefix to data from clipboard
     * @return last line of the clipboard data
     */
    Q_INVOKABLE QString handleClipboard(const QString& command_pre);

    Q_PROPERTY(QString text                     READ getText                    CONSTANT)

private slots:
    void _setActiveVehicle  (Vehicle* vehicle);
    void _receiveData(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);

private:
    bool _processANSItext(QByteArray &line);
    void _sendSerialData(QByteArray, bool close = false);
    void writeLine(int line, const QByteArray &text);

    QString transformLineForRichText(const QString& line) const;

    QString getText() const;

    //存储历史命令的类
    class CommandHistory
    {
    public:
        void append(const QString& command);
        QString up(const QString& current);
        QString down(const QString& current);
    private:
        static constexpr int maxHistoryLength = 100;
        QList<QString> _history;
        int _index = 0;
    };

    static constexpr int _max_num_lines = 500; ///< history size (affects CPU load) 最大500个命令

    int           _cursor_home_pos{-1};
    int           _cursorY{0}; //光标y
    int           _cursorX{0}; //光标x
    QByteArray    _incoming_buffer; //输入的缓冲区
    Vehicle*      _vehicle{nullptr}; //设备列表
    QList<QMetaObject::Connection> _uas_connections; //设备连接
    CommandHistory _history; //历史命令
    QGCPalette     _palette; //调色板
};
/****************************************************************************
 *
 *   (c) 2009-2017 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.
 *
 ****************************************************************************/

#include "MavlinkConsoleController.h"
#include "QGCApplication.h"
#include "UAS.h"

#include <QClipboard>

MavlinkConsoleController::MavlinkConsoleController()
    : QStringListModel()
{
    //获取MultiVehicleManager
    auto *manager = qgcApp()->toolbox()->multiVehicleManager();
    //绑定激活设备改变的信号
    connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &MavlinkConsoleController::_setActiveVehicle);
    _setActiveVehicle(manager->activeVehicle());
}

MavlinkConsoleController::~MavlinkConsoleController()
{
    if (_vehicle) {
        QByteArray msg;
        _sendSerialData(msg, true);
    }
}

void MavlinkConsoleController::sendCommand(QString command)
{
    // there might be multiple commands, add them separately to the history
    // 可能有多个命令,将它们分别添加到历史记录中
    QStringList lines = command.split('\n');
    for (int i = 0; i < lines.size(); ++i) {
        if (lines[i].size() > 0) {
            //存储命令
            _history.append(lines[i]);
        }
    }
    command.append("\n");
    //发送命令
    _sendSerialData(qPrintable(command));
    _cursor_home_pos = -1;
}

QString MavlinkConsoleController::historyUp(const QString& current)
{
    return _history.up(current);
}

QString MavlinkConsoleController::historyDown(const QString& current)
{
    return _history.down(current);
}

//处理剪贴板
QString MavlinkConsoleController::handleClipboard(const QString& command_pre)
{
    //命令前缀加上剪贴板的内容
    QString clipboardData = command_pre + QApplication::clipboard()->text();
    int lastLinePos = clipboardData.lastIndexOf('\n');
    if (lastLinePos != -1) {
        QString commands = clipboardData.mid(0, lastLinePos);
        //发送
        sendCommand(commands);
        clipboardData = clipboardData.mid(lastLinePos+1);
    }
    return clipboardData;
}


//设置激活设备
void MavlinkConsoleController::_setActiveVehicle(Vehicle* vehicle)
{
    //遍历所有的_uas_connections 断开所有的绑定事件 对每一个uas
    for (auto &con : _uas_connections)
        disconnect(con);
    _uas_connections.clear();

    //设置新的设备
    _vehicle = vehicle;

    if (_vehicle) {
        _incoming_buffer.clear();
        // Reset the model
        setStringList(QStringList());
        _cursorY = 0;
        _cursorX = 0;
        _cursor_home_pos = -1;
        //创建并添加绑定mavlink串口控制信号到_uas_connections
        _uas_connections << connect(_vehicle, &Vehicle::mavlinkSerialControl, this, &MavlinkConsoleController::_receiveData);
    }
}

//接收消息
void MavlinkConsoleController::_receiveData(uint8_t device, uint8_t, uint16_t, uint32_t, QByteArray data)
{
    if (device != SERIAL_CONTROL_DEV_SHELL)
        return;

    // Append incoming data and parse for ANSI codes
    // 附加传入数据并解析ANSI代码
    _incoming_buffer.append(data);
    while(!_incoming_buffer.isEmpty()) {
        bool newline = false;
        int idx = _incoming_buffer.indexOf('\n');
        if (idx == -1) {
            // Read the whole incoming buffer 读取整个传入缓冲区
            idx = _incoming_buffer.size();
        } else {
            newline = true;
        }

        QByteArray fragment = _incoming_buffer.mid(0, idx);
        if (_processANSItext(fragment)) {
            writeLine(_cursorY, fragment);
            //新行则另起
            if (newline) {
                _cursorY++;
                _cursorX = 0;
                // ensure line exists 确保行存在
                int rc = rowCount();
                if (_cursorY >= rc) {
                    insertRows(rc, 1 + _cursorY - rc);
                }
            }
            //清空缓冲区
            _incoming_buffer.remove(0, idx + (newline ? 1 : 0));
        } else {
            // ANSI processing failed, need more data
            return;
        }
    }
}


//串口发送数据
void MavlinkConsoleController::_sendSerialData(QByteArray data, bool close)
{
    if (!_vehicle) {
        qWarning() << "Internal error";
        return;
    }

    SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
    if (!sharedLink) {
        return;
    }

    // Send maximum sized chunks until the complete buffer is transmitted
    // 发送最大大小的块,直到发送完整的缓冲区 MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN=70
    while(data.size()) {
        QByteArray chunk{data.left(MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN)};
        int dataSize = chunk.size();
        // Ensure the buffer is large enough, as the MAVLink parser expects MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN bytes
        // 确保缓冲区足够大,因为MAVLink解析器期望MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN字节
        chunk.append(MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN - chunk.size(), '\0');
        uint8_t flags = SERIAL_CONTROL_FLAG_EXCLUSIVE |  SERIAL_CONTROL_FLAG_RESPOND | SERIAL_CONTROL_FLAG_MULTI;
        if (close) flags = 0;
        //获取mavlink协议
        auto protocol = qgcApp()->toolbox()->mavlinkProtocol();
        //获取_vehicle primaryLink
        auto link = _vehicle->vehicleLinkManager()->primaryLink();
        mavlink_message_t msg;
        //发消息
        mavlink_msg_serial_control_pack_chan(
                    protocol->getSystemId(),
                    protocol->getComponentId(),
                    sharedLink->mavlinkChannel(),
                    &msg,
                    SERIAL_CONTROL_DEV_SHELL,
                    flags,
                    0,
                    0,
                    dataSize,
                    reinterpret_cast<uint8_t*>(chunk.data()),
                    _vehicle->id(), _vehicle->defaultComponentId());
        _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
        data.remove(0, chunk.size());
    }
}

//处理字符
bool MavlinkConsoleController::_processANSItext(QByteArray &line)
{
    // Iterate over the incoming buffer to parse off known ANSI control codes
    // 遍历传入缓冲区以解析出已知的ANSI控制代码
    for (int i = 0; i < line.size(); i++) {
        if (line.at(i) == '\x1B') {
            // For ANSI codes we expect at least 3 incoming chars
            if (i < line.size() - 2 && line.at(i+1) == '[') {
                // Parse ANSI code
                switch(line.at(i+2)) {
                    default:
                        continue;
                    case 'H':
                        if (_cursor_home_pos == -1) {
                            // Assign new home position if home is unset
                            _cursor_home_pos = _cursorY;
                        } else {
                            // Rewind write cursor position to home
                            _cursorY = _cursor_home_pos;
                            _cursorX = 0;
                        }
                        break;
                    case 'K':
                        // Erase the current line to the end
                        if (_cursorY < rowCount()) {
                            auto idx = index(_cursorY);
                            QString updated = data(idx, Qt::DisplayRole).toString();
                            int eraseIdx = _cursorX + i;
                            if (eraseIdx < updated.length()) {
                                setData(idx, updated.remove(eraseIdx, updated.length()));
                            }
                        }
                        break;
                    case '2':
                        // Check for sufficient buffer size
                        if ( i >= line.size() - 3)
                            return false;

                        if (line.at(i+3) == 'J' && _cursor_home_pos != -1) {
                            // Erase everything and rewind to home
                            bool blocked = blockSignals(true);
                            for (int j = _cursor_home_pos; j < rowCount(); j++)
                                setData(index(j), "");
                            blockSignals(blocked);
                            QVector<int> roles({Qt::DisplayRole, Qt::EditRole});
                            emit dataChanged(index(_cursorY), index(rowCount()), roles);
                        }
                        // Even if we didn't understand this ANSI code, remove the 4th char
                        line.remove(i+3,1);
                        break;
                }
                // Remove the parsed ANSI code and decrement the bufferpos
                line.remove(i, 3);
                i--;
            } else {
                // We can reasonably expect a control code was fragemented
                // Stop parsing here and wait for it to come in
                return false;
            }
        }
    }
    return true;
}

QString MavlinkConsoleController::transformLineForRichText(const QString& line) const
{
    QString ret = line.toHtmlEscaped().replace(" ","&nbsp;").replace("\t", "&nbsp;&nbsp;&nbsp;&nbsp;");

    if (ret.startsWith("WARN", Qt::CaseSensitive)) {
        ret.replace(0, 4, "<font color=\"" + _palette.colorOrange().name() + "\">WARN</font>");
    } else if (ret.startsWith("ERROR", Qt::CaseSensitive)) {
        ret.replace(0, 5, "<font color=\"" + _palette.colorRed().name() + "\">ERROR</font>");
    }

    return ret;
}

QString
MavlinkConsoleController::getText() const
{
    QString ret;
    if (rowCount() > 0) {
        ret = transformLineForRichText(data(index(0), Qt::DisplayRole).toString());
    }
    for (int i = 1; i < rowCount(); ++i) {
        ret += "<br>" + transformLineForRichText(data(index(i), Qt::DisplayRole).toString());
    }

    return ret;
}

void
MavlinkConsoleController::writeLine(int line, const QByteArray &text)
{
    auto rc = rowCount();
    if (line >= rc) {
        insertRows(rc, 1 + line - rc);
    }
    if (rowCount() > _max_num_lines) {
        int count = rowCount() - _max_num_lines;
        removeRows(0, count);
        line -= count;
        _cursorY -= count;
        _cursor_home_pos -= count;
        if (_cursor_home_pos < 0)
            _cursor_home_pos = -1;
    }
    auto idx = index(line);
    QString updated = data(idx, Qt::DisplayRole).toString();
    updated.replace(_cursorX, text.size(), text);
    setData(idx, updated);
    _cursorX += text.size();
}

void MavlinkConsoleController::CommandHistory::append(const QString& command)
{
    if (command.length() > 0) {

        // do not append duplicates
        if (_history.length() == 0 || _history.last() != command) {

            if (_history.length() >= maxHistoryLength) {
                _history.removeFirst();
            }
            _history.append(command);
        }
    }
    _index = _history.length();
}

QString MavlinkConsoleController::CommandHistory::up(const QString& current)
{
    if (_index <= 0)
        return current;

    --_index;
    if (_index < _history.length()) {
        return _history[_index];
    }
    return "";
}

QString MavlinkConsoleController::CommandHistory::down(const QString& current)
{
    if (_index >= _history.length())
        return current;

    ++_index;
    if (_index < _history.length()) {
        return _history[_index];
    }
    return "";
}

总结

该类主要讲解了AnalyzeView页面下mavlink相关操作的两个类,分别处理了mavlink消息的管理,和mavlink控制台的逻辑处理。

本文含有隐藏内容,请 开通VIP 后查看

微信公众号

今日签到

点亮在社区的每一天
去签到