mirror of
https://github.com/chengyangkj/Ros_Qt5_Gui_App.git
synced 2025-09-15 12:58:58 +08:00
多线程spin解决卡顿问题
This commit is contained in:
parent
cbdb98130f
commit
46311012d1
41
README.md
41
README.md
@ -6,21 +6,23 @@
|
||||
|
||||
- 注意!未经作者的许可,此代码仅用于学习,不能用于其他用途。
|
||||
|
||||
|
||||
- 本仓库以分支的形式,长期维护各种有趣的ROS Qt项目,持续更新中.....
|
||||
- 本仓库以分支的形式,长期维护各种有趣的ROS 可视化项目,持续更新中.....
|
||||
|
||||
- 欢迎在issues提交bug
|
||||
|
||||
[](https://postimg.cc/N5zW0K2z)
|
||||
|
||||
## 菜单
|
||||
|
||||
- [安装教程](#安装教程)
|
||||
- [分支](#分支)
|
||||
- [使用说明](#使用说明)
|
||||
- [功能介绍](#功能介绍)
|
||||
- [开源协议](#开源协议)
|
||||
- [相关教程及交流群](#相关教程及交流群)
|
||||
## 一,菜单
|
||||
|
||||
## 安装教程
|
||||
- [安装教程](#二,安装教程)
|
||||
- [分支](#三,分支)
|
||||
- [使用说明](#四,使用说明)
|
||||
- [功能介绍](#五,功能介绍)
|
||||
- [开源协议](#六,开源协议)
|
||||
- [相关教程及交流群](#七,相关教程及交流群)
|
||||
|
||||
## 二,安装教程
|
||||
|
||||
#### 1,首先安装ros对qt pkg的支持(非必须)
|
||||
|
||||
@ -57,9 +59,9 @@ rosrun cyrobot_monitor cyrobot_monitor
|
||||
|
||||
- 借助 ROS windows版本,编译后可在win10平板使用,安装教程[古月学院 如何实现Windows ROS人机交互软件](https://class.guyuehome.com/detail/p_5fc5ab97e4b04db7c091f475/6)
|
||||
|
||||
## 分支
|
||||
## 三,分支
|
||||
|
||||
#### 1. Qml版本分支(开发中)
|
||||
#### 1. Qml版本demo
|
||||
|
||||
- ROS + QML + C++混合编程,使用qml自绘制地图,激光雷达点云等
|
||||
- [qml_hmi](https://github.com/chengyangkj/Ros_Qt5_Gui_App/tree/qml_hmi)
|
||||
@ -87,19 +89,24 @@ rosrun cyrobot_monitor cyrobot_monitor
|
||||
|
||||
#### 7,web版本分支 敬请期待
|
||||
|
||||
## 使用说明
|
||||
## 四,使用说明
|
||||
|
||||
- 使用前需要在菜单->设置 中进行必要设置
|
||||
### 1,连接主节点
|
||||
- 使用前需要在连接界面连接rosore主节点
|
||||
|
||||

|
||||
[](https://postimg.cc/Xr6kxWRv)
|
||||
|
||||
- ROS_MASTER_URI: ROS多机通讯主节点地址,如果只是单机通讯填127.0.0.1即可
|
||||
- ROS_IP: 软件运行的机器的IP 如果是单机通讯填127.0.0.1即可
|
||||
- 勾选使用环境变量连接就不使用界面设置的ROS_IP与ROS_MASTER_URI,需要在环境变量文件(~/.bashrc)配置好多机通讯环境变量,否则会导致连接失败,配置多机通讯教程[csdn 博客](https://blog.csdn.net/qq_38441692/article/details/98205852)
|
||||
- 其他一些话题设置
|
||||
- 勾选自动连接会在打开软件时进行自动连接
|
||||
- 注意!保存设置后需要重启软件生效
|
||||
- 重启软件后点击连接按钮即可连接master
|
||||
- 点击检测IP会自动检测本机IP并填入ros ip与ros master ip
|
||||
|
||||
### 2,设置
|
||||
|
||||
点击连接界面右下角,进行相关必要设置
|
||||
|
||||
## 功能介绍
|
||||
|
||||
#### 1,速度仪表盘
|
||||
|
||||
@ -133,6 +133,8 @@ private:
|
||||
QPolygon mapPonits;
|
||||
QPolygonF plannerPoints;
|
||||
QPolygonF laserPoints;
|
||||
int m_threadNum=4;
|
||||
int m_frameRate=40;
|
||||
//地图 0 0点坐标对应世界坐标系的坐标
|
||||
int m_mapOriginX;
|
||||
int m_mapOriginY;
|
||||
|
||||
@ -106,7 +106,8 @@ void LoginWidget::slot_writeSettings(){
|
||||
main_setting.setValue("main/turn_thre",ui->lineEdit_turnLightThre->text());
|
||||
main_setting.setValue("main/show_mode",ui->radioButton_robot->isChecked()?"robot":"control");
|
||||
main_setting.setValue("main/robotpic",ui->lineEdit_robotPic->text());
|
||||
// main_setting.setValue("odom_topic",ui->lineEdit_odom->text());
|
||||
main_setting.setValue("main/thread_num",ui->spinBox_thread_num->value());
|
||||
main_setting.setValue("main/framerate",ui->spinBox_frameRate->value());
|
||||
QStringList name_data;
|
||||
QStringList topic_data;
|
||||
QStringList format_data;
|
||||
@ -225,6 +226,8 @@ void LoginWidget::readSettings(){
|
||||
ui->lineEdit_odm->setText(main_setting.value("topic/topic_odom","raw_odom").toString());
|
||||
ui->lineEdit_power->setText(main_setting.value("topic/topic_power","power").toString());
|
||||
ui->lineEdit_turnLightThre->setText(main_setting.value("main/turn_thre","0.2").toString());
|
||||
ui->spinBox_frameRate->setValue(main_setting.value("main/framerate",40).toInt());
|
||||
ui->spinBox_thread_num->setValue(main_setting.value("main/thread_num",6).toInt());
|
||||
QSettings connect_info("cyrobot_monitor","connect_info");
|
||||
ui->lineEditMasterIp->setText(connect_info.value("master_url",m_qMasterIp).toString());
|
||||
|
||||
|
||||
@ -39,23 +39,9 @@ MainWindow::MainWindow(int argc, char** argv, QWidget *parent)
|
||||
setWindowIcon(QIcon(":/images/robot.png"));
|
||||
setWindowFlags(Qt::CustomizeWindowHint);//去掉标题栏
|
||||
//QObject::connect(&qnode, SIGNAL(rosShutdown()), this, SLOT(close()));
|
||||
QSettings windows_setting("cyrobot_monitor","windows");
|
||||
int x = windows_setting.value("WindowGeometry/x").toInt();
|
||||
int y = windows_setting.value("WindowGeometry/y").toInt();
|
||||
int width = windows_setting.value("WindowGeometry/width").toInt();
|
||||
int height = windows_setting.value("WindowGeometry/height").toInt();
|
||||
QDesktopWidget* desktopWidget = QApplication::desktop();
|
||||
QRect clientRect = desktopWidget->availableGeometry();
|
||||
QRect targRect0 = QRect(clientRect.width()/4,clientRect.height()/4,clientRect.width()/2,clientRect.height()/2);
|
||||
QRect targRect = QRect(x,y,width,height);
|
||||
if(width == 0|| height == 0 || x<0 || x>clientRect.width() || y<0 || y>clientRect.height())//如果上一次关闭软件的时候,窗口位置不正常,则本次显示在显示器的正中央
|
||||
{
|
||||
targRect = targRect0;
|
||||
}
|
||||
this->setGeometry(targRect);//设置主窗口的大小
|
||||
|
||||
ui.view_logging->setModel(qnode.loggingModel());
|
||||
connections();
|
||||
|
||||
}
|
||||
//订阅video话题
|
||||
void MainWindow::initVideos()
|
||||
@ -183,6 +169,21 @@ void MainWindow::initUis()
|
||||
ui.btn_control->hide();
|
||||
ui.settings_btn->hide();
|
||||
this->showFullScreen();
|
||||
}else{
|
||||
QSettings windows_setting("cyrobot_monitor","windows");
|
||||
int x = windows_setting.value("WindowGeometry/x").toInt();
|
||||
int y = windows_setting.value("WindowGeometry/y").toInt();
|
||||
int width = windows_setting.value("WindowGeometry/width").toInt();
|
||||
int height = windows_setting.value("WindowGeometry/height").toInt();
|
||||
QDesktopWidget* desktopWidget = QApplication::desktop();
|
||||
QRect clientRect = desktopWidget->availableGeometry();
|
||||
QRect targRect0 = QRect(clientRect.width()/4,clientRect.height()/4,clientRect.width()/2,clientRect.height()/2);
|
||||
QRect targRect = QRect(x,y,width,height);
|
||||
if(width == 0|| height == 0 || x<0 || x>clientRect.width() || y<0 || y>clientRect.height())//如果上一次关闭软件的时候,窗口位置不正常,则本次显示在显示器的正中央
|
||||
{
|
||||
targRect = targRect0;
|
||||
}
|
||||
this->setGeometry(targRect);//设置主窗口的大小
|
||||
}
|
||||
}
|
||||
|
||||
@ -867,10 +868,10 @@ void MainWindow::slot_minWindows(){
|
||||
this->showMinimized();
|
||||
}
|
||||
void MainWindow::slot_maxWindows(){
|
||||
if(this->isMaximized()){
|
||||
if(this->isFullScreen()){
|
||||
this->showNormal();
|
||||
}else{
|
||||
this->showMaximized();
|
||||
this->showFullScreen();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@ -38,6 +38,8 @@ QNode::QNode(int argc, char** argv ) :
|
||||
laser_topic=topic_setting.value("topic/topic_laser","scan").toString();
|
||||
pose_topic=topic_setting.value("topic/topic_amcl","amcl_pose").toString();
|
||||
show_mode=topic_setting.value("main/show_mode","control").toString();
|
||||
m_frameRate=topic_setting.value("main/framerate",40).toInt();
|
||||
m_threadNum=topic_setting.value("main/thread_num",6).toInt();
|
||||
qRegisterMetaType<sensor_msgs::BatteryState>("sensor_msgs::BatteryState");
|
||||
}
|
||||
|
||||
@ -50,7 +52,6 @@ QNode::~QNode() {
|
||||
}
|
||||
|
||||
bool QNode::init() {
|
||||
|
||||
ros::init(init_argc,init_argv,"cyrobot_monitor_"+show_mode.toStdString());
|
||||
if ( ! ros::master::check() ) {
|
||||
return false;
|
||||
@ -66,7 +67,7 @@ bool QNode::init(const std::string &master_url, const std::string &host_url) {
|
||||
std::map<std::string,std::string> remappings;
|
||||
remappings["__master"] = master_url;
|
||||
remappings["__hostname"] = host_url;
|
||||
ros::init(remappings,"cyrobot_monitor");
|
||||
ros::init(remappings,"cyrobot_monitor_"+show_mode.toStdString());
|
||||
if ( ! ros::master::check() ) {
|
||||
return false;
|
||||
}
|
||||
@ -92,7 +93,6 @@ void QNode::SubAndPubTopic(){
|
||||
cmd_pub = n.advertise<geometry_msgs::Twist>("cmd_vel", 1000);
|
||||
//激光雷达点云话题订阅
|
||||
m_laserSub=n.subscribe(laser_topic.toStdString(),1000,&QNode::laserScanCallback,this);
|
||||
//m_rosTimer=n.createTimer(ros::Duration(1.0),boost::bind(&QNode::transformPoint,boost::ref(m_tfListener)));
|
||||
//全局规划Path
|
||||
m_plannerPathSub=n.subscribe("/move_base/NavfnROS/plan",1000,&QNode::plannerPathCallback,this);
|
||||
image_transport::ImageTransport it(n);
|
||||
@ -279,12 +279,11 @@ void QNode::speedCallback(const nav_msgs::Odometry::ConstPtr& msg)
|
||||
emit speed_y(msg->twist.twist.linear.y);
|
||||
}
|
||||
void QNode::run() {
|
||||
ros::Rate loop_rate(20);
|
||||
ros::Rate loop_rate(m_frameRate);
|
||||
ros::AsyncSpinner spinner(m_threadNum);
|
||||
spinner.start();
|
||||
//当当前节点没有关闭时
|
||||
while ( ros::ok() ) {
|
||||
//调用消息处理回调函数
|
||||
ros::spinOnce();
|
||||
|
||||
loop_rate.sleep();
|
||||
}
|
||||
//如果当前节点关闭
|
||||
|
||||
@ -1245,7 +1245,7 @@ background-color:none</string>
|
||||
</rect>
|
||||
</property>
|
||||
<attribute name="label">
|
||||
<string>显示设置</string>
|
||||
<string>通用设置</string>
|
||||
</attribute>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_16">
|
||||
<item>
|
||||
@ -1337,6 +1337,30 @@ background-color:none</string>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_32">
|
||||
<item>
|
||||
<widget class="QLabel" name="label_12">
|
||||
<property name="text">
|
||||
<string>话题订阅线程数:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSpinBox" name="spinBox_thread_num"/>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_13">
|
||||
<property name="text">
|
||||
<string>FrameRate:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSpinBox" name="spinBox_frameRate"/>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_msg">
|
||||
<property name="maximumSize">
|
||||
|
||||
Loading…
Reference in New Issue
Block a user