QGC开发 显示双GPS/RTK信息以及自定义页面(ubuntu)

一、QGC开发 显示双GPS/RTK信息

1. 在sitl中进行仿真,虚拟出第二个GPS mavlink发送到地面站。

如下图中,在mavlink_msg_gps2_raw.h中找到发送第二组gps/rtk数据函数mavlink_msg_gps2_raw_send()发送,由于第一组已经有在发送,故只加入第二组。
QGC开发 显示双GPS/RTK信息以及自定义页面(ubuntu)_第1张图片
发送代码如下:

    mavlink_msg_gps2_raw_send  (
        chan,
        last_fix_time_ms(0)*(uint64_t)1000,
        status(0),
        loc.lat,        // in 1E7 degrees
        loc.lng,        // in 1E7 degrees
        loc.alt * 10UL, // in mm
        get_hdop(0),
        get_vdop(0),
        ground_speed(0)*100,  // cm/s
        ground_course(0)*100, // 1/100 degrees,
        num_sats(0),
        0,                    // TODO: Elipsoid height in mm
        0);   
        

2. 在QGC工程中加入解析第二个gps/rtl那包。

主要改了三个文件以及添加一个文件:分别为FirmwarePlugin.ccVehicle.ccVehicle.h + GPS2Indicator.qml
FirmwarePlugin.cc中如图中加入:

_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/GPS2Indicator.qml")));

QGC开发 显示双GPS/RTK信息以及自定义页面(ubuntu)_第2张图片

  • Vehicle.h 中,首先加入一个class
class VehicleGPS2FactGroup : public FactGroup
{
    Q_OBJECT

public:
    VehicleGPS2FactGroup(QObject* parent = nullptr);

    Q_PROPERTY(Fact* lat                READ lat                CONSTANT)
    Q_PROPERTY(Fact* lon                READ lon                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               (void) { return &_latFact; }
    Fact* lon               (void) { return &_lonFact; }
    Fact* hdop              (void) { return &_hdopFact; }
    Fact* vdop              (void) { return &_vdopFact; }
    Fact* courseOverGround  (void) { return &_courseOverGroundFact; }
    Fact* count             (void) { return &_countFact; }
    Fact* lock              (void) { return &_lockFact; }

    static const char* _latFactName;
    static const char* _lonFactName;
    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        _hdopFact;
    Fact        _vdopFact;
    Fact        _courseOverGroundFact;
    Fact        _countFact;
    Fact        _lockFact;
};

  • 再加入一些,声明:(由于改的部分比较零散,故用直接看git改的内容)
    QGC开发 显示双GPS/RTK信息以及自定义页面(ubuntu)_第3张图片
  • Vehicle.cc中加入mavlink解析函数:
    QGC开发 显示双GPS/RTK信息以及自定义页面(ubuntu)_第4张图片
  • 加入:
    QGC开发 显示双GPS/RTK信息以及自定义页面(ubuntu)_第5张图片QGC开发 显示双GPS/RTK信息以及自定义页面(ubuntu)_第6张图片

3. 最后新建一个qml文件

QGC开发 显示双GPS/RTK信息以及自定义页面(ubuntu)_第7张图片
—>
QGC开发 显示双GPS/RTK信息以及自定义页面(ubuntu)_第8张图片然后把下面的内容复制粘贴进去:

/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT 
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

import QtQuick          2.11
import QtQuick.Layouts  1.11

import QGroundControl                       1.0
import QGroundControl.Controls              1.0
import QGroundControl.MultiVehicleManager   1.0
import QGroundControl.ScreenTools           1.0
import QGroundControl.Palette               1.0

//-------------------------------------------------------------------------
//-- GPS Indicator
Item {
    id:             _root
    width:          (gps2ValuesColumn.x + gps2ValuesColumn.width) * 1.1
    anchors.top:    parent.top
    anchors.bottom: parent.bottom

    Component {
        id: gps2Info

        Rectangle {
            width:  gps2Col.width   + ScreenTools.defaultFontPixelWidth  * 3 //宽度
            height: gps2Col.height  + ScreenTools.defaultFontPixelHeight * 2 //高度
            radius: ScreenTools.defaultFontPixelHeight * 0.5                //半径
            color:  qgcPal.window                                           //颜色
            border.color:   qgcPal.text                                     //加边框

            Column {
                id:                 gps2Col
                spacing:            ScreenTools.defaultFontPixelHeight * 0.5
                width:              Math.max(gps2Grid.width, gps2Label.width)
                anchors.margins:    ScreenTools.defaultFontPixelHeight
                anchors.centerIn:   parent                                   // anchors.centerIn:parent,是将子控件放在父控件的正中心

                QGCLabel {
                    id:             gps2Label
                    text:           (activeVehicle && activeVehicle.gps2.count.value >= 0) ? qsTr("GPS Status") : qsTr("GPS Data Unavailable")
                    font.family:    ScreenTools.demiboldFontFamily          // 字体
                    anchors.horizontalCenter: parent.horizontalCenter       // 水平居中
                }

                GridLayout {
                    id:                 gps2Grid
                    visible:            (activeVehicle && activeVehicle.gps2.count.value >= 0)
                    anchors.margins:    ScreenTools.defaultFontPixelHeight
                    columnSpacing:      ScreenTools.defaultFontPixelWidth
                    anchors.horizontalCenter: parent.horizontalCenter
                    columns: 2

                    QGCLabel { text: qsTr("GPS Count:") }
                    QGCLabel { text: activeVehicle ? activeVehicle.gps2.count.valueString : qsTr("N/A", "No data to display") }
                    QGCLabel { text: qsTr("GPS Lock:") }
                    QGCLabel { text: activeVehicle ? activeVehicle.gps2.lock.enumStringValue : qsTr("N/A", "No data to display") }
                    QGCLabel { text: qsTr("HDOP:") }
                    QGCLabel { text: activeVehicle ? activeVehicle.gps2.hdop.valueString : qsTr("--.--", "No data to display") }
                    QGCLabel { text: qsTr("VDOP:") }
                    QGCLabel { text: activeVehicle ? activeVehicle.gps2.vdop.valueString : qsTr("--.--", "No data to display") }
                    QGCLabel { text: qsTr("Course Over Ground:") }
                    QGCLabel { text: activeVehicle ? activeVehicle.gps2.courseOverGround.valueString : activeVehicle.gps2.courseOverGround.valueString }
                }
            }
        }
    }

    QGCColoredImage {
        id:                 gps2Icon
        width:              height
        anchors.top:        parent.top
        anchors.bottom:     parent.bottom
        source:             "/qmlimages/Gps.svg"
        fillMode:           Image.PreserveAspectFit
        sourceSize.height:  height
        opacity:            (activeVehicle && activeVehicle.gps2.count.value >= 0) ? 1 : 0.5
        color:              qgcPal.buttonText
    }

    Column {
        id:                     gps2ValuesColumn
        anchors.verticalCenter: parent.verticalCenter
        anchors.leftMargin:     ScreenTools.defaultFontPixelWidth / 2
        anchors.left:           gps2Icon.right

        QGCLabel {
            anchors.horizontalCenter:   hdopValue.horizontalCenter
            visible:                    activeVehicle && !isNaN(activeVehicle.gps2.hdop.value)
            color:                      qgcPal.buttonText
            text:                       activeVehicle ? activeVehicle.gps2.count.valueString : ""
        }

        QGCLabel {
            id:         hdopValue
            visible:    activeVehicle && !isNaN(activeVehicle.gps2.hdop.value)
            color:      qgcPal.buttonText
            text:       activeVehicle ? activeVehicle.gps2.hdop.value.toFixed(1) : ""
        }
    }

    MouseArea {
        anchors.fill:   parent
        onClicked: {
            mainWindow.showPopUp(_root, gps2Info)
        }
    }
}

然后debug即可:

出现了两个GPS,由于在飞控中发下来的数据一模一样,所以存在两个一样,为了验证没问题,去飞控把下发的卫星数量改下。
把卫星改为40颗

