ros标准版Action通讯

53 篇文章 0 订阅
43 篇文章 1 订阅

                             ros标准版Action通讯

Action通讯模型

Action通讯模型组成

ROS中,节点与节点间通讯,提供了新的方式,就是Action通讯。

Action通讯分为Client端Server端Client端负责给Server端发送指令,Server端接收到指令,根据自身的业务逻辑进行处理指令,处理过程中,可以反馈进度给为Client端,处理结束后将结构反馈给Client端

在Action通讯模型交互过程中,分为三个数据交互阶段:

  • client端请求阶段
  • server端进度反馈阶段
  • server端结果反馈阶段

对于Client端而言,可做的操作行为有两种:

  • 发送指令请求
  • 取消指令请求

对于Server而言,可做的操作行为有:

  • 响应进度信息
  • 响应结果信息

Action交互过程中的专有名称

Goal 请求指令

client端server端发送请求时所带的数据,我们称之为Goal

Feedback过程响应

server端进度反馈阶段,反馈给client端的数据,我们称之为Feedback

Result结果响应

server端结果反馈阶段,反馈给client端的数据,我们称之为Result

设计艺术

client端请求,server端响应,操作为异步的,通讯信息采用数据来规范,通过GoalFeedbackResult规定了统一操作数据的规范。

 

一.python

1.非ui版

1.1

client.py

#!/usr/bin/env python
# coding:utf-8
import rospy
from actionlib import ActionClient,ClientGoalHandle,CommState,TerminalState
from demo_actions.msg import CountNumberAction,CountNumberGoal

def transition_cb(goalHandle):

    commState = goalHandle.get_comm_state()
    if commState==CommState.PENDING:
        rospy.loginfo('PENDING')
    elif commState==CommState.ACTIVE:
        rospy.loginfo('ACTIVE')
    elif commState==CommState.DONE:
        rospy.loginfo('DONE')


def feedback_cb(goalHandle,feedback):
    rospy.loginfo('feedback')


if __name__ == '__main__':
    # 创建节点
    rospy.init_node("action_client")
    # action名字
    actionName = 'action_py'
    # 创建客户端
    client = ActionClient(actionName,CountNumberAction)
    # 等待
    client.wait_for_server()
    goal = CountNumberGoal()
    goal.max = 10
    goal.duration = 1
    # 发送指令
    goal = client.send_goal(goal,transition_cb,feedback_cb)
    # 阻塞
    rospy.spin()

1.2

server.py

#!/usr/bin/env python
# coding:utf-8
import rospy
from actionlib import ActionServer,ServerGoalHandle
from demo_actions.msg import CountNumberAction,CountNumberFeedback

def goal_cb(goalHandle):
    rospy.loginfo('receive goal')
    # goal = ServerGoalHandle()
    # 接受
    goalHandle.set_accepted()
    # 获取目标
    max = goalHandle.get_goal().max
    duration = goalHandle.get_goal().duration
    for i in range(1,max):
        feed = CountNumberFeedback()
        feed.percent = float(i)/max
        # 进度
        goalHandle.publish_feedback(feed)


def cancel_cb(goalHandle):
    rospy.loginfo('cancel goal')

if __name__ == '__main__':
    # 创建节点
    rospy.init_node("action_server")
    # action名字
    actionName = 'action_py'
    # server
    server = ActionServer(actionName,CountNumberAction,goal_cb,cancel_cb,auto_start=False)
    # 开启服务
    server.start()
    # 阻塞
    rospy.spin()

ui版

ActionClientWindow.py

#! /usr/bin/env python
# coding: utf-8
from PyQt5.QtWidgets import QWidget,QFormLayout,QLineEdit,QLabel,QPushButton
from PyQt5.QtCore import QTimer
from actionlib import ActionClient,ClientGoalHandle,CommState,TerminalState
from demo_actions.msg import CountNumberAction,CountNumberGoal,CountNumberResult,CountNumberFeedback
import rospy

