qgc开发-添加控件

1、添加矩形框,在FlightDisplayView.qml中,Fly操作栏对应的组件id是toolstrip

        Rectangle{
            anchors.left: toolStrip.left
            anchors.top:  toolStrip.bottom
            anchors.topMargin: _margins * 2
            width: 00
            height: 40
            color: "red"
            radius: 4
            visible: true
            z: _panel.z+4
            Text {
                anchors.fill: parent
                text: qsTr("Request All Parameters")
            }
            MouseArea{
            anchors.fill: parent
            onClicked: {
            console.log("Request all Parameter is clicked!")
                QGroundControl.multiVehicleManager.activeVehicle.requestAllParameters()
            }
            }
        }

2、在Vehicle中添加函数实现
Vehicle.h中函数定义:

Q_INVOKABLE void requestAllParameters(void);

在这里插入图片描述
Vehicle.cc中完成函数实现:

void Vehicle::requestAllParameters()
{
    mavlink_message_t msg;
    mavlink_msg_param_request_list_pack_chan(
                _mavlink->getSystemId(),
                _mavlink->getComponentId(),
                priorityLink()->mavlinkChannel(),
                &msg,_id,MAV_COMP_ID_ALL
                );
    sendMessageOnLink(priorityLink(),msg);
    qDebug()<<"========send Vehicle::requestAllParameters========"<<_id<<MAV_COMP_ID_ALL;
}

在这里插入图片描述
3、mock回路验证:在mocklink.cc中

void MockLink::_handleParamRequestList(const mavlink_message_t& msg)
{
//    if (_failureMode == MockConfiguration::FailParamNoReponseToRequestList) {
//        return;
//    }

//    mavlink_param_request_list_t request;

//    mavlink_msg_param_request_list_decode(&msg, &request);

//    Q_ASSERT(request.target_system == _vehicleSystemId);
//    Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);

//    // Start the worker routine
//    _currentParamRequestListComponentIndex = 0;
//    _currentParamRequestListParamIndex = 0;
    mavlink_param_request_list_t request;
    mavlink_msg_param_request_list_decode(&msg, &request);
    qDebug()<<"message with param request list is received,and message id:"<<msg.msgid<<"target_system:"<<request.target_system<<"target_component"<<request.target_component;
}

在这里插入图片描述

  • 0
    点赞
  • 2
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值