PX4 QGC透明串口转发二--自定义Mavlink消息实现Q

2019-09-28  本文已影响0人  N2ED

2. 自定义Mavlink消息实现QGC和PX4 mavlink守护进程通信

设计构想

QGC <--mavlink(数传)--> PX4(mavlink守护进程) <--uORB--> raw_serial_rtx <--UART--> device

2.1 自定义Mavlink消息

2.1.1 安装mavlink消息生成器

#下载源码
git clone https://github.com/mavlink/mavlink.git

#进入代码目录并更新子模块
cd mavlink
git submodule update --init --recursive

#可能报错需要安装,如果以前没有安装的话,目前python3的脚本还不怎么好使
sudo apt install python-tk
pip install future
#运行python脚本
python -m mavgenerate

2.1.2 创建消息定义XML

<?xml version="1.0"?>
<mavlink>
  <enums>
    <enum name="RSRTX_OPT_DEV_ENUM">
      <description>which port send to or receive </description>
      <entry value="0" name="DEV_TTYS0">
        <description>/dev/ttyS0</description>
      </entry>
      <entry value="1" name="DEV_TTYS1">
        <description>/dev/ttyS1</description>
      </entry>
      <entry value="2" name="DEV_TTYS2">
        <description>/dev/ttyS2</description>
      </entry>
      <entry value="3" name="DEV_TTYS3">
        <description>/dev/ttyS3</description>
      </entry>
      <entry value="4" name="DEV_TTYS4">
        <description>/dev/ttyS4</description>
      </entry>
      <entry value="5" name="DEV_TTYS5">
        <description>/dev/ttyS5</description>
      </entry>
      <entry value="6" name="DEV_TTYS6">
        <description>/dev/ttyS6</description>
      </entry>
    </enum>
  </enums>
  <!--ID不能与其他消息重复,v2使用24字节的ID号,因为前面踩坑的原因把97611,97612改成了211和213,应该不影响-->
  <messages>
    <!--从地面站到无人机-->
    <message id="211" name="RTX_GCS2UAV">
      <description>Message form GCS to UAV</description>
      <field type="uint8_t" name="dev">which port send to ,see RSRTX_OPT_DEV_ENUM</field>
      <field type="uint8_t" name="len">pkg lenght , 250 max</field>
      <!--需要根据实际调整,如果是数据大,实时性要求不高,尽量调大,反之亦然,整个包不能大于255,下同-->
      <field type="uint8_t[250]" name="data">data payload</field>
    </message>
    <!--从无人机到地面站-->
    <message id="213" name="RTX_UAV2GCS">
      <description>Message form UAV to GCS</description>
      <field type="uint8_t" name="dev">which port send this pkg,see RSRTX_OPT_DEV_ENUM</field>
      <field type="uint8_t" name="len">pkg lenght , 250 max</field>
      <field type="uint8_t[250]" name="data">data payload</field>
    </message>
  </messages>
</mavlink>
mavgen.png mavgen2.png
/*
#if MAVLINK_THIS_XML_IDX == MAVLINK_PRIMARY_XML_IDX
# define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_RTX_GCS2UAV, MAVLINK_MESSAGE_INFO_RTX_UAV2GCS}
# define MAVLINK_MESSAGE_NAMES {{ "RTX_GCS2UAV", 211 }, { "RTX_UAV2GCS", 213 }}
# if MAVLINK_COMMAND_24BIT
#  include "../mavlink_get_info.h"
# endif
#endif
*/

2.2 将消息添加到PX4上

2.2.1 拷贝头文件

...
#include "./mavlink_msg_smart_battery_status.h"
#include "./mavlink_msg_time_estimate_to_target.h"
#include "./mavlink_msg_wheel_distance.h"
//添加生成的头文件
#include "../rsrtx/rsrtx.h"
//在rsrtx.h 找到对应的校验和说明,按照由小自大的顺序插到原来的table中,mavlink_helper会使用排序二分法查找,如果不按顺序就找不到。
#define MAVLINK_MESSAGE_CRCS {{0, 50, 9, 9, 0, 0, 0},...{149, 200, 30, 60, 0, 0, 0},{211, 35, 252, 252, 0, 0, 0}, {213, 62, 252, 252, 0, 0, 0},{230, 163, 42, 42, 0, 0, 0},...}

//在rsrtx.h 找到对应宏定义,按照id号排序,在QGC里拍了,这里也跟着按顺序排吧
#define MAVLINK_MESSAGE_INFO {...,MAVLINK_MESSAGE_INFO_LANDING_TARGET,MAVLINK_MESSAGE_INFO_RTX_GCS2UAV, MAVLINK_MESSAGE_INFO_RTX_UAV2GCS, MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS,...}