class ActionClientWindow(QWidget):

    def __init__(self):
        super(ActionClientWindow, self).__init__()

        # 自定义 timer, 负责页面更新
        # update_timer = QTimer(self)
        # update_timer.setInterval(16)
        # update_timer.start()
        # # timer事件回调
        # update_timer.timeout.connect(self.on_update)

        # 设置title
        self.setWindowTitle("")

        layout = QFormLayout()
        self.setLayout(layout)

        self.le_max = QLineEdit("100")
        layout.addRow("数到多少", self.le_max)

        self.le_duration = QLineEdit("0.1")
        layout.addRow("间隔时间", self.le_duration)

        self.lb_percent = QLabel()
        layout.addRow("进度显示", self.lb_percent)

        self.lb_result = QLabel()
        layout.addRow("结果显示", self.lb_result)

        self.lb_result_state = QLabel()
        layout.addRow("结果状态", self.lb_result_state)

        btn_send = QPushButton("发送")
        layout.addRow(btn_send)

        btn_cancel = QPushButton("取消执行")
        layout.addRow(btn_cancel)

        btn_send.clicked.connect(self.click_send)
        btn_cancel.clicked.connect(self.click_cancel)

        # 创建Action client
        action_name = "/hello/action"
        self.client = ActionClient(action_name, CountNumberAction)

        self.handle = None

    def click_send(self):
        goal = CountNumberGoal()
        goal.max = long(self.le_max.text())
        goal.duration = float(self.le_duration.text())
        self.handle = self.client.send_goal(goal, self.transition_cb, self.feedback_cb)

    def transition_cb(self, handle):
        if not isinstance(handle, ClientGoalHandle):
            return
        comm_state = handle.get_comm_state()
        if comm_state == CommState.ACTIVE:
            print "ACTIVE"
        elif comm_state == CommState.DONE:
            # 干完活后的回调
            state = handle.get_terminal_state()
            if state == TerminalState.ABORTED:
                # sever中断
                self.lb_result_state.setText("sever中断")
            elif state == TerminalState.PREEMPTED:
                # client取消
                self.lb_result_state.setText("client取消")
            elif state == TerminalState.REJECTED:
                # client数据校验未通过
                self.lb_result_state.setText("client数据校验未通过")
            elif state == TerminalState.SUCCEEDED:
                # SUCCEEDED
                self.lb_result_state.setText("SUCCEEDED")
            result = handle.get_result()
            if not isinstance(result, CountNumberResult):
                return
            self.lb_result.setText(str(result.count))

    def feedback_cb(self, handle, feedback):
        if not isinstance(handle, ClientGoalHandle):
            return
        if not isinstance(feedback, CountNumberFeedback):
            return
        self.lb_percent.setText(str(feedback.percent))

    def click_cancel(self):
        print "cancel"
        if not isinstance(self.handle, ClientGoalHandle):
            return
        self.handle.cancel()

    # def on_update(self):
    #     # qt刷新
    #     self.update()
    #
    #     # 判断用户终止操作
    #     if rospy.is_shutdown():
    #         self.close()

ActionServerWindow.py

#! /usr/bin/env python
# coding: utf-8
from PyQt5.QtWidgets import QWidget, QTableView, QFormLayout, QPushButton, QLabel, QLineEdit
from PyQt5.QtGui import QStandardItemModel,QStandardItem
from PyQt5.QtCore import QTimer,pyqtSignal,Qt
from actionlib import ActionServer,ServerGoalHandle
from demo_actions.msg import CountNumberAction,CountNumberGoal,CountNumberFeedback,CountNumberResult
import rospy
import threading


