用自定义信号与曹函数来解决在子线程中不能调用QTimer定时器
报错:
QObject::startTimer: Timers cannot be started from another thread
(此方法区别与其他博主给的方案,其他博主给的方案是在子线程中创建QTimer定时器,我的方法是用信号和槽来处理,此方法的好处是可以在子线程中开启定时器,在其他线程或主线程中关闭定时器)
如何在ros的 SimpleActionClient的回调函数子线程中调用主线程创建的QTimer定时器
实例 1 :
#ifndef VISUALORIENTATION_CarStartServuceClient_H
#define VISUALORIENTATION_CarStartServuceClient_H
#include <Eigen/Geometry>
#include <opencv/cxeigen.hpp>
#include <opencv2/opencv.hpp>
#include <QtWidgets>
#include <QDebug>
#include <QComboBox>
#include <QHBoxLayout>
#include <QVBoxLayout>
#include "ros/ros.h"
#include <actionlib/client/simple_action_client.h>
#include "move_base_msgs/MoveBaseAction.h"
#include "move_base_msgs/MoveBaseGoal.h"
#include <ros/package.h>
#include <iostream>
#include <math.h>
#include <qrcode_srvs/qRcode.h>
#include "qrcode_msg/qRcode_msg.h"
#include "geometry_msgs/PoseWithCovarianceStamped.h"
#include <visualization_msgs/Marker.h>
#include <std_msgs/String.h>
#include <QtSql/QSqlDatabase>
#include <QtSql/QSqlQuery>
#include <QtSql/QSqlRecord>
#include <QTimer>
#include "utils/data.h"
#include "disinfect_msg/gono_msg.h"
/**
* 发送路点目标点
* 苏凯
* 2021-03-26
*/
using namespace std;
using namespace cv;
class CarStartServuceClient: public QWidget {
Q_OBJECT
public:
CarStartServuceClient(ros::NodeHandle *node, QWidget *parent = nullptr);
~CarStartServuceClient() ;
private:
ros::NodeHandle *node;
ros::Subscriber subscriber;
//等待5分钟执行下一条送餐指令: 1000*60*5
QTimer* waitGoalTimer;
//move_base 控制小车运动
// actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> ac_client;
actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> *ac_client;
private:
//SimpleActionClient 回调函数
void done_cb(const actionlib::SimpleClientGoalState &state,
const move_base_msgs::MoveBaseResult::ConstPtr &result);
//发送SimpleActionClient
void CarStartServuceClient::move_to_goal(double xGoal,double yGoal,double z,double w);
//自定义信号与槽
signals:
void backwaitGoalWithTimeSignal();
protected slots:
void sendwaitGoalWithTimeSignal();
};
#endif //VISUALORIENTATION_CarStartServuceClient_H
#include "carStartServuceClient.h"
#include "utils/Rotation3DUtils.h"
#include "utils/data.h"
#include <thread>
/**
* 发送目标点
* 苏凯
* 2021-03-26
*/
CarStartServuceClient::CarStartServuceClient(ros::NodeHandle *node, QWidget *parent): QWidget(parent),node(node) {
initWidgets();
bindSignal();
initRosCommunication();
}
CarStartServuceClient::~CarStartServuceClient(){
};
void CarStartServuceClient::initWidgets() {
//等待5分钟执行下一条送餐指令: 1000*60*5
waitGoalTimer= new QTimer(this);
waitGoalTimer->setInterval(1000*60*5);
}
void CarStartServuceClient::bindSignal() {
//等待5分钟执行下一条送餐指令: 1000*60*5
connect(waitGoalTimer, &QTimer::timeout, this, &CarStartServuceClient::waitGoalWithTime);
//自定义信号与曹, 调用waitGoalTimer 待5分钟执行下一条送餐指令: 1000*60*5 [处理多线程中不能调用QTimer定时器的问题]
connect(this,SIGNAL(backwaitGoalWithTimeSignal()),this,SLOT(sendwaitGoalWithTimeSignal()));
}
//自定义曹 调用waitGoalTimer 待5分钟执行下一条送餐指令: 1000*60*5 [处理多线程中不能调用QTimer定时器的问题]
void CarStartServuceClient::sendwaitGoalWithTimeSignal(){
//等待5分钟执行下一条送餐指令: 1000*60*5
waitGoalTimer->start();
cout << "多线程 sendwaitGoalWithTimeSignal!"<< endl;
}
//ros通讯
void CarStartServuceClient::initRosCommunication() {
ac_client = new actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction>(*node,"move_base");
}
//等待5分钟执行下一条送餐指令: 1000*60*5
void CarStartServuceClient::waitGoalWithTime(){
waitGoalTimer->stop();
isGoal=true;
cout << "等待5分钟执行下一条送餐指令"<< endl;
}
//SimpleActionClient 回调函数【此函数是在子线程中运行的,这个函数里不能直接操作主线程创建的QTimer定时器,需要通过自定义的信号与曹来间接的调用定时器】
void CarStartServuceClient::done_cb(const actionlib::SimpleClientGoalState &state,
const move_base_msgs::MoveBaseResult::ConstPtr &result){
if (state==actionlib::SimpleClientGoalState::SUCCEEDED){//服务端setSucced
ROS_INFO_STREAM("成功到达—new!");
cout << "成功到达—new!"<< endl;
//【子线程中通过自定义的信号与曹间接的调用定时器】
emit backwaitGoalWithTimeSignal();
}else if(state==actionlib::SimpleClientGoalState::ABORTED){//setAborted
ROS_INFO_STREAM("服务出错—new!");
cout << "服务出错—new!"<< endl;
}else if(state==actionlib::SimpleClientGoalState::PREEMPTED){//setAborted
ROS_INFO_STREAM("取消—new!");
cout << "取消—new!"<< endl;
}
}
//发送SimpleActionClient
void CarStartServuceClient::move_to_goal(double xGoal,double yGoal,double z,double w){
while (not ac_client->waitForServer())
cout << "等待move_base actionserver启动" << endl;
move_base_msgs::MoveBaseGoal goal;
//指定地图参考系
goal.target_pose.header.frame_id = "map";
goal.target_pose.header.stamp = ros::Time::now();
//移动目标设定位姿 xyz和四元数
goal.target_pose.pose.position.x = xGoal;
goal.target_pose.pose.position.y =yGoal;
goal.target_pose.pose.position.z= 0;
goal.target_pose.pose.orientation.x = 0.0;
goal.target_pose.pose.orientation.y = 0.0;
goal.target_pose.pose.orientation.z = z;
goal.target_pose.pose.orientation.w = w;
cout << "发送目标到actionserver ..." << endl;
//发送带有回调函数的SimpleActionClient
ac_client->sendGoal(goal,boost::bind(&CarStartServuceClient::done_cb,this,_1,_2),boost::bind(&CarStartServuceClient::active_cb,this),boost::bind(&CarStartServuceClient::feedback_cb,this,_1));
}
实例 2 :自定义信号和槽函数简单示例
class MyMainWindow : public QWidget
{
Q_OBJECT
public:
void MyMainWindow();
void SetNum(int);
signals:
void backwaitGoalWithTimeSignal(int); //自定义信号
public slots:
void sendwaitGoalWithTimeSignal(int); //自定义槽
};
//调用函数
void MyMainWindow::SetNum(int num)
{
//调用自定义信号执行自定义槽函数
emit backwaitGoalWithTimeSignal(num);
}
}
//自定义槽函数
void MyMainWindow::sendwaitGoalWithTimeSignal(int num)
{
cout<<num<<endl;
}
评论(0)
您还未登录,请登录后发表或查看评论