//在rsrtx.h 找到对应宏定义,插到最后,应该是按字母表排序,没找到地方使用
#define MAVLINK_MESSAGE_NAMES {...{ "RTX_GCS2UAV", 211 }, { "RTX_UAV2GCS", 213 }}

2.2.2 编写收发代码

#pragma once
#include "mavlink_bridge_header.h"
#include <drivers/drv_hrt.h>

class Mavlink;

class MavlinkRawSerialRTX
{
public:
    explicit MavlinkRawSerialRTX(Mavlink *mavlink);
    ~MavlinkRawSerialRTX();
    void handle_message(const mavlink_message_t *msg);
private:
    MavlinkRawSerialRTX(MavlinkRawSerialRTX &);
    MavlinkRawSerialRTX &operator = (const MavlinkRawSerialRTX &);

    int sendData(uint8_t dev,uint8_t len,uint8_t * data );

    Mavlink *_mavlink;
};
#include <stdio.h>
#include "mavlink_raw_serial_rtx.h"
#include "mavlink_main.h"

MavlinkRawSerialRTX::MavlinkRawSerialRTX(Mavlink *mavlink) :
    _mavlink(mavlink)
{
}

MavlinkRawSerialRTX::~MavlinkRawSerialRTX()
{
}

void
MavlinkRawSerialRTX::handle_message(const mavlink_message_t *msg)
{
    //接收消息
    switch (msg->msgid){
        case MAVLINK_MSG_ID_RTX_GCS2UAV:{
            mavlink_rtx_gcs2uav_t pkg ;
            mavlink_msg_rtx_gcs2uav_decode(msg,&pkg);

            //收到之后原样回发
            sendData(pkg.dev,pkg.len,pkg.data);

        }
        default:
            break;
    }
}

//向地面站直接发送消息
int
MavlinkRawSerialRTX::sendData(uint8_t dev,uint8_t len,uint8_t * data ){
    if(len>sizeof(mavlink_rtx_uav2gcs_t::data) || _mavlink==nullptr )
        return -1;

    mavlink_rtx_uav2gcs_t pkg;
    pkg.dev = dev;
    pkg.len = len;
    memcpy(pkg.data,data,len);

    mavlink_msg_rtx_uav2gcs_send_struct(_mavlink->get_channel(),&pkg);

    return 0;
}
...
//加头文件
#include "mavlink_raw_serial_rtx.h"
//...

class MavlinkReceiver
{
public:
    //...
    MavlinkFTP          _mavlink_ftp;
    MavlinkLogHandler       _mavlink_log_handler;
    MavlinkTimesync         _mavlink_timesync;
    MavlinkMissionManager       _mission_manager;
    MavlinkParametersManager    _parameters_manager;
    //添加一个public成员
    MavlinkRawSerialRTX _mavlink_rawSerialRTX;
    //...
};

//...
//在构造函数中初始化_mavlink_rawSerialRTX成员
MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
    _mavlink(parent),
    _mavlink_ftp(parent),
    _mavlink_log_handler(parent),
    _mavlink_timesync(parent),
    _mission_manager(parent),
    _parameters_manager(parent),
    _mavlink_rawSerialRTX(parent),
    _p_bat_emergen_thr(param_find("BAT_EMERGEN_THR")),
    _p_bat_crit_thr(param_find("BAT_CRIT_THR")),
    _p_bat_low_thr(param_find("BAT_LOW_THR")),
    _p_flow_rot(param_find("SENS_FLOW_ROT")),
    _p_flow_maxr(param_find("SENS_FLOW_MAXR")),
    _p_flow_minhgt(param_find("SENS_FLOW_MINHGT")),
    _p_flow_maxhgt(param_find("SENS_FLOW_MAXHGT"))
{
    /* Make the attitude quaternion valid */
    _att.q[0] = 1.0f;
}
//...
void *
MavlinkReceiver::receive_thread(void *arg)
{
//...
    /* handle packet with log component */
    _mavlink_log_handler.handle_message(&msg);

    /* handle packet with timesync component */
    _mavlink_timesync.handle_message(&msg);

    /* 处理地面站向飞控发送的透明串口数据,在消息转发前处理 */
    _mavlink_rawSerialRTX.handle_message(&msg);

    /* handle packet with parent object */
    _mavlink->handle_message(&msg);
//...
}

2.3 将消息添加到QGC上并实现收发

本节中所有路径都是QGC工程下的相对路径

2.3.1 拷贝头文件