class ActionServerWindow(QWidget):
    # 创建信号
    _update_signal = pyqtSignal()

    def __init__(self):
        super(ActionServerWindow, self).__init__()

        print threading.current_thread().name

        # 自定义 timer, 负责页面更新
        update_timer = QTimer(self)
        update_timer.setInterval(16)
        update_timer.start()
        # timer事件回调
        update_timer.timeout.connect(self.on_update)

        # 设置title
        self.setWindowTitle("")

        layout = QFormLayout()
        self.setLayout(layout)

        self.table = QTableView()
        layout.addRow(self.table)

        self.model = QStandardItemModel()
        self.table.setModel(self.model)

        # 为表格设计两个列
        self.model.setColumnCount(2)
        self.model.setHeaderData(0, Qt.Horizontal, "任务ID")
        self.model.setHeaderData(1, Qt.Horizontal, "终止操作")

        # 存放用户操作的数据
        self.map = {}

        # 绑定事件信号
        # btn = QPushButton("")
        # btn.clicked.connect(self.click)
        self._update_signal.connect(self.update_table)

        # 新建Action Server
        action_name = "/hello/action"
        self.server = ActionServer(action_name, CountNumberAction, self.goal_cb, self.cancel_cb, False)
        self.server.start()

    def goal_cb(self, handle):
        print threading.current_thread().name

        if not isinstance(handle, ServerGoalHandle):
            return
        # UI上需要显示 任务
        id = handle.get_goal_id().id
        self.map[id] = {
            "id": id,
            "isCanceled": False,
            "isAborted": False
        }

        # 在子线程中发送信号,调用ui更新
        self._update_signal.emit()
        # self.update_table()

        # 开启子线程,去执行任务
        thread = threading.Thread(target=self.do_goal, args=(handle,))
        thread.start()

    def update_table(self):

        # model清理
        self.model.clear()

        row = 0
        # 循环便利数据,将数据显示到table上
        for key in self.map.keys():
            value = self.map[key]

            self.model.setItem(row, 0, QStandardItem(value["id"]))
            self.model.setItem(row, 1, QStandardItem("xxxxxxxxxxxxxx"))

            btn = QPushButton("终止操作")
            btn.clicked.connect(lambda: self.do_aborted(value["id"]))
            self.table.setIndexWidget(self.model.index(row, 1), btn)

            row += 1

    def do_aborted(self, id):
        print "do_aborted: {}".format(id)
        # 修改记录的数据
        self.map[id]["isAborted"] = True

    def do_goal(self, handle):
        if not isinstance(handle, ServerGoalHandle):
            return
        # server接收到client goal指令
        id = handle.get_goal_id().id

        goal = handle.get_goal()
        if not isinstance(goal, CountNumberGoal):
            # 数据不符合要求
            handle.set_rejected()
            return

        # 1. 数据校验
        # 2. 完成业务
        # 3. 发布进度
        # 4. 发布结果
        # 5. 取消操作
        # 6. 中断操作

        # 1. 数据校验
        max = goal.max
        duration = goal.duration
        if max < 0 or duration < 0:
            handle.set_rejected()
            return

        # 数据校验成功后,手动更改状态为 Active
        handle.set_accepted()

        count = 0
        while not rospy.is_shutdown() and count < max:
            # 5. 取消操作:
            if self.map[id]["isCanceled"]:
                break

            # 6. 中断操作
            if self.map[id]["isAborted"]:
                break

            # 3. 发布进度
            feedback = CountNumberFeedback()
            feedback.percent = count * 100.0 / max
            handle.publish_feedback(feedback)

            # print feedback.percent

            # 2. 完成业务
            count += 1
            rospy.sleep(duration)

        # 4. 发布结果
        result = CountNumberResult()
        result.count = count

        if self.map[id]["isAborted"]:
            handle.set_aborted(result)
        elif self.map[id]["isCanceled"]:
            handle.set_canceled(result)
        else:
            handle.set_succeeded(result)

        # 清理数据
        del self.map[id]
        # 更新UI
        self._update_signal.emit()

    def cancel_cb(self, handle):
        if not isinstance(handle, ServerGoalHandle):
            return

        # 接收到取消的逻辑
        id = handle.get_goal_id().id
        # 设置数据
        self.map[id]["isCanceled"] = True

    def on_update(self):
        # qt刷新
        self.update()

        # 判断用户终止操作
        if rospy.is_shutdown():
            self.close()