    mavlink_msg_gps2_raw_send  (
        chan,
        last_fix_time_ms(0)*(uint64_t)1000,
        status(0),
        loc.lat,        // in 1E7 degrees
        loc.lng,        // in 1E7 degrees
        loc.alt * 10UL, // in mm
        get_hdop(0),
        get_vdop(0),
        ground_speed(0)*100,  // cm/s
        ground_course(0)*100, // 1/100 degrees,
        40,
        0,                    // TODO: Elipsoid height in mm
        0);   

第二个卫星显示是40,故接收以及显示成功:
QGC开发 显示双GPS/RTK信息以及自定义页面(ubuntu)_第9张图片
完成

二、自定义页面

用到的文件为:MainRootWindow.qmlMainToolBar.qml
效果如下图,功能可后续扩展:
QGC开发 显示双GPS/RTK信息以及自定义页面(ubuntu)_第10张图片

如下图,新建myadd.qml

QGC开发 显示双GPS/RTK信息以及自定义页面(ubuntu)_第11张图片


import QtQuick                  2.11
import QtQuick.Controls         2.4
import QtQuick.Layouts          1.11
import QtQuick.Dialogs          1.3
import QtQuick.Controls.Styles  1.4
import QtLocation               5.3
import QtPositioning            5.3

import QGroundControl                       1.0
import QGroundControl.Controls              1.0
import QGroundControl.ScreenTools           1.0
import QGroundControl.Palette               1.0
import QGroundControl.FlightMap             1.0
import QGroundControl.QGCMapEngineManager   1.0
import QGroundControl.FactSystem            1.0
import QGroundControl.FactControls          1.0

Rectangle{
    id:         myRect
    color:      "red"
    visible:     true
    x:          100
    y:          100
    width:      100
    height:     100
    Text {
        id: myTest
        text: qsTr("!!!!!")
        color: "blue"
        font.pointSize: 20
    }

MainRootWindow.qml中加入内容如下图:

QGC开发 显示双GPS/RTK信息以及自定义页面(ubuntu)_第12张图片

MainToolBar.qml中加入

QGC开发 显示双GPS/RTK信息以及自定义页面(ubuntu)_第13张图片

            QGCToolBarButton {
                id:                 addmyButton
                anchors.top:        parent.top
                anchors.bottom:     parent.bottom
                icon.source:        "/qmlimages/Plan.svg"
                onClicked: {
                    checked = true
                    mainWindow.showmyaddview()
                }
            }

编译后完成

你可能感兴趣的:(QGC,Mavlink,APM)