...
#include "./mavlink_msg_smart_battery_status.h"
#include "./mavlink_msg_time_estimate_to_target.h"
#include "./mavlink_msg_wheel_distance.h"
//添加生成的头文件
#include "../rsrtx/rsrtx.h"
//在rsrtx.h 找到对应的校验和说明,按照由小自大的顺序插到原来的table中,mavlink_helper会使用排序二分法查找,如果不按顺序就找不到。
#define MAVLINK_MESSAGE_CRCS {{0, 50, 9, 9, 0, 0, 0},...{149, 200, 30, 60, 0, 0, 0},{211, 35, 252, 252, 0, 0, 0}, {213, 62, 252, 252, 0, 0, 0},{230, 163, 42, 42, 0, 0, 0},...}

//在rsrtx.h 找到对应宏定义,也是要插入到149和230之间,位置基本不影响主要功能,但是MAvLinkeInspector会排序查找,找不到看不到
#define MAVLINK_MESSAGE_INFO {...,, MAVLINK_MESSAGE_INFO_GIMBAL_CONTROL,MAVLINK_MESSAGE_INFO_RTX_GCS2UAV, MAVLINK_MESSAGE_INFO_RTX_UAV2GCS, MAVLINK_MESSAGE_INFO_GIMBAL_TORQUE_CMD_REPORT,...}

//在rsrtx.h 找到对应宏定义,插到最后,应该是按字母表排序,没找到地方使用
#define MAVLINK_MESSAGE_NAMES {...{ "RTX_GCS2UAV", 211 }, { "RTX_UAV2GCS", 213 }}

QGCMAKE.png

2.3.2 设计一个简单的qml界面

import QtQuick          2.3
import QtQuick.Controls 1.2
import QtQuick.Dialogs  1.2
import QtQuick.Layouts      1.2
import QGroundControl               1.0
import QGroundControl.Palette       1.0
import QGroundControl.FactSystem    1.0
import QGroundControl.FactControls  1.0
import QGroundControl.Controls      1.0
import QGroundControl.ScreenTools   1.0
import QGroundControl.Controllers   1.0
AnalyzePage {
    id:              serialTestPage
    pageComponent:   pageComponent
    pageName:        "板载串口调试"
    pageDescription: "通过Mavlink远程调试飞控板载串口外接设备"
    property bool isLoaded: false

    Component {
        id: pageComponent

        ColumnLayout {
            id:     consoleColumn
            height: availableHeight
            width:  availableWidth

            Connections {
                target: rawSerialRtxTestController

                onDataChanged: {
                    // Keep the view in sync if the button is checked
                    if (isLoaded) {
                        if (followTail.checked) {
                            listview.positionViewAtEnd();
                        }
                    }
                }
            }

            Component {
                id: delegateItem
                Rectangle {
                    color:  qgcPal.windowShade
                    height: Math.round(ScreenTools.defaultFontPixelHeight * 0.1 + field.height)
                    width:  listview.width

                    QGCLabel {
                        id:          field
                        text:        display
                        width:       parent.width
                        wrapMode:    Text.NoWrap
                        font.family: ScreenTools.fixedFontFamily
                        anchors.verticalCenter: parent.verticalCenter
                    }
                }
            }

            QGCListView {
                Component.onCompleted: {
                    isLoaded = true
                }
                Layout.fillHeight: true
                Layout.fillWidth:  true
                clip:              true
                id:                listview
                model:             rawSerialRtxTestController
                delegate:          delegateItem

                onMovementStarted: {
                    followTail.checked = false
                }
            }

            RowLayout {
                Layout.fillWidth:   true

                QGCTextField {
                    id:               serialString
                    Layout.fillWidth: true
                    placeholderText:  "在此键入要发送的数据"
                    onAccepted: {
                        rawSerialRtxTestController.sendCommand(text)
                        text = ""
                    }
                    Keys.onPressed: {
                        if (event.key == Qt.Key_Up) {
                            text = rawSerialRtxTestController.historyUp(text);
                            event.accepted = true;
                        } else if (event.key == Qt.Key_Down) {
                            text = rawSerialRtxTestController.historyDown(text);
                            event.accepted = true;
                        }
                    }
                }

                QGCButton {
                    id:        followTail
                    text:      "显示最新"
                    checkable: true
                    checked:   true

                    onCheckedChanged: {
                        if (checked && isLoaded) {
                            listview.positionViewAtEnd();
                        }
                    }
                }
            }
        }
    } // Component
} // AnalyzePage
//...
MavlinkConsoleController {
    id: conController
}