gui_action_client.py

#! /usr/bin/env python
# coding: utf-8

import rospy
from PyQt5.QtWidgets import *
import sys
from ActionClientWindow import ActionClientWindow

if __name__ == '__main__':
    # 创建node
    node_name = "gui_action_client_node"
    rospy.init_node(node_name, anonymous=True)
    
    app = QApplication(sys.argv)
    
    window = ActionClientWindow()
    window.show()

    sys.exit(app.exec_())

gui_action_server.py

#! /usr/bin/env python
# coding: utf-8

import rospy
from PyQt5.QtWidgets import *
import sys
from ActionServerWindow import ActionServerWindow

if __name__ == '__main__':
    # 创建node
    node_name = "gui_action_server_node"
    rospy.init_node(node_name)
    
    app = QApplication(sys.argv)
    
    window = ActionServerWindow()
    window.show()

    sys.exit(app.exec_())

二.c++版

1.非ui版

1.1client.cpp

//
// Created by wt on 2020/7/6.
//
#include <iostream>
#include <ros/ros.h>
#include <actionlib/client/action_client.h>
#include <demo_actions/CountNumberAction.h>
#include <thread>

using namespace std;

//状态改变
void transition_cb(actionlib::ClientGoalHandle<demo_actions::CountNumberAction> goalHandle) {

//    ROS_INFO_STREAM("transition cb");
    const actionlib::CommState &commState = goalHandle.getCommState();
    //等待
    if (commState == actionlib::CommState::PENDING) {
        ROS_INFO_STREAM("pending");
    } else if (commState == actionlib::CommState::ACTIVE) {//激活
        ROS_INFO_STREAM("active");
    } else if (commState == actionlib::CommState::DONE) {//结束
        const actionlib::TerminalState &state = goalHandle.getTerminalState();
        if (state == actionlib::TerminalState::REJECTED) {
            ROS_INFO_STREAM("reject");
        } else if (state == actionlib::TerminalState::PREEMPTED) {
            ROS_INFO_STREAM("preempt");
        } else if (state == actionlib::TerminalState::ABORTED) {
            ROS_INFO_STREAM("aborted "<<goalHandle.getResult()->count);
        } else if (state == actionlib::TerminalState::SUCCEEDED) {
            ROS_INFO_STREAM("succeed "<<goalHandle.getResult()->count);
        } else if (state == actionlib::TerminalState::LOST) {//服务端没有做任何处理
            ROS_INFO_STREAM("lost");
        }
    }

}

//进度回调
void feedback_cb(actionlib::ClientGoalHandle<demo_actions::CountNumberAction> goalHandle,
                 const demo_actions::CountNumberFeedback::ConstPtr &feedback) {
    ROS_INFO_STREAM("feedback "<<feedback->percent);
    ROS_INFO_STREAM("feedback "<<this_thread::get_id());
}

int main(int argc, char *argv[]) {
    ROS_INFO_STREAM("main "<<this_thread::get_id());
    //节点名
    string nodeName = "action_client";
    //初始化节点
    ros::init(argc, argv, nodeName,ros::init_options::AnonymousName);
    //创建节点
    ros::NodeHandle node;
    /*-------------------------- asy --------------------------*/
    ros::AsyncSpinner spinner(1);
    spinner.start();
    /*-------------------------- action --------------------------*/
    //action名字
    string actionName = "action_gui";
    actionlib::ActionClient<demo_actions::CountNumberAction> client(node, actionName);
    //等到服务开启(阻塞线程 一直查看服务是否已经开启)
    client.waitForActionServerToStart();
    //目标
    demo_actions::CountNumberGoal goal;
    goal.max = 10;
    goal.duration = 1;
    //发送目标
    actionlib::ActionClient<demo_actions::CountNumberAction>::GoalHandle handle =
            client.sendGoal(goal,
                            transition_cb, feedback_cb);
    /*-------------------------- 取消 --------------------------*/
    ros::Rate rate(0.3);
    rate.sleep();
//    handle.cancel();
//    client.cancelAllGoals();

    //客户端不要停下来
    ros::waitForShutdown();
    return 0;
}

