QGroundControl 添加自定义FactGroup

基于QGC4.1.2版本进行添加,首先由于QGC的原来对FactGroup定义均写在Vehicle.h和Vehicle.cc两个文件中,个人感觉都写在Vehicle文件下回导致文件过大,所以将FactGroup定义进行分离,写在各自的.h和.cc文件下,然后在Vehicle中include。

进入正题,添加自定义的FactGroup有一下几步(以VehicleGPSFactGroup为例):

  1. 新建.h文件然后定义FactGroup类

#pragma once

#include "FactGroup.h"
#include "QGCMAVLink.h"

class VehicleGPSFactGroup : public FactGroup
{
    Q_OBJECT

public:
    VehicleGPSFactGroup(QObject* parent = nullptr);

    Q_PROPERTY(Fact* lat                READ lat                CONSTANT)
    Q_PROPERTY(Fact* lon                READ lon                CONSTANT)
    Q_PROPERTY(Fact* mgrs               READ mgrs               CONSTANT)
    Q_PROPERTY(Fact* hdop               READ hdop               CONSTANT)
    Q_PROPERTY(Fact* vdop               READ vdop               CONSTANT)
    Q_PROPERTY(Fact* courseOverGround   READ courseOverGround   CONSTANT)
    Q_PROPERTY(Fact* count              READ count              CONSTANT)
    Q_PROPERTY(Fact* lock               READ lock               CONSTANT)

    Fact* lat               () { return &_latFact; }
    Fact* lon               () { return &_lonFact; }
    Fact* mgrs              () { return &_mgrsFact; }
    Fact* hdop              () { return &_hdopFact; }
    Fact* vdop              () { return &_vdopFact; }
    Fact* courseOverGround  () { return &_courseOverGroundFact; }
    Fact* count             () { return &_countFact; }
    Fact* lock              () { return &_lockFact; }

    static const char* _latFactName;
    static const char* _lonFactName;
    static const char* _mgrsFactName;
    static const char* _hdopFactName;
    static const char* _vdopFactName;
    static const char* _courseOverGroundFactName;
    static const char* _countFactName;
    static const char* _lockFactName;

private:
    Fact        _latFact;
    Fact        _lonFact;
    Fact        _mgrsFact;
    Fact        _hdopFact;
    Fact        _vdopFact;
    Fact        _courseOverGroundFact;
    Fact        _countFact;
    Fact        _lockFact;
};

  1. 新建.cc文件,进行类的初始化(不太确定这个是不是叫初始化)

#include "VehicleGPSFactGroup.h"

const char* VehicleGPSFactGroup::_latFactName =                 "lat";
const char* VehicleGPSFactGroup::_lonFactName =                 "lon";
const char* VehicleGPSFactGroup::_mgrsFactName =                "mgrs";
const char* VehicleGPSFactGroup::_hdopFactName =                "hdop";
const char* VehicleGPSFactGroup::_vdopFactName =                "vdop";
const char* VehicleGPSFactGroup::_courseOverGroundFactName =    "courseOverGround";
const char* VehicleGPSFactGroup::_countFactName =               "count";
const char* VehicleGPSFactGroup::_lockFactName =                "lock";

VehicleGPSFactGroup::VehicleGPSFactGroup(QObject* parent)
    : FactGroup(1000, ":/json/Vehicle/GPSFact.json", parent)
    , _latFact              (0, _latFactName,               FactMetaData::valueTypeDouble)
    , _lonFact              (0, _lonFactName,               FactMetaData::valueTypeDouble)
    , _mgrsFact             (0, _mgrsFactName,              FactMetaData::valueTypeString)
    , _hdopFact             (0, _hdopFactName,              FactMetaData::valueTypeDouble)
    , _vdopFact             (0, _vdopFactName,              FactMetaData::valueTypeDouble)
    , _courseOverGroundFact (0, _courseOverGroundFactName,  FactMetaData::valueTypeDouble)
    , _countFact            (0, _countFactName,             FactMetaData::valueTypeInt32)
    , _lockFact             (0, _lockFactName,              FactMetaData::valueTypeInt32)
{
    _addFact(&_latFact,                 _latFactName);
    _addFact(&_lonFact,                 _lonFactName);
    _addFact(&_mgrsFact,                _mgrsFactName);
    _addFact(&_hdopFact,                _hdopFactName);
    _addFact(&_vdopFact,                _vdopFactName);
    _addFact(&_courseOverGroundFact,    _courseOverGroundFactName);
    _addFact(&_lockFact,                _lockFactName);
    _addFact(&_countFact,               _countFactName);

    _latFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _lonFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _mgrsFact.setRawValue("");
    _hdopFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _vdopFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _courseOverGroundFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
}
  1. 添加对应的json文件,这一步有点问题,需要手动修改qgroundcontrol.qrc文件中文件别名

[
{
    "name":             "lat",
    "shortDescription": "Latitude",
    "type":             "double",
    "decimalPlaces":    7
},
{
    "name":             "lon",
    "shortDescription": "Longitude",
    "type":             "double",
    "decimalPlaces":    7
},
{
    "name":             "mgrs",
    "shortDescription": "MGRS Position",
    "type":             "string"
},
{
    "name":             "hdop",
    "shortDescription": "HDOP",
    "type":             "double",
    "decimalPlaces":    1
},
{
    "name":             "vdop",
    "shortDescription": "VDOP",
    "type":             "double",
    "decimalPlaces":    1
},
{
    "name":             "courseOverGround",
    "shortDescription": "Course Over Ground",
    "type":             "double",
    "decimalPlaces":    1,
    "units":            "deg"
},
{
    "name":             "lock",
    "shortDescription": "GPS Lock",
    "type":             "uint32",
    "enumStrings":      "None,None,2D Lock,3D Lock,3D DGPS Lock,3D RTK GPS Lock (float),3D RTK GPS Lock (fixed),Static (fixed)",
    "enumValues":       "0,1,2,3,4,5,6,7",
    "decimalPlaces":    0
},
{
    "name":             "count",
    "shortDescription": "Sat Count",
    "type":             "uint32"
}
]
  1. 在CMakeList.txt文件中添加新建的类文件,文件路径:qgroundcontrol\src\Vehicle

以上准备好之后开始在Vehicle.h和Vehicle.cc中添加FactGroup

  1. 在Vehicle.h文件中include FactGroup.h

  1. 在Vehicle.h文件中声明FactGroup

  1. 在Vehicle.h文件中添加FactGrounp对应的Q_PROPERTY,在qml读取数据使用

  1. 在Vehicle.h文件中定义Q_PROPERTY对应的READ 函数

  1. 在Vehicle.h中定义FactGroup对应的FactGroupName

  1. 在Vehicle.cc中初始化FactGroupName

  1. 在Vehicle.cc中Vehicle类初始化部分添加FactGroup

  1. 在Vehicle.cc中_commonInit函数中添加_addFactGroup()

  1. 对FactGroup成员赋值

完成以上内容后即完成了FactGroup 的添加,就可以在显示页面进行数据显示了。同时添加FactGroup后程序会将数据保存,和其他FactGroup存储在csv中。

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值