RawSerialRtxTestController {
    id: rawSerialRtxTestController
}
//...
 Repeater {
    id: buttonRepeater
    model: ListModel {
        ListElement {
            buttonImage:        "/qmlimages/LogDownloadIcon"
            buttonText:         qsTr("Log Download")
            pageSource:         "LogDownloadPage.qml"
        }
        ListElement {
            buttonImage:        "/qmlimages/GeoTagIcon"
            buttonText:         qsTr("GeoTag Images")
            pageSource:         "GeoTagPage.qml"
        }
        ListElement {
            buttonImage:        "/qmlimages/MavlinkConsoleIcon"
            buttonText:         qsTr("Mavlink Console")
            pageSource:         "MavlinkConsolePage.qml"
        }
        //添加的连接,图标懒得改了
        ListElement {
            buttonImage:        "/qmlimages/MavlinkConsoleIcon"
            buttonText:         "板载串口调试"
            pageSource:         "RawSerilaRtxTest.qml"
        }
    }
 }
 //...

2.3.2 编写收发逻辑代码

//...
// MAVlink Serial Data
void mavlinkSerialControl(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);

//Raw Sersial Data 添加的信号函数根
void rawSerialDataReceived(uint8_t dev,uint8_t len,QByteArray data);
//...
//...
case MAVLINK_MSG_ID_SERIAL_CONTROL:
{
    mavlink_serial_control_t ser;
    mavlink_msg_serial_control_decode(&message, &ser);
    emit mavlinkSerialControl(ser.device, ser.flags, ser.timeout, ser.baudrate, QByteArray(reinterpret_cast<const char*>(ser.data), ser.count));
}
    break;
//过滤MAVLINK_MSG_ID_RTX_UAV2GCS消息,并发射rawSerialDataReceived信号
case MAVLINK_MSG_ID_RTX_UAV2GCS:
{
    mavlink_rtx_uav2gcs_t pkg;
    mavlink_msg_rtx_uav2gcs_decode(&message,&pkg);
    emit rawSerialDataReceived(pkg.dev,pkg.len,QByteArray(reinterpret_cast<const char*>(pkg.data),pkg.len));
}
    break;
//...
#pragma once
#include "QmlObjectListModel.h"
#include "Fact.h"
#include "FactMetaData.h"
#include <QObject>
#include <QString>
#include <QMetaObject>
#include <QStringListModel>
// Fordward decls
class Vehicle;
class RawSerialRtxTestController : public QStringListModel
{
    Q_OBJECT
public:
    RawSerialRtxTestController();
    virtual ~RawSerialRtxTestController();
    Q_INVOKABLE void sendCommand(QString command);
    Q_INVOKABLE QString historyUp(const QString& current);
    Q_INVOKABLE QString historyDown(const QString& current);
private slots:
    void _setActiveVehicle  (Vehicle* vehicle);
    //修改符合信号参数表
    void _receiveData(uint8_t dev,uint8_t len,QByteArray data);
private:
    bool _processANSItext(QByteArray &line);
    void _sendSerialData(QByteArray, bool close = false);
    void writeLine(int line, const QByteArray &text);
    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;
    };
    int           _cursor_home_pos;
    int           _cursor;
    QByteArray    _incoming_buffer;
    Vehicle*      _vehicle;
    QList<QMetaObject::Connection> _uas_connections;
    CommandHistory _history;
};
#include "RawSerialRtxTestController.h"
#include "QGCApplication.h"
#include "UAS.h"

RawSerialRtxTestController::RawSerialRtxTestController()
    : QStringListModel(),
      _cursor_home_pos{-1},
      _cursor{0},
      _vehicle{nullptr}
{
    auto *manager = qgcApp()->toolbox()->multiVehicleManager();
    //连接信号activeVehicleChanged
    connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &RawSerialRtxTestController::_setActiveVehicle);
    _setActiveVehicle(manager->activeVehicle());
}

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

void
RawSerialRtxTestController::sendCommand(QString command)
{
    _history.append(command);
    command.append("\n");
    _sendSerialData(qPrintable(command));
    _cursor_home_pos = -1;
    _cursor = rowCount();
}

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

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

void
RawSerialRtxTestController::_setActiveVehicle(Vehicle* vehicle)
{
    for (auto &con : _uas_connections)
        disconnect(con);
    _uas_connections.clear();

    _vehicle = vehicle;

    if (_vehicle) {
        _incoming_buffer.clear();
        // Reset the model
        setStringList(QStringList());
        _cursor = 0;
        _cursor_home_pos = -1;
        //将Vehicle::rawSerialDataReceived连接到_receiveData
        _uas_connections << connect(_vehicle, &Vehicle::rawSerialDataReceived, this, &RawSerialRtxTestController::_receiveData);
    }
}