1.2 server.cpp

//
// Created by wt on 2020/7/6.
//
#include <iostream>
#include <ros/ros.h>
#include <actionlib/server/action_server.h>
#include <demo_actions/CountNumberAction.h>
#include <thread>


using namespace std;
//被取消
bool isCancel = false;

void done_cb(actionlib::ServerGoalHandle<demo_actions::CountNumberAction> goalHandle);

void done_cb(actionlib::ServerGoalHandle<demo_actions::CountNumberAction> goalHandle) {//2.处理
    long max = goalHandle.getGoal()->max;
    double duration = goalHandle.getGoal()->duration;
    ros::Rate rate(duration);

    //结果
    demo_actions::CountNumberResult result;
    for (int i = 1; i < max; ++i) {
        /*-------------------------- 中断状态 --------------------------*/
//        if(i==7){
//            //中断
//            result.count = i;
//            goalHandle.setAborted(result);
//            return;
//        }
        /*-------------------------- 取消 --------------------------*/
        if(isCancel){
            result.count = i;
            goalHandle.setCanceled(result);
            return;
        }
        //进度
        demo_actions::CountNumberFeedback feedback;
        feedback.percent = (double)i/max;
        //回调进度
        goalHandle.publishFeedback(feedback);
        //睡眠
        rate.sleep();
    }
    /*-------------------------- 成功状态 --------------------------*/
    //成功
    result.count = max;
    goalHandle.setSucceeded(result);
}

//收到目标回调
void goal_cb(actionlib::ServerGoalHandle<demo_actions::CountNumberAction> goalHandle){
    ROS_INFO_STREAM("goal cb "<<this_thread::get_id());
    ROS_INFO_STREAM("receive goal");
    //拒绝
//    goalHandle.setRejected();
    //1.决定是否要接受任务
    goalHandle.setAccepted();
    //开启新线程
    new std::thread(done_cb,goalHandle);
}


//收到取消指令
void cancel_cb(actionlib::ServerGoalHandle<demo_actions::CountNumberAction> goalHandle){
    ROS_INFO_STREAM("cancel goal");
    goalHandle.getGoalID().id;
    isCancel = true;
}
int main(int argc,char *argv[]){
    ROS_INFO_STREAM("thread "<<this_thread::get_id());
    //节点名
    string nodeName = "action_server";
    //初始化节点
    ros::init(argc,argv,nodeName);
    //创建节点
    ros::NodeHandle node;
    /*-------------------------- action --------------------------*/
    //action名字
    string actionName = "action_gui";
    actionlib::ActionServer<demo_actions::CountNumberAction> server(node,actionName,goal_cb,cancel_cb, false);
    //开启server
    server.start();
    //事件轮询
    ros::spin();
    return 0;
}

ui版

MainWindowClient.h

//
// Created by wt on 2020/7/6.
//

#ifndef DEMO_USE_ACTION_NEW_MAINWINDOWCLIENT_H
#define DEMO_USE_ACTION_NEW_MAINWINDOWCLIENT_H

#include <QWidget>
#include <QLineEdit>
#include <QPushButton>
#include <QFormLayout>
#include <QLabel>
#include <actionlib/client/action_client.h>
#include <demo_actions/CountNumberAction.h>

class MainWindowClient: public QWidget {
private:
    QFormLayout layout;
    QLineEdit maxEdit;
    QLineEdit durationEdit;
    QLabel feedLabel;
    QLabel activeLabel;
    QLabel doneLabel;
    QPushButton sendBtn;
    QPushButton preemptBtn;
    //client
    actionlib::ActionClient<demo_actions::CountNumberAction> *client;
    //发送之后的handle
    actionlib::ActionClient<demo_actions::CountNumberAction>::GoalHandle handle;
public:
    MainWindowClient(ros::NodeHandle node,QWidget* parent = Q_NULLPTR);