//接收数据
void
RawSerialRtxTestController::_receiveData(uint8_t dev,uint8_t len,QByteArray data)
{

    auto rc = rowCount();
    if (_cursor >= rc) {
        insertRows(rc, 1 + _cursor - rc);
    }
    auto idx = index(_cursor);
    setData(idx,  QString("%1 ttyS6 -> * [%2]").arg(QTime::currentTime().toString("HH:mm:ss.zzz")).arg(len));
    _cursor++;

    // Append incoming data and parse for ANSI codes
    _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(_cursor, fragment);
            if (newline)
                _cursor++;
            _incoming_buffer.remove(0, idx + (newline ? 1 : 0));
        } else {
            // ANSI processing failed, need more data
            return;
        }
    }
}

//发送数据
void
RawSerialRtxTestController::_sendSerialData(QByteArray data, bool close)
{
    auto rc = rowCount();
    if (_cursor >= rc) {
        insertRows(rc, 1 + _cursor - rc);
    }
    auto idx = index(_cursor);

    if (!_vehicle) {
         setData(idx,  "飞控未连接");
        _cursor++;
        return;
    }

    // Send maximum sized chunks until the complete buffer is transmitted
    while(data.size()) {
        QByteArray chunk{data.left(sizeof(mavlink_rtx_gcs2uav_t::data))};
        uint8_t flags = SERIAL_CONTROL_FLAG_EXCLUSIVE |  SERIAL_CONTROL_FLAG_RESPOND | SERIAL_CONTROL_FLAG_MULTI;
        if (close) flags = 0;
        auto protocol = qgcApp()->toolbox()->mavlinkProtocol();
        auto priority_link = _vehicle->priorityLink();
        mavlink_message_t msg;
        //使用定义消息时的生成的编码函数,简单测试这里把dev数据段写死
        mavlink_msg_rtx_gcs2uav_pack_chan(
                   protocol->getSystemId(),
                   protocol->getComponentId(),
                   priority_link->mavlinkChannel(),
                   &msg,
                   RSRTX_OPT_DEV_ENUM::DEV_TTYS6,
                   chunk.size(),
                   reinterpret_cast<uint8_t*>(chunk.data()));

        setData(idx,  QString("%1 * -> ttyS6 [%2] ").arg(QTime::currentTime().toString("HH:mm:ss.zzz")).arg(chunk.size()));
         _cursor++;
        writeLine(_cursor, chunk);

        //发送
        _vehicle->sendMessageOnLink(priority_link, msg);
        data.remove(0, chunk.size());
    }

    _history.append(data);
}

bool
RawSerialRtxTestController::_processANSItext(QByteArray &line)
{
    // Iterate over the incoming buffer to parse off known ANSI control codes
    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 = _cursor;
                        } else {
                            // Rewind write cursor position to home
                            _cursor = _cursor_home_pos;
                        }
                        break;
                    case 'K':
                        // Erase the current line to the end
                        if (_cursor < rowCount()) {
                            setData(index(_cursor), "");
                        }
                        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;
                            roles.reserve(2);
                            roles.append(Qt::DisplayRole);
                            roles.append(Qt::EditRole);
                            emit dataChanged(index(_cursor), 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;
}

void
RawSerialRtxTestController::writeLine(int line, const QByteArray &text)
{
    auto rc = rowCount();
    if (line >= rc) {
        insertRows(rc, 1 + line - rc);
    }
    auto idx = index(line);
    setData(idx, data(idx, Qt::DisplayRole).toString() + text);
}

void RawSerialRtxTestController::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 RawSerialRtxTestController::CommandHistory::up(const QString& current)
{
    if (_index <= 0)
        return current;

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

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

    ++_index;
    if (_index < _history.length()) {
        return _history[_index];
    }
    return "";
}
//...
#include "MavlinkConsoleController.h"
//引入头文件
#include "RawSerialRtxTestController.h"
//...
qmlRegisterType<MavlinkConsoleController>       (kQGCControllers,                       1, 0, "MavlinkConsoleController");
//注册RawSerialRtxTestController为QML对象
qmlRegisterType<RawSerialRtxTestController>     (kQGCControllers,                       1, 0, "RawSerialRtxTestController");
//...

2.4 功能测试

QGCSERTEST0.png QGCSERTEST1.png MavlinkInspector.png

传送门: PX4 QGC透明串口转发

1. PX4串口读写
2.自定义Mavlink消息实现QGC和PX4 mavlink守护进程通信
3.自定义uORB消息实现,实现PX4模块间数据传递

上一篇 下一篇

猜你喜欢

热点阅读