    ~MainWindowClient();
    //发送
    void send();
    //取消任务
    void cancel();
    //结果回调
    void transition_cb(actionlib::ClientGoalHandle<demo_actions::CountNumberAction> goalHandle);
    //进度回调
    void feedback_cb(actionlib::ClientGoalHandle<demo_actions::CountNumberAction> goalHandle, const demo_actions::CountNumberFeedback::ConstPtr &feedback);

};


#endif //DEMO_USE_ACTION_NEW_MAINWINDOWCLIENT_H

MainWindowClient.cpp

//
// Created by wt on 2020/7/6.
//

#include "MainWindowClient.h"

MainWindowClient::MainWindowClient(ros::NodeHandle node, QWidget *parent) : QWidget(parent), sendBtn("发送"),
                                                                            preemptBtn("取消") {
    //设置布局
    setLayout(&layout);
    //默认值
    maxEdit.setText("10");
    durationEdit.setText("1");
    //添加控件
    layout.addRow("max:", &maxEdit);
    layout.addRow("duration:", &durationEdit);
    layout.addRow("进度:", &feedLabel);
    layout.addRow("激活状态:", &activeLabel);
    layout.addRow("完成状态:", &doneLabel);
    layout.addRow("", &sendBtn);
    layout.addRow("", &preemptBtn);

    //创建client
    client = new actionlib::ActionClient<demo_actions::CountNumberAction>(node, "action_gui");
    //阻塞当前线程  服务是否连接上
//    client->waitForActionServerToStart();
    //信号和槽
    connect(&sendBtn, &QPushButton::clicked, this, &MainWindowClient::send);
    connect(&preemptBtn, &QPushButton::clicked, this, &MainWindowClient::cancel);
}

MainWindowClient::~MainWindowClient() {

}

void MainWindowClient::send() {
    //发送目标
    demo_actions::CountNumberGoal goal;
    goal.max = maxEdit.text().toInt();
    goal.duration = durationEdit.text().toDouble();
    //一定要保存成员变量
    handle = client->sendGoal(goal, boost::bind(&MainWindowClient::transition_cb, this, _1),
                              boost::bind(&MainWindowClient::feedback_cb, this, _1, _2));
}

void MainWindowClient::transition_cb(actionlib::ClientGoalHandle<demo_actions::CountNumberAction> goalHandle) {
    const actionlib::CommState &comState = goalHandle.getCommState();
    if (comState == actionlib::CommState::ACTIVE) {
        activeLabel.setText("激活");
    } else if (comState == actionlib::CommState::DONE) {
        const actionlib::TerminalState &terState = goalHandle.getTerminalState();
        if (terState == actionlib::TerminalState::REJECTED) {
            doneLabel.setText("拒绝");
        } else if (terState == actionlib::TerminalState::ABORTED) {
            doneLabel.setText("中止");
        } else if (terState == actionlib::TerminalState::PREEMPTED) {
            doneLabel.setText("取消");
        } else if (terState == actionlib::TerminalState::SUCCEEDED) {
            doneLabel.setText("成功");
        }
    } else if (comState == actionlib::CommState::PENDING) {
        activeLabel.setText("等待");
    }
}

void MainWindowClient::feedback_cb(actionlib::ClientGoalHandle<demo_actions::CountNumberAction> goalHandle,
                                   const demo_actions::CountNumberFeedback::ConstPtr &feedback) {
    feedLabel.setText(QString::number(feedback->percent));
}

void MainWindowClient::cancel() {
    handle.cancel();
}

client_gui.cpp

//
// Created by wt on 2020/7/6.
//
#include <iostream>
#include <ros/ros.h>
#include <QApplication>
#include "MainWindowClient.h"
using namespace std;

int main(int argc,char *argv[]){
    //节点名
    string nodeName = "action_client";
    //初始化节点
    ros::init(argc,argv,nodeName,ros::init_options::AnonymousName);
    //创建节点
    ros::NodeHandle node;
    /*-------------------------- asy --------------------------*/
    ros::AsyncSpinner spinner(1);
    spinner.start();
    /*-------------------------- qt --------------------------*/
    QApplication app(argc,argv);
    MainWindowClient w(node);
    w.show();

    return QApplication::exec();
}

MainWindowServer.h

//
// Created by wt on 2020/7/6.
//

#ifndef DEMO_USE_ACTION_NEW_MAINWINDOWSERVER_H
#define DEMO_USE_ACTION_NEW_MAINWINDOWSERVER_H

#include <QWidget>
#include <actionlib/server/action_server.h>
#include <demo_actions/CountNumberAction.h>
#include <thread>
#include <QVBoxLayout>
#include <QPushButton>
#include <QTableView>
#include <iostream>
#include <QStandardItemModel>

using namespace std;

struct Goal {
    string id;
    //是否被中止
    bool isAborted = false;
    //是否被取消
    bool isCanceled = false;
};

class MainWindowServer : public QWidget {
Q_OBJECT
private:
    //server
    actionlib::ActionServer<demo_actions::CountNumberAction> *server;
    //布局
    QVBoxLayout layout;
    QPushButton aboredAllBtn;
    QTableView tableView;
    //model
    QStandardItemModel model;
    //所有的任务 map<id,task>
    map<string, Goal> goals;
    //task id 是否被取消  是否被中止

public:
    MainWindowServer(ros::NodeHandle node, QWidget *parent = Q_NULLPTR);

    ~MainWindowServer();

    //收到目标回调
    void goal_cb(actionlib::ServerGoalHandle<demo_actions::CountNumberAction> goalHandle);

    //取消
    void cancel_cb(actionlib::ServerGoalHandle<demo_actions::CountNumberAction> goalHandle);

    //处理目标的方法
    void done_cb(actionlib::ServerGoalHandle<demo_actions::CountNumberAction> goalHandle);

    //更新列表
    void updateTableView();
signals:
    //更新ui信号
    void updateUI();
};


#endif //DEMO_USE_ACTION_NEW_MAINWINDOWSERVER_H

MainWindowServer.cpp

//
// Created by wt on 2020/7/6.
//

#include "MainWindowServer.h"

MainWindowServer::MainWindowServer(ros::NodeHandle node, QWidget *parent) : QWidget(parent), aboredAllBtn("中止") {
    //创建server
    server = new actionlib::ActionServer<demo_actions::CountNumberAction>(node, "action_gui",
                                                                          boost::bind(&MainWindowServer::goal_cb, this,
                                                                                      _1),
                                                                          boost::bind(&MainWindowServer::cancel_cb,
                                                                                      this, _1), false);
    server->start();
    /*-------------------------- 初始化ui --------------------------*/
    setLayout(&layout);
    layout.addWidget(&aboredAllBtn);
    layout.addWidget(&tableView);
    //设置model
    tableView.setModel(&model);
    //表头
    model.setHorizontalHeaderItem(0, new QStandardItem("ID"));
    model.setHorizontalHeaderItem(1, new QStandardItem("操作"));
    /*-------------------------- 绑定信号和槽 --------------------------*/
    connect(this, &MainWindowServer::updateUI, this, &MainWindowServer::updateTableView);
    connect(&aboredAllBtn,&QPushButton::clicked,[this]{
        //把所有的任务的isAborted变成true
        for (auto i = goals.begin(); i != goals.end(); ++i) {
            i->second.isAborted = true;
        }
    });
}

void MainWindowServer::done_cb(actionlib::ServerGoalHandle<demo_actions::CountNumberAction> goalHandle) {
    //获取当前任务状态,是否被取消
    string id = goalHandle.getGoalID().id;

    long max = goalHandle.getGoal()->max;
    double duration = goalHandle.getGoal()->duration;
    ros::Rate rate(duration);
        
    //结果
    demo_actions::CountNumberResult result;
    for (int i = 1; i < max; ++i) {
        /*-------------------------- 中断状态 --------------------------*/
        if(goals[id].isAborted){
            //中断
            result.count = i;
            goalHandle.setAborted(result);
            //删除当前任务
            goals.erase(id);
            // 再更新ui
            emit updateUI();
            return;
        }
        /*-------------------------- 取消 --------------------------*/
        if(goals[id].isCanceled){
            result.count = i;
            goalHandle.setCanceled(result);
            //删除当前任务
            goals.erase(id);
            // 再更新ui
            emit updateUI();
            return;
        }
        //进度
        demo_actions::CountNumberFeedback feedback;
        feedback.percent = (double) i / max;
        //回调进度
        goalHandle.publishFeedback(feedback);
        //睡眠
        rate.sleep();
    }
    /*-------------------------- 成功状态 --------------------------*/
    //成功
    result.count = max;
    goalHandle.setSucceeded(result);
    //删除当前任务
    goals.erase(id);
    // 再更新ui
    emit updateUI();
}

void MainWindowServer::goal_cb(actionlib::ServerGoalHandle<demo_actions::CountNumberAction> goalHandle) {
    ROS_INFO_STREAM("goal cb  " << this_thread::get_id());
    //1.决定是否要接受任务
    goalHandle.setAccepted();
    /*-------------------------- 添加到任务map中,更新界面 --------------------------*/
    Goal goal;
    string id = goalHandle.getGoalID().id;
    goal.id = id;
    //添加到map
    goals.insert({id, goal});
    //更新界面(主线程更新) 在主线程中更新
    //发送更新信号
    emit updateUI();
//    updateTableView();

    //开启线程处理
    new std::thread(&MainWindowServer::done_cb, this, goalHandle);
}

//取消
void MainWindowServer::cancel_cb(actionlib::ServerGoalHandle<demo_actions::CountNumberAction> goalHandle) {
    //获取任务id
    string id = goalHandle.getGoalID().id;
    //停下里任务,修改当前任务的isCanceled状态
    goals[id].isCanceled = true;
}

MainWindowServer::~MainWindowServer() {

}

//子线程更新界面就会出现问题
void MainWindowServer::updateTableView() {
    //清理列表
    model.clear();
    //表头
    model.setHorizontalHeaderItem(0, new QStandardItem("ID"));
    model.setHorizontalHeaderItem(1, new QStandardItem("操作"));

    int row = 0;
    //把所有的任务展示出来
    for (auto i = goals.begin(); i != goals.end(); ++i) {
        string id = i->second.id;
        //添加一条数据
        model.setItem(row, 0, new QStandardItem(QString(id.c_str())));
        model.setItem(row, 1, new QStandardItem(""));
        //按钮
        QPushButton *btn = new QPushButton("中止");
        //中止点击事件
        connect(btn,&QPushButton::clicked,[i]{
            //修改中止状态
            i->second.isAborted = true;
        });
        //把后面的控件替换成按钮
        tableView.setIndexWidget(model.index(row, 1), btn);
        ++row;
    }
}

server_gui.cpp

//
// Created by wt on 2020/7/6.
//
#include <iostream>
#include <ros/ros.h>
#include <QApplication>
#include "MainWindowServer.h"
#include <thread>
using namespace std;

int main(int argc,char *argv[]){
    ROS_INFO_STREAM("main "<<this_thread::get_id());
    //节点名
    string nodeName = "action_server";
    //初始化节点
    ros::init(argc,argv,nodeName);
    //创建节点
    ros::NodeHandle node;
    /*-------------------------- 异步 --------------------------*/
    ros::AsyncSpinner spinner(1);
    spinner.start();
    /*-------------------------- qt --------------------------*/
    QApplication app(argc,argv);
    MainWindowServer w(node);
    w.show();

    return QApplication::exec();
}

 

 

  • 0
    点赞
  • 8
    收藏
    觉得还不错? 一键收藏
  • 打赏
    打赏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

_无往而不胜_

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

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

余额充值