├── .gitignore ├── srv └── Order.srv ├── examples ├── 图片1.png └── 图片2.png ├── .idea ├── interact_slam.iml ├── misc.xml ├── vcs.xml ├── .gitignore └── modules.xml ├── LICENSE ├── readme.md ├── src ├── roshandle.h ├── Console.cpp ├── mainwindow.h ├── roshandle.cpp ├── mainwindow.cpp └── mainwindow.ui ├── CMakeLists.txt ├── scripts └── order_service.py └── package.xml /.gitignore: -------------------------------------------------------------------------------- 1 | /cmake-build-debug/ -------------------------------------------------------------------------------- /srv/Order.srv: -------------------------------------------------------------------------------- 1 | string request 2 | --- 3 | string response -------------------------------------------------------------------------------- /examples/图片1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chenjianqu/interact_slam/HEAD/examples/图片1.png -------------------------------------------------------------------------------- /examples/图片2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/chenjianqu/interact_slam/HEAD/examples/图片2.png -------------------------------------------------------------------------------- /.idea/interact_slam.iml: -------------------------------------------------------------------------------- 1 | 2 | -------------------------------------------------------------------------------- /.idea/misc.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /.idea/vcs.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | -------------------------------------------------------------------------------- /.idea/.gitignore: -------------------------------------------------------------------------------- 1 | # Default ignored files 2 | /shelf/ 3 | /workspace.xml 4 | # Datasource local storage ignored files 5 | /dataSources/ 6 | /dataSources.local.xml 7 | # Editor-based HTTP Client requests 8 | /httpRequests/ 9 | -------------------------------------------------------------------------------- /.idea/modules.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2022 ChenJianqu 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /readme.md: -------------------------------------------------------------------------------- 1 | # interact_slam 2 | 这是一个基于QT5的、用于ROS环境下的交互软件。 3 | **注:这是我本科毕业设计的一部分** 4 | 5 | ## Motivation 6 | ​ 在ROS程序开发中,很多情况下会遇到编写图形界面程序的需求。有几种方法可以在ROS中开发图形界面程序,若基于Python语言, 7 | 可以使用pyqt、thinker等图形界面库。若基于C++,最好的选择是Qt。作者存在通过点云库处理点云的需求,但是点云库缺乏一个稳定、高效的 8 | Python接口。因此,这里选择C++而不是Python开发交互程序,选择Qt作为开发框架。 9 | 虽然ROS官方支持Qt,比如可以使用 catkin_create_qt_pkg命令创建Qt功能包,而且ROS中很多基本工具也都是基于Qt的。但是ROS Kinect 10 | 版本只支持Qt4库,无法有效兼容当前流行的程序。因此,这里使用Levi-Armstrong开发的Qt Creator插件:ros_qtc_plugin,使用Qt5开发交互程序。 11 | 12 | ## Main 13 | 本程序基于Qt5 进行开发,程序的启动界面如下图所示。 14 | 15 | ![image](https://github.com/chenjianqu/interact_slam/blob/master/examples/%E5%9B%BE%E7%89%871.png) 16 | 17 | 交互程序主界面 18 | 19 | ​ 如上图所示,左上角的黑框是交互终端,用于显示文本交互的结果。左边中间是输入区域,可以通过文本输入,也可以通过语音进行输入。 20 | 左下角用于显示原始的RGB-D帧。中间四个显示区域分别用于显示实例分割的结果、稠密的三维点云、稀疏的三维特征点、导航地图。 21 | 其中稠密三维点云和稀疏三维特征点均使用点云控件显示,在点云控件中还可以显示实例包围框和移动机器人的运动轨迹。右侧是配置选项, 22 | 比如可以设置程序监听的话题(Topic)、设置显示的点云大小等。 23 | 24 | 25 | ​ 上面提到的用于渲染点云的控件是图形渲染库vtk编译生成的QVTKWidget组件。最著名的图形渲染库是OpenGL和VTK,这里选择后者 26 | 用于渲染点云。这是因为点云库的可视化类CloudViewer和PCLVisualizer是基于vtk图形库的,这里使用vtk可以兼容PCL提供的相关程序接口。 27 | 28 | ​ 节点需要轮循接收ROS话题消息,而Qt库也需要轮循监听交互事件,要解决这两者的冲突,一个可选的办法是构造两个线程:一个用于 29 | 接收ROS消息,另一个用于监听事件。但是在这里,ROS操作与Qt库的交互十分频繁,如果按照这种思路实现将非常复杂,也会造成性能下降。 30 | 解决办法是通过定时器轮循ROS消息,而把代码都放在同一个线程中,这样编写的代码更加清晰、高效。 31 | 32 | ![image](https://github.com/chenjianqu/interact_slam/blob/master/examples/%E5%9B%BE%E7%89%872.png) 33 | 34 | 运行中的交互界面 35 | 36 | 上图是正在运行的交互节点程序,由图可知交互节点可以完美的监测系统各个部分的运行结果。此外,用户还可以在图 4.10左侧的命令 37 | 输入框或语音输入命令中输入命令,接着交互节点会将输入的命令通过服务机制调用命令节点执行,然后显示命令执行的结果。 38 | 39 | -------------------------------------------------------------------------------- /src/roshandle.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2022, Chen Jianqu, Shanghai University 3 | * 4 | * This file is part of interact_slam. 5 | * 6 | * Licensed under the MIT License; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | 11 | #ifndef ROSHANDLE_H 12 | #define ROSHANDLE_H 13 | 14 | 15 | #include "mainwindow.h" 16 | #include "ros/ros.h" 17 | #include "image_transport/image_transport.h" 18 | #include "ros/master.h" 19 | #include 20 | #include 21 | 22 | #include 23 | #include 24 | #include 25 | #include 26 | #include 27 | #include 28 | 29 | #include 30 | #include 31 | #include 32 | 33 | 34 | class MainWindow; 35 | 36 | typedef pcl::PointCloud PointCloud; 37 | typedef pcl::PointCloud PointCloudXYZ; 38 | 39 | class RosHandle 40 | { 41 | public: 42 | ros::NodeHandle *nh; 43 | MainWindow *win; 44 | 45 | RosHandle(ros::NodeHandle *nh_); 46 | image_transport::ImageTransport *it; 47 | image_transport::Subscriber rawImageSub; 48 | image_transport::Subscriber instanceImageSub; 49 | ros::Subscriber navigationSub; 50 | ros::Subscriber denseMapSub; 51 | ros::Subscriber sparseMapSub; 52 | 53 | ros::ServiceClient orderService; 54 | tf::TransformListener* listener; 55 | 56 | void RawImageSubscribe(QString topic); 57 | void RawImageCallBack(const sensor_msgs::ImageConstPtr& msg); 58 | void InstanceImageSubscribe(QString topic); 59 | void InstanceImageCallBack(const sensor_msgs::ImageConstPtr& msg); 60 | void DenseMapSubscribe(QString topic); 61 | void DenseMapCallBack(const PointCloud::ConstPtr& msg); 62 | void SparseMapSubscribe(QString topic); 63 | void SparseMapCallBack(const PointCloudXYZ::ConstPtr& msg); 64 | void NavigationSubscribe(QString topic); 65 | void NavigationCallBack(const nav_msgs::OccupancyGrid& msg); 66 | 67 | QString SendOrder(QString msg); 68 | 69 | void PoseLookup(); 70 | 71 | QSet GetTopics(const QSet& message_types, const QList& transports); 72 | QList UpdateTopicList(QSet message_types); 73 | QList GetSpecificTopics(const QSet& message_types); 74 | QString GetAllTopics(); 75 | 76 | 77 | private: 78 | int rawImageCounter; 79 | 80 | 81 | }; 82 | 83 | #endif // INTERACT_H 84 | -------------------------------------------------------------------------------- /src/Console.cpp: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2022, Chen Jianqu, Shanghai University 3 | * 4 | * This file is part of interact_slam. 5 | * 6 | * Licensed under the MIT License; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | 11 | #include "ros/ros.h" 12 | #include "ros/master.h" 13 | #include "std_msgs/String.h" 14 | #include "cv_bridge/cv_bridge.h" 15 | #include "image_transport/image_transport.h" 16 | 17 | #include "roshandle.h" 18 | #include "mainwindow.h" 19 | 20 | 21 | #include 22 | #include 23 | 24 | 25 | #include 26 | #include 27 | #include 28 | #include 29 | #include 30 | 31 | 32 | using namespace std; 33 | 34 | 35 | class CallBackClass 36 | { 37 | public: 38 | MainWindow *win; 39 | RosHandle *rh; 40 | 41 | CallBackClass(ros::NodeHandle *nhp); 42 | 43 | void ImageCallback(const sensor_msgs::ImageConstPtr& msg); 44 | 45 | protected: 46 | unsigned long frameCounter; 47 | }; 48 | 49 | 50 | 51 | 52 | int main(int argc, char **argv) 53 | { 54 | ros::init(argc, argv, "Console"); 55 | ros::NodeHandle nh; 56 | 57 | QApplication a(argc,argv); 58 | 59 | CallBackClass cb(&nh); 60 | 61 | cb.win->timer->setInterval(200); 62 | cb.win->connect(cb.win->timer,&QTimer::timeout,[=]() 63 | { 64 | ros::spinOnce(); 65 | cb.rh->PoseLookup(); 66 | 67 | }); 68 | 69 | cb.win->timerSlow->setInterval(10000); 70 | cb.win->connect(cb.win->timerSlow,&QTimer::timeout,[=]() 71 | { 72 | cb.win->UpdateInstance(); 73 | }); 74 | 75 | cb.win->show(); 76 | 77 | cb.win->timer->start(); 78 | cb.win->timerSlow->start(); 79 | 80 | return a.exec(); 81 | } 82 | 83 | 84 | CallBackClass::CallBackClass(ros::NodeHandle *nhp) 85 | { 86 | frameCounter=0; 87 | 88 | rh=new RosHandle(nhp); 89 | win=new MainWindow(); 90 | 91 | win->rh=rh; 92 | rh->win=win; 93 | 94 | win->Init(); 95 | } 96 | 97 | 98 | 99 | void CallBackClass::ImageCallback(const sensor_msgs::ImageConstPtr& msg) 100 | { 101 | try{ 102 | //cv::imshow("view", cv_bridge::toCvShare(msg, "bgr8")->image); 103 | win->SetRawImage(cv_bridge::toCvShare(msg, "bgr8")->image); 104 | //cvWaitKey(1); 105 | 106 | }catch (cv_bridge::Exception& e) 107 | { 108 | ROS_ERROR("Could not convert from '%s' to 'bgr8'.", msg->encoding.c_str()); 109 | } 110 | } 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(interact_slam) 3 | 4 | add_compile_options(-std=c++11) 5 | 6 | find_package(catkin REQUIRED COMPONENTS 7 | cv_bridge 8 | image_transport 9 | message_filters 10 | roscpp 11 | rospy 12 | sensor_msgs 13 | std_msgs 14 | nav_msgs 15 | tf 16 | tf_conversions 17 | pcl_conversions 18 | message_generation 19 | ) 20 | 21 | find_package( 22 | Qt5 REQUIRED COMPONENTS Widgets 23 | ) 24 | 25 | 26 | set(CMAKE_AUTOMOC ON) 27 | set(CMAKE_AUTOUIC ON) 28 | set(CMAKE_INCLUDE_CURRENT_DIR ON) 29 | 30 | 31 | add_service_files(FILES Order.srv) 32 | generate_messages(DEPENDENCIES std_msgs) 33 | 34 | 35 | catkin_package( 36 | # INCLUDE_DIRS include 37 | # LIBRARIES interact_slam 38 | # CATKIN_DEPENDS cv_bridge image_transport message_filters roscpp sensor_msgs std_msgs tf tf_conversions 39 | # DEPENDS system_lib 40 | ) 41 | 42 | 43 | 44 | 45 | include_directories( 46 | include/interact_slam 47 | include 48 | ${catkin_INCLUDE_DIRS} 49 | /usr/local/include 50 | /usr/include/pcl-1.7 51 | /usr/include/eigen3 52 | /usr/include/vtk-6.2 53 | /usr/local/include/opencv 54 | /usr/local/include/opencv2 55 | ) 56 | 57 | 58 | set(LIBS 59 | -lpcl_common 60 | -lpcl_search 61 | -lpcl_features 62 | -lpcl_segmentation 63 | -lpcl_recognition 64 | -lpcl_visualization 65 | -L/usr/lib/x86_64-linux-gnu/ 66 | -L/usr/lib/x86_64-linux-gnu/ 67 | -lboost_system 68 | -lboost_thread 69 | -lvtkRenderingCore-6.2 70 | -lvtkCommonDataModel-6.2 71 | -lvtkCommonMath-6.2 72 | -lvtkCommonCore-6.2 73 | -lvtkGUISupportQt-6.2 74 | /usr/local/lib/libopencv_highgui.so 75 | /usr/local/lib/libopencv_core.so 76 | /usr/local/lib/libopencv_imgproc.so 77 | /usr/local/lib/libopencv_imgcodecs.so 78 | Qt5::Widgets 79 | ) 80 | 81 | 82 | set(SOURCES 83 | src/Console.cpp 84 | src/mainwindow.cpp 85 | ) 86 | 87 | set(FORMS 88 | src/mainwindow.ui 89 | ) 90 | 91 | add_library(roshandle src/roshandle.h src/roshandle.cpp) 92 | target_link_libraries(roshandle ${catkin_LIBRARIES} ${LIBS}) 93 | add_dependencies(roshandle ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 94 | set(LIBS3 95 | roshandle 96 | ) 97 | 98 | 99 | add_executable(${PROJECT_NAME}_node ${SOURCES} ${FORMS}) 100 | 101 | target_link_libraries( 102 | ${PROJECT_NAME}_node 103 | ${catkin_LIBRARIES} ${LIBS} ${LIBS3} 104 | ) 105 | 106 | -------------------------------------------------------------------------------- /scripts/order_service.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | # -*- coding: utf-8 -*- 3 | 4 | ######################################################### 5 | # Copyright (C) 2022, Chen Jianqu, Shanghai University 6 | # 7 | # This file is part of interact_slam. 8 | # 9 | # Licensed under the MIT License; 10 | # you may not use this file except in compliance with the License. 11 | ######################################################### 12 | 13 | 14 | 15 | import rospy 16 | from interact_slam.srv import * 17 | 18 | import cv2 19 | import json 20 | import urllib2 21 | import urllib 22 | import re 23 | import string 24 | 25 | 26 | keyWords=["人","自行车","汽车","摩托车","飞机", 27 | "公共汽车","火车","卡车","船","红绿灯", 28 | "消防栓","停车标志","停车表","长凳","鸟", 29 | "猫","狗","马","羊","牛", 30 | "象","熊","斑马","长颈鹿","背包", 31 | "伞","手提包","领带","手提箱","飞盘", 32 | "滑雪板","滑雪板","运动球","风筝","棒球棒", 33 | "棒球手套","滑板","冲浪板","网球拍","瓶子", 34 | "酒杯","杯子","叉子","刀子","勺子", 35 | "碗","香蕉","苹果","三明治","橘子", 36 | "花椰菜","胡萝卜","热狗","披萨","甜甜圈", 37 | "蛋糕","椅子","沙发","盆栽","床", 38 | "餐桌","马桶","电视","笔记本","鼠标", 39 | "遥控器","键盘","手机","微波炉","烤箱", 40 | "烤面包机","水槽","冰箱","书","时钟", 41 | "花瓶","剪刀","泰迪熊","吹风机","牙刷" 42 | ] 43 | 44 | fileName="/media/chen/chen/Robot/slam_ws/data/InstanceMat.exr"; 45 | instVector=cv2.imread(fileName,-1) 46 | 47 | 48 | def chat(text): 49 | BOT_NAME='系统' 50 | BOT_SELF_NAME='本系统' 51 | x = urllib.quote(text) 52 | link = urllib2.urlopen( 53 | "http://nlp.xiaoi.com/robot/webrobot?&callback=__webrobot_processMsg&data=%7B%22sessionId%22%3A%22ff725c236e5245a3ac825b2dd88a7501%22%2C%22robotId%22%3A%22webbot%22%2C%22userId%22%3A%227cd29df3450745fbbdcf1a462e6c58e6%22%2C%22body%22%3A%7B%22content%22%3A%22" + x + "%22%7D%2C%22type%22%3A%22txt%22%7D") 54 | html_doc = link.read() 55 | reply_list = re.findall(r'\"content\":\"(.+?)\\r\\n\"', html_doc) 56 | reply=str(reply_list[-1]) 57 | reply=reply.replace("小i机器人",BOT_NAME) 58 | reply=reply.replace("小i",BOT_SELF_NAME) 59 | return reply 60 | 61 | def Handle(text): 62 | result='' 63 | key='' 64 | index=0 65 | for (i,k) in enumerate(keyWords): 66 | if(k in text): #存在关键词 67 | key=k 68 | index=i 69 | break 70 | if(key!=''): 71 | insts=[] 72 | for inst in instVector: 73 | if(int(inst[0])==index): 74 | insts.append(((inst[2]+inst[3])/2,(inst[4]+inst[5])/2,(inst[6]+inst[7])/2)) 75 | print(insts) 76 | if(len(insts)==0): 77 | result="实例地图中未找到"+key 78 | else: 79 | if("拿" in text): 80 | result="发现"+str(len(insts))+"个"+key+"实例,正在导航到:\n"+str(insts[0]) 81 | else: 82 | result="发现"+str(len(insts))+"个"+key+"实例:\n"+str(insts) 83 | 84 | if(("实例" in text or "东西" in text) and ("所有" in text or "全部" in text)): 85 | result+="当前所有的实例如下:\n" 86 | instCurrent={} 87 | for inst in instVector: 88 | clsIndex=int(inst[0]) 89 | k=keyWords[clsIndex] 90 | n=instCurrent.get(k,0) 91 | instCurrent[k]=n+1 92 | for k,v in instCurrent.items(): 93 | result+=str(k)+":"+str(v)+"\n" 94 | 95 | 96 | if(result==""): 97 | #result="无法理解" 98 | result=chat(text) 99 | if("资讯" in result): 100 | result="行吧" 101 | if("你可能关心" in result): 102 | result="哦" 103 | if(result==""): 104 | result="无法理解" 105 | 106 | return result 107 | 108 | 109 | 110 | def UpdateInstance(event): 111 | global instVector 112 | fileName="/media/chen/chen/Robot/slam_ws/data/InstanceMat.exr"; 113 | instVector=cv2.imread(fileName,-1); 114 | #print(instVector) 115 | 116 | 117 | def CallBack(req): 118 | s=req.request 119 | rospy.loginfo("请求:"+s) 120 | result=Handle(s) 121 | rospy.loginfo("结果:"+result) 122 | return OrderResponse(result) #返回应答数据包(这里传进去的参数按.srv文件的顺序填写) 123 | 124 | def OrderServices(): 125 | rospy.init_node('Order_Service_Node') 126 | s = rospy.Service('OrderService',Order,CallBack) 127 | 128 | rospy.Timer(rospy.Duration(10),UpdateInstance) 129 | 130 | rospy.loginfo("命令服务节点已启动") 131 | rospy.spin() 132 | rospy.loginfo("命令服务节点已关闭") 133 | 134 | if __name__ == "__main__": 135 | OrderServices() -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | interact_slam 4 | 0.1.0 5 | The interact_slam package 6 | 7 | 8 | 9 | 10 | chenjianqu 11 | 12 | 13 | 14 | 15 | 16 | Apache 2.0 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | chenjianqu 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | catkin 53 | cv_bridge 54 | image_transport 55 | message_filters 56 | roscpp 57 | rospy 58 | sensor_msgs 59 | std_msgs 60 | tf 61 | tf_conversions 62 | nav_msgs 63 | pcl_conversions 64 | message_generation 65 | 66 | 67 | 68 | cv_bridge 69 | image_transport 70 | message_filters 71 | roscpp 72 | rospy 73 | sensor_msgs 74 | std_msgs 75 | tf 76 | tf_conversions 77 | nav_msgs 78 | pcl_conversions 79 | 80 | cv_bridge 81 | image_transport 82 | message_filters 83 | roscpp 84 | rospy 85 | sensor_msgs 86 | std_msgs 87 | tf 88 | tf_conversions 89 | nav_msgs 90 | pcl_conversions 91 | message_runtime 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | -------------------------------------------------------------------------------- /src/mainwindow.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2022, Chen Jianqu, Shanghai University 3 | * 4 | * This file is part of interact_slam. 5 | * 6 | * Licensed under the MIT License; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #ifndef MAINWINDOW_H 11 | #define MAINWINDOW_H 12 | 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | 21 | 22 | #include 23 | #include 24 | #include 25 | #include 26 | #include 27 | 28 | #include 29 | #include 30 | #include 31 | 32 | #include "ros/ros.h" 33 | #include 34 | #include 35 | #include 36 | 37 | 38 | #include "roshandle.h" 39 | 40 | 41 | typedef pcl::PointXYZRGB PointT; 42 | typedef pcl::PointXYZ PointXYZ; 43 | typedef pcl::PointCloud PointCloud; 44 | typedef pcl::PointCloud PointCloudXYZ; 45 | typedef boost::shared_ptr ViewerPtr; 46 | 47 | namespace Ui { 48 | class MainWindow; 49 | } 50 | 51 | 52 | class RosHandle;//头文件相互包含要进行类别的前置声明 53 | 54 | 55 | class MainWindow : public QMainWindow 56 | { 57 | Q_OBJECT 58 | 59 | public: 60 | RosHandle *rh; 61 | 62 | ViewerPtr densePointCloudViewer; 63 | ViewerPtr sparsePointCloudViewer; 64 | PointCloud::Ptr densePointCloud; 65 | PointCloudXYZ::Ptr sparsePointCloud; 66 | PointCloudXYZ::Ptr trackPointCloud; 67 | 68 | QString interactString; 69 | 70 | QString rawImageTopicString; 71 | QString instanceImageTopicString; 72 | QString densePointCloudTopicString; 73 | QString sparsePointCloudTopicString; 74 | QString navigationTopicString; 75 | 76 | QTimer *timer; 77 | QTimer *timerSlow; 78 | 79 | 80 | MainWindow(QWidget *parent = nullptr); 81 | ~MainWindow(); 82 | void InitWindow(); 83 | void Init(); 84 | void InitPCLViewer(); 85 | 86 | void SetRawImage(cv::Mat img); 87 | void SetInstanceImage(cv::Mat img); 88 | void SetDenseMap(PointCloud::ConstPtr pc); 89 | void SetSparseMap(PointCloudXYZ::ConstPtr pc); 90 | void SetNavigationMap(const nav_msgs::OccupancyGrid& msg); 91 | void InsertPose(tf::Quaternion q,tf::Vector3 t); 92 | void UpdateInstance(); 93 | QImage GetRandomImage(); 94 | 95 | inline void SetOutputString(QString s); 96 | inline QImage Mat2QImage(cv::Mat img); 97 | 98 | 99 | private slots: 100 | void on_rawImageEnableCheckbox_stateChanged(int arg1); 101 | 102 | void on_instanceSegmentationImageEnableCheckbox_stateChanged(int arg1); 103 | 104 | void on_densePointCloudMapEnableCheckbox_stateChanged(int arg1); 105 | 106 | void on_sparsePointCloudMapEnableCheckbox_stateChanged(int arg1); 107 | 108 | void on_navigationMapEnableCheckbox_stateChanged(int arg1); 109 | 110 | void on_pointSizeSlider_valueChanged(int value); 111 | 112 | void on_pointSizeSlider_sliderReleased(); 113 | 114 | void on_densePointCloudMapInstanceCheckbox_stateChanged(int arg1); 115 | 116 | void on_sparsePointCloudMapInstanceCheckbox_stateChanged(int arg1); 117 | 118 | 119 | void on_rawImageTopicRefreshButton_clicked(); 120 | 121 | void on_rawImageSubComboBox_currentIndexChanged(const QString &arg1); 122 | 123 | void on_instanceSegmentationImageTopicRefreshButton_clicked(); 124 | 125 | void on_instanceSegmentationImageSubComboBox_currentIndexChanged(const QString &arg1); 126 | 127 | void on_densePointCloudMapTopicRefreshButton_clicked(); 128 | 129 | void on_densePointCloudMapSubComboBox_currentIndexChanged(const QString &arg1); 130 | 131 | void on_sparsePointCloudMapTopicRefreshButton_clicked(); 132 | 133 | void on_sparsePointCloudMapSubComboBox_currentIndexChanged(const QString &arg1); 134 | 135 | void on_navigationMapTopicRefreshButton_clicked(); 136 | 137 | void on_navigationMapSubComboBox_currentIndexChanged(const QString &arg1); 138 | 139 | void on_interactSendButton_clicked(); 140 | 141 | void on_interactOutpuClearButton_clicked(); 142 | 143 | void on_rawImageSubComboBox_currentTextChanged(const QString &arg1); 144 | 145 | void on_pushButton_clicked(); 146 | 147 | void on_densePointCloudMapTrackCheckbox_stateChanged(int arg1); 148 | 149 | void on_sparsePointCloudMapTrackCheckbox_stateChanged(int arg1); 150 | 151 | void on_densePointCloudMapShowLabelCheckbox_stateChanged(int arg1); 152 | 153 | void on_sparsePointCloudMapShowLabelCheckbox_stateChanged(int arg1); 154 | 155 | void on_interactVoiceButton_clicked(); 156 | 157 | void on_voiceInputCheckbox_stateChanged(int arg1); 158 | 159 | void on_voiceOutputCheckbox_stateChanged(int arg1); 160 | 161 | private: 162 | void ShowInstance(ViewerPtr viewer); 163 | void ShowInstanceLabel(ViewerPtr viewer); 164 | void HideInstance(ViewerPtr viewer); 165 | void HideInstanceLabel(ViewerPtr viewer); 166 | 167 | Ui::MainWindow *ui; 168 | 169 | int pointSize; 170 | int showInstanceNum; 171 | int showInstanceLabelNum; 172 | 173 | std::string COCO_CLASSES[80]; 174 | 175 | std::vector> instVector; 176 | }; 177 | 178 | #endif // MAINWINDOW_H 179 | -------------------------------------------------------------------------------- /src/roshandle.cpp: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2022, Chen Jianqu, Shanghai University 3 | * 4 | * This file is part of interact_slam. 5 | * 6 | * Licensed under the MIT License; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | 11 | #include "roshandle.h" 12 | #include "ros/ros.h" 13 | #include "interact_slam/Order.h" 14 | 15 | 16 | RosHandle::RosHandle(ros::NodeHandle *nh_) 17 | { 18 | rawImageCounter=0; 19 | nh=nh_; 20 | it=new image_transport::ImageTransport(*nh); 21 | 22 | listener=new tf::TransformListener();//tf监听器 23 | 24 | orderService=nh->serviceClient("OrderService"); 25 | } 26 | 27 | 28 | QString RosHandle::SendOrder(QString msg) 29 | { 30 | interact_slam::Order srv; 31 | srv.request.request=msg.toStdString(); 32 | if(orderService.call(srv)) 33 | { 34 | return QString(srv.response.response.c_str()); 35 | } 36 | else{ 37 | return QString("命令服务调用失败"); 38 | } 39 | } 40 | 41 | void RosHandle::PoseLookup() 42 | { 43 | tf::StampedTransform m; 44 | try{ 45 | listener->lookupTransform("world", "orb_slam2", ros::Time(0), m);//查找坐标转换 46 | tf::Quaternion q=m.getRotation(); 47 | tf::Vector3 t=m.getOrigin(); 48 | //cout<InsertPose(q,t); 50 | } 51 | catch (tf::TransformException &ex){ 52 | ROS_ERROR("%s",ex.what()); 53 | ros::Duration(0.1).sleep(); 54 | } 55 | } 56 | 57 | 58 | 59 | 60 | void RosHandle::RawImageSubscribe(QString topic) 61 | { 62 | rawImageSub.shutdown(); 63 | if (!topic.isEmpty()) 64 | { 65 | rawImageSub=it->subscribe(topic.toStdString(),1,&RosHandle::RawImageCallBack,this); 66 | } 67 | } 68 | 69 | void RosHandle::RawImageCallBack(const sensor_msgs::ImageConstPtr& msg) 70 | { 71 | cv_bridge::CvImageConstPtr cv_ptrRGB; 72 | try{ 73 | cv_ptrRGB = cv_bridge::toCvShare(msg); 74 | } 75 | catch (cv_bridge::Exception& e){ 76 | ROS_ERROR("cv_bridge exception: %s", e.what()); 77 | return; 78 | } 79 | win->SetRawImage(cv_ptrRGB->image); 80 | } 81 | 82 | void RosHandle::InstanceImageSubscribe(QString topic) 83 | { 84 | instanceImageSub.shutdown(); 85 | if (!topic.isEmpty()) 86 | { 87 | instanceImageSub=it->subscribe(topic.toStdString(),1,&RosHandle::InstanceImageCallBack,this); 88 | } 89 | } 90 | 91 | void RosHandle::InstanceImageCallBack(const sensor_msgs::ImageConstPtr& msg) 92 | { 93 | cv_bridge::CvImageConstPtr cv_ptrRGB; 94 | try{ 95 | cv_ptrRGB = cv_bridge::toCvShare(msg); 96 | } 97 | catch (cv_bridge::Exception& e){ 98 | ROS_ERROR("cv_bridge exception: %s", e.what()); 99 | return; 100 | } 101 | win->SetInstanceImage(cv_ptrRGB->image); 102 | } 103 | 104 | void RosHandle::DenseMapSubscribe(QString topic) 105 | { 106 | denseMapSub.shutdown(); 107 | if (!topic.isEmpty()) 108 | { 109 | denseMapSub=nh->subscribe(topic.toStdString(),1,&RosHandle::DenseMapCallBack,this); 110 | } 111 | } 112 | 113 | 114 | void RosHandle::DenseMapCallBack(const PointCloud::ConstPtr& msg) 115 | { 116 | win->SetDenseMap(msg); 117 | } 118 | 119 | 120 | void RosHandle::SparseMapSubscribe(QString topic) 121 | { 122 | sparseMapSub.shutdown(); 123 | if (!topic.isEmpty()) 124 | { 125 | sparseMapSub=nh->subscribe(topic.toStdString(),1,&RosHandle::SparseMapCallBack,this); 126 | } 127 | } 128 | 129 | 130 | void RosHandle::SparseMapCallBack(const PointCloudXYZ::ConstPtr& msg) 131 | { 132 | win->SetSparseMap(msg); 133 | //cout<size()<subscribe(topic.toStdString(),1,&RosHandle::NavigationCallBack,this); 143 | } 144 | } 145 | 146 | 147 | void RosHandle::NavigationCallBack(const nav_msgs::OccupancyGrid& msg) 148 | { 149 | win->SetNavigationMap(msg); 150 | } 151 | 152 | 153 | 154 | 155 | QList RosHandle::UpdateTopicList(QSet message_types) 156 | { 157 | // get declared transports 158 | QList transports; 159 | image_transport::ImageTransport it(*nh); 160 | std::vector declared = it.getDeclaredTransports(); 161 | for (std::vector::const_iterator it = declared.begin(); it != declared.end(); it++) 162 | { 163 | QString transport = it->c_str(); 164 | QString prefix = "image_transport/"; 165 | if (transport.startsWith(prefix)) 166 | transport = transport.mid(prefix.length());// strip prefix from transport name 167 | transports.append(transport); 168 | std::cout< topics = GetTopics(message_types, transports).values(); 173 | topics.append(""); 174 | qSort(topics); 175 | return topics; 176 | } 177 | 178 | 179 | 180 | QSet RosHandle::GetTopics(const QSet& message_types, const QList& transports) 181 | { 182 | ros::master::V_TopicInfo topic_info; 183 | ros::master::getTopics(topic_info); 184 | 185 | QSet all_topics; 186 | for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++) 187 | all_topics.insert(it->name.c_str()); 188 | 189 | QSet topics; 190 | for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++) 191 | { 192 | if (message_types.contains(it->datatype.c_str())) 193 | { 194 | QString topic = it->name.c_str(); 195 | topics.insert(topic);// add raw topic 196 | 197 | // add transport specific sub-topics 198 | for (QList::const_iterator jt = transports.begin(); jt != transports.end(); jt++) 199 | { 200 | if (all_topics.contains(topic + "/" + *jt)) 201 | { 202 | QString sub = topic + " " + *jt; 203 | topics.insert(sub); 204 | } 205 | } 206 | } 207 | 208 | } 209 | return topics; 210 | } 211 | 212 | 213 | 214 | 215 | QList RosHandle::GetSpecificTopics(const QSet& message_types) 216 | { 217 | ros::master::V_TopicInfo topic_info; 218 | ros::master::getTopics(topic_info); 219 | 220 | QSet all_topics; 221 | for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++) 222 | all_topics.insert(it->name.c_str()); 223 | 224 | QSet tp; 225 | for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++) 226 | { 227 | if (message_types.contains(it->datatype.c_str())) 228 | { 229 | QString topic = it->name.c_str(); 230 | tp.insert(topic);// add raw topic 231 | } 232 | } 233 | 234 | QList topics = tp.values(); 235 | topics.append(""); 236 | qSort(topics); 237 | 238 | return topics; 239 | } 240 | 241 | 242 | 243 | 244 | QString RosHandle::GetAllTopics() 245 | { 246 | ros::master::V_TopicInfo topic_info; 247 | ros::master::getTopics(topic_info); 248 | 249 | QString s=""; 250 | 251 | QSet all_topics; 252 | for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++) 253 | { 254 | s+="主题:"+QString(it->name.c_str())+"\n"; 255 | s+="数据类型:"+QString(it->datatype.c_str())+"\n"; 256 | s+="\n"; 257 | } 258 | 259 | return s; 260 | } 261 | -------------------------------------------------------------------------------- /src/mainwindow.cpp: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2022, Chen Jianqu, Shanghai University 3 | * 4 | * This file is part of interact_slam. 5 | * 6 | * Licensed under the MIT License; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #include "mainwindow.h" 11 | #include "ui_mainwindow.h" 12 | 13 | #include "roshandle.h" 14 | #include 15 | #include 16 | #include 17 | 18 | 19 | 20 | 21 | MainWindow::MainWindow(QWidget *parent) : 22 | QMainWindow(parent), 23 | ui(new Ui::MainWindow) 24 | { 25 | ui->setupUi(this); 26 | interactString="交互程序正在启动\n"; 27 | timer=new QTimer(); 28 | timerSlow=new QTimer(); 29 | trackPointCloud.reset (new PointCloudXYZ); 30 | 31 | showInstanceNum=0; 32 | showInstanceLabelNum=0; 33 | 34 | std::string coco_label_[]={"person", "bicycle", "car", "motorcycle", "airplane", "bus", 35 | "train", "truck", "boat", "traffic light", "fire hydrant", 36 | "stop sign", "parking meter", "bench", "bird", "cat", "dog", 37 | "horse", "sheep", "cow", "elephant", "bear", "zebra", "giraffe", 38 | "backpack", "umbrella", "handbag", "tie", "suitcase", "frisbee", 39 | "skis", "snowboard", "sports ball", "kite", "baseball bat", 40 | "baseball glove", "skateboard", "surfboard", "tennis racket", 41 | "bottle", "wine glass", "cup", "fork", "knife", "spoon", "bowl", 42 | "banana", "apple", "sandwich", "orange", "broccoli", "carrot", 43 | "hot dog", "pizza", "donut", "cake", "chair", "couch", 44 | "potted plant", "bed", "dining table", "toilet", "tv", "laptop", 45 | "mouse", "remote", "keyboard", "cell phone", "microwave", "oven", 46 | "toaster", "sink", "refrigerator", "book", "clock", "vase", 47 | "scissors", "teddy bear", "hair drier", "toothbrush"}; 48 | //复制到COCO_label数组 49 | std::copy(std::begin(coco_label_),std::end(coco_label_),std::begin(COCO_CLASSES)); 50 | 51 | rawImageTopicString="/camera/rgb"; 52 | instanceImageTopicString="/ps/rgb"; 53 | densePointCloudTopicString="/point_cloud/raw"; 54 | sparsePointCloudTopicString="/point_cloud/sparse"; 55 | navigationTopicString="/map"; 56 | } 57 | 58 | MainWindow::~MainWindow() 59 | { 60 | delete ui; 61 | } 62 | 63 | 64 | void MainWindow::Init() 65 | { 66 | pointSize=1; 67 | InitPCLViewer(); 68 | InitWindow(); 69 | 70 | //init comboBox 71 | on_rawImageTopicRefreshButton_clicked(); 72 | on_instanceSegmentationImageTopicRefreshButton_clicked(); 73 | on_densePointCloudMapTopicRefreshButton_clicked(); 74 | on_sparsePointCloudMapTopicRefreshButton_clicked(); 75 | on_navigationMapTopicRefreshButton_clicked(); 76 | } 77 | 78 | 79 | 80 | void MainWindow::InitWindow() 81 | { 82 | cv::Mat imgRand = cv::Mat::zeros(cv::Size(640, 480), CV_8UC3); 83 | cv::randu(imgRand, cv::Scalar::all(0), cv::Scalar::all(255)); 84 | ui->rawImage->setPixmap(QPixmap::fromImage(Mat2QImage(imgRand))); 85 | ui->instanceSegmentationImage->setPixmap(QPixmap::fromImage(Mat2QImage(imgRand))); 86 | ui->navigationMap->setPixmap(QPixmap::fromImage(Mat2QImage(imgRand))); 87 | 88 | //on_rawImageTopicRefreshButton_clicked(); 89 | 90 | ui->interactOutputLabel->setText(interactString); 91 | ui->interactOutputLabel->setTextInteractionFlags(Qt::TextSelectableByMouse); 92 | ui->interactOutputLabel->setTextInteractionFlags(Qt::TextSelectableByKeyboard); 93 | 94 | ui->rawImageEnableCheckbox->setChecked(true); 95 | // ui->instanceSegmentationImageEnableCheckbox->setChecked(false); 96 | //ui->densePointCloudMapEnableCheckbox->setChecked(false); 97 | //ui->sparsePointCloudMapEnableCheckbox->setChecked(false); 98 | //ui->navigationMapEnableCheckbox->setChecked(false); 99 | ui->instanceSegmentationImageSubComboBox->setEnabled(false); 100 | ui->instanceSegmentationImageTopicRefreshButton->setEnabled(false); 101 | ui->densePointCloudMapSubComboBox->setEnabled(false); 102 | ui->densePointCloudMapTopicRefreshButton->setEnabled(false); 103 | ui->sparsePointCloudMapSubComboBox->setEnabled(false); 104 | ui->sparsePointCloudMapTopicRefreshButton->setEnabled(false); 105 | ui->navigationMapSubComboBox->setEnabled(false); 106 | ui->navigationMapTopicRefreshButton->setEnabled(false); 107 | } 108 | 109 | 110 | QImage MainWindow::Mat2QImage(cv::Mat img) 111 | { 112 | if(img.type()==16){ 113 | cv::cvtColor(img, img, cv::COLOR_BGR2RGB); 114 | return QImage((const unsigned char*)(img.data), int(img.cols), int(img.rows), img.step, QImage::Format_RGB888); 115 | } 116 | else if(img.type()==0){ 117 | return QImage((const unsigned char*)(img.data), int(img.cols), int(img.rows), img.step, QImage::Format_Mono); 118 | } 119 | else if(img.type()==5){ 120 | return QImage((const unsigned char*)(img.data), int(img.cols), int(img.rows), img.step, QImage::Format_Mono); 121 | } 122 | } 123 | 124 | 125 | 126 | 127 | QImage MainWindow::GetRandomImage() 128 | { 129 | cv::Mat imgRand = cv::Mat::zeros(cv::Size(640, 480), CV_8UC3); 130 | cv::randu(imgRand, cv::Scalar::all(0), cv::Scalar::all(255)); 131 | return Mat2QImage(imgRand); 132 | } 133 | 134 | 135 | void MainWindow::InitPCLViewer() 136 | { 137 | densePointCloudViewer.reset (new pcl::visualization::PCLVisualizer ("DensePointMap", false)); 138 | densePointCloudViewer->setBackgroundColor (0, 0, 0); 139 | densePointCloudViewer->addCoordinateSystem (0.5);//设置坐标轴大小 140 | densePointCloudViewer->initCameraParameters (); 141 | ui->densePointCloudMap->SetRenderWindow (densePointCloudViewer->getRenderWindow()); 142 | densePointCloudViewer->setupInteractor (ui->densePointCloudMap->GetInteractor (), ui->densePointCloudMap->GetRenderWindow ()); 143 | ui->densePointCloudMap->update (); 144 | 145 | sparsePointCloudViewer.reset (new pcl::visualization::PCLVisualizer ("FeaturePointMap", false)); 146 | sparsePointCloudViewer->setBackgroundColor (0, 0, 0); 147 | sparsePointCloudViewer->addCoordinateSystem (0.5);//设置坐标轴大小 148 | sparsePointCloudViewer->initCameraParameters (); 149 | ui->sparsePointCloudMap->SetRenderWindow (sparsePointCloudViewer->getRenderWindow()); 150 | sparsePointCloudViewer->setupInteractor (ui->sparsePointCloudMap->GetInteractor (), ui->sparsePointCloudMap->GetRenderWindow ()); 151 | ui->sparsePointCloudMap->update (); 152 | 153 | densePointCloud.reset (new PointCloud); 154 | densePointCloud->points.resize (1000); 155 | for (size_t i = 0; i < densePointCloud->points.size (); ++i) 156 | { 157 | densePointCloud->points[i].x = 2 * rand () / (RAND_MAX + 1.0f); 158 | densePointCloud->points[i].y = 2 * rand () / (RAND_MAX + 1.0f); 159 | densePointCloud->points[i].z = 2 * rand () / (RAND_MAX + 1.0f); 160 | 161 | densePointCloud->points[i].r = 255; 162 | densePointCloud->points[i].g = 255; 163 | densePointCloud->points[i].b = 255; 164 | } 165 | 166 | sparsePointCloud.reset (new PointCloudXYZ); 167 | sparsePointCloud->points.resize (1000); 168 | for (size_t i = 0; i < sparsePointCloud->points.size (); ++i) 169 | { 170 | sparsePointCloud->points[i].x = 2 * rand () / (RAND_MAX + 1.0f); 171 | sparsePointCloud->points[i].y = 2 * rand () / (RAND_MAX + 1.0f); 172 | sparsePointCloud->points[i].z = 2 * rand () / (RAND_MAX + 1.0f); 173 | } 174 | 175 | densePointCloudViewer->addPointCloud (densePointCloud, "cloud"); 176 | ui->densePointCloudMap->update (); 177 | 178 | sparsePointCloudViewer->addPointCloud (sparsePointCloud, "cloud"); 179 | ui->sparsePointCloudMap->update (); 180 | } 181 | 182 | 183 | void MainWindow::UpdateInstance() 184 | { 185 | std::string fileName="/media/chen/chen/Robot/ws/data/InstanceMat.exr"; 186 | cv::Mat img=cv::imread(fileName,-1); 187 | if(img.empty()) 188 | return; 189 | 190 | instVector.clear(); 191 | for(int i=0;i v; 194 | for(int j=0;j(i,j))); 196 | instVector.push_back(v); 197 | } 198 | 199 | if(ui->densePointCloudMapInstanceCheckbox->checkState()==Qt::CheckState::Checked){ 200 | HideInstance(densePointCloudViewer); 201 | ShowInstance(densePointCloudViewer); 202 | } 203 | if(ui->sparsePointCloudMapInstanceCheckbox->checkState()==Qt::CheckState::Checked){ 204 | HideInstance(sparsePointCloudViewer); 205 | ShowInstance(sparsePointCloudViewer); 206 | } 207 | if(ui->densePointCloudMapShowLabelCheckbox->checkState()==Qt::CheckState::Checked){ 208 | HideInstanceLabel(densePointCloudViewer); 209 | ShowInstanceLabel(densePointCloudViewer); 210 | } 211 | if(ui->sparsePointCloudMapShowLabelCheckbox->checkState()==Qt::CheckState::Checked){ 212 | HideInstanceLabel(sparsePointCloudViewer); 213 | ShowInstanceLabel(sparsePointCloudViewer); 214 | } 215 | } 216 | 217 | 218 | void MainWindow::ShowInstance(ViewerPtr viewer) 219 | { 220 | if(instVector.size()>0) 221 | { 222 | for(int i=0;i v=instVector[i]; 225 | std::string name="instance"+std::to_string(i); 226 | double color_r=rand() / double(RAND_MAX); 227 | double color_g=rand() / double(RAND_MAX); 228 | double color_b=rand() / double(RAND_MAX); 229 | //绘制立方体 230 | viewer->addCube(v[2],v[3],v[4],v[5],v[6],v[7],color_r,color_g,color_b,name); 231 | } 232 | showInstanceNum=instVector.size(); 233 | } 234 | } 235 | 236 | 237 | void MainWindow::HideInstance(ViewerPtr viewer) 238 | { 239 | if(showInstanceNum>0) 240 | { 241 | for(int i=0;iremoveShape("instance"+std::to_string(i)); 243 | } 244 | } 245 | 246 | 247 | void MainWindow::ShowInstanceLabel(ViewerPtr viewer) 248 | { 249 | if(instVector.size()>0) 250 | { 251 | for(int i=0;i v=instVector[i]; 254 | std::string insName=COCO_CLASSES[int(v[0])]+std::to_string(int(v[1])); 255 | double color_r=rand() / double(RAND_MAX); 256 | double color_g=rand() / double(RAND_MAX); 257 | double color_b=rand() / double(RAND_MAX); 258 | PointXYZ p; 259 | p.x=v[2]; 260 | p.y=v[4]; 261 | p.z=v[6]; 262 | //绘制标签,尺度为1.0,颜色为红色 263 | //viewer->addText3D("*"+insName,p,0.03,color_r,color_g,color_b,"label"+std::to_string(i)); 264 | // viewer->addText3D("*"+insName,p,0.03,color_r,color_g,color_b); 265 | } 266 | showInstanceLabelNum=instVector.size(); 267 | } 268 | } 269 | 270 | void MainWindow::HideInstanceLabel(ViewerPtr viewer) 271 | { 272 | if(showInstanceLabelNum>0) 273 | { 274 | //for(int i=0;iremoveText3D(""); 276 | } 277 | } 278 | 279 | 280 | void MainWindow::SetRawImage(cv::Mat img) 281 | { 282 | QImage imgQ=Mat2QImage(img); 283 | ui->rawImage->setPixmap(QPixmap::fromImage(imgQ)); 284 | } 285 | 286 | void MainWindow::SetInstanceImage(cv::Mat img) 287 | { 288 | QImage imgQ=Mat2QImage(img); 289 | ui->instanceSegmentationImage->setPixmap(QPixmap::fromImage(imgQ)); 290 | } 291 | 292 | 293 | void MainWindow::SetDenseMap(PointCloud::ConstPtr pc) 294 | { 295 | densePointCloudViewer->updatePointCloud(pc,"cloud"); 296 | ui->densePointCloudMap->update (); 297 | } 298 | 299 | void MainWindow::SetSparseMap(PointCloudXYZ::ConstPtr pc) 300 | { 301 | sparsePointCloudViewer->updatePointCloud(pc,"cloud"); 302 | ui->sparsePointCloudMap->update (); 303 | } 304 | 305 | void MainWindow::SetNavigationMap(const nav_msgs::OccupancyGrid& msg) 306 | { 307 | int width=int(msg.info.width); 308 | int height=int(msg.info.height); 309 | 310 | QPoint leftButtonPosition=QPoint(msg.info.origin.position.x,msg.info.origin.position.y); 311 | float step=msg.info.resolution; 312 | 313 | QPoint originPosition; 314 | originPosition.setX(int(-leftButtonPosition.x()*10)); 315 | originPosition.setY(int(-leftButtonPosition.y()*10)); 316 | 317 | 318 | std::vector vec=msg.data; 319 | int cursor=width*height; 320 | 321 | cv::Mat img = cv::Mat::zeros(cv::Size(width, height), CV_8UC1); 322 | for (int i = 0; i=0; j--) 325 | imageRow[j]=(unsigned char)(255-vec[--cursor]*255/100); 326 | } 327 | cv::Mat imgColor = cv::Mat::zeros(cv::Size(width, height), CV_8UC3); 328 | cv::cvtColor(img, imgColor, cv::COLOR_GRAY2RGB); 329 | 330 | cv::Mat imgResize; 331 | //图片自适应窗口 332 | double wPh=586.0/440.0; 333 | if(width/height>wPh){ 334 | double scale=586.0/width; 335 | cv::resize(imgColor, imgResize, cv::Size(),scale,scale); 336 | } 337 | else{ 338 | double scale=440.0/height; 339 | cv::resize(imgColor, imgResize, cv::Size(),scale,scale); 340 | } 341 | 342 | 343 | 344 | 345 | QImage qimg=Mat2QImage(imgResize); 346 | 347 | QPainter painter(&qimg); 348 | QPen pen(QColor(0,255,0)); 349 | painter.setPen(pen); 350 | 351 | if(0<=originPosition.x() && originPosition.x()navigationMap->setPixmap(QPixmap::fromImage(qimg)); 357 | } 358 | 359 | 360 | 361 | inline void MainWindow::SetOutputString(QString s) 362 | { 363 | interactString+=s+"\n"; 364 | QList sl=interactString.split(QRegExp("[\r\n]"),QString::SkipEmptyParts); 365 | 366 | if(sl.length()>30){ 367 | interactString=""; 368 | int i=sl.length()-30; 369 | for (QList::const_iterator jt = sl.begin(); jt != sl.end(); jt++) 370 | { 371 | i--; 372 | if(i>0) 373 | continue; 374 | interactString+=*jt+"\n"; 375 | } 376 | } 377 | ui->interactOutputLabel->setText(interactString); 378 | } 379 | 380 | 381 | 382 | 383 | void MainWindow::InsertPose(tf::Quaternion q,tf::Vector3 t) 384 | { 385 | PointXYZ p; 386 | p.x=float(t.getX()); 387 | p.y=float(t.getY()); 388 | p.z=float(t.getZ()); 389 | 390 | if(trackPointCloud->size()==0){ 391 | trackPointCloud->points.push_back(p); 392 | return; 393 | } 394 | 395 | PointXYZ lastPose=trackPointCloud->points[trackPointCloud->size()-1]; 396 | double distance=sqrt(pow(lastPose.x-p.x,2)+pow(lastPose.y-p.y,2)+pow(lastPose.z-p.z,2)); 397 | if(distance<0.01) 398 | return; 399 | trackPointCloud->points.push_back(p); 400 | 401 | if(ui->densePointCloudMapTrackCheckbox->checkState() == Qt::CheckState::Checked) 402 | { 403 | densePointCloudViewer->addLine(lastPose,p,"track"+std::to_string(trackPointCloud->size())); 404 | ui->densePointCloudMap->update(); 405 | } 406 | 407 | if(ui->sparsePointCloudMapTrackCheckbox->checkState() == Qt::CheckState::Checked) 408 | { 409 | sparsePointCloudViewer->addLine(lastPose,p,"track"+std::to_string(trackPointCloud->size())); 410 | ui->sparsePointCloudMap->update(); 411 | } 412 | } 413 | 414 | 415 | 416 | 417 | 418 | 419 | 420 | void MainWindow::on_rawImageEnableCheckbox_stateChanged(int arg1) 421 | { 422 | if(arg1==2) //Enable 423 | { 424 | ui->rawImageSubComboBox->setEnabled(true); 425 | ui->rawImageTopicRefreshButton->setEnabled(true); 426 | rh->RawImageSubscribe(rawImageTopicString); 427 | on_rawImageTopicRefreshButton_clicked(); 428 | 429 | SetOutputString("打开数据源监视器"); 430 | } 431 | else if(arg1==0) //Disable 432 | { 433 | ui->rawImageSubComboBox->setEnabled(false); 434 | ui->rawImageTopicRefreshButton->setEnabled(false); 435 | rh->rawImageSub.shutdown(); 436 | cv::Mat imgRand = cv::Mat::zeros(cv::Size(640, 480), CV_8UC3); 437 | cv::randu(imgRand, cv::Scalar::all(0), cv::Scalar::all(255)); 438 | ui->rawImage->setPixmap(QPixmap::fromImage(Mat2QImage(imgRand))); 439 | SetOutputString("关闭数据源监视器"); 440 | } 441 | } 442 | 443 | void MainWindow::on_instanceSegmentationImageEnableCheckbox_stateChanged(int arg1) 444 | { 445 | if(arg1==2) //Enable 446 | { 447 | ui->instanceSegmentationImageSubComboBox->setEnabled(true); 448 | ui->instanceSegmentationImageTopicRefreshButton->setEnabled(true); 449 | rh->InstanceImageSubscribe(instanceImageTopicString); 450 | on_instanceSegmentationImageTopicRefreshButton_clicked(); 451 | 452 | SetOutputString("打开实例分割监视器"); 453 | } 454 | else if(arg1==0) //Disable 455 | { 456 | ui->instanceSegmentationImageSubComboBox->setEnabled(false); 457 | ui->instanceSegmentationImageTopicRefreshButton->setEnabled(false); 458 | rh->instanceImageSub.shutdown(); 459 | cv::Mat imgRand = cv::Mat::zeros(cv::Size(640, 480), CV_8UC3); 460 | cv::randu(imgRand, cv::Scalar::all(0), cv::Scalar::all(255)); 461 | ui->instanceSegmentationImage->setPixmap(QPixmap::fromImage(Mat2QImage(imgRand))); 462 | SetOutputString("关闭实例分割监视器"); 463 | } 464 | } 465 | 466 | void MainWindow::on_densePointCloudMapEnableCheckbox_stateChanged(int arg1) 467 | { 468 | if(arg1==2) //Enable 469 | { 470 | ui->densePointCloudMapSubComboBox->setEnabled(true); 471 | ui->densePointCloudMapTopicRefreshButton->setEnabled(true); 472 | rh->DenseMapSubscribe(densePointCloudTopicString); 473 | on_densePointCloudMapTopicRefreshButton_clicked(); 474 | 475 | SetOutputString("打开稠密点云监视器"); 476 | } 477 | else if(arg1==0) //Disable 478 | { 479 | ui->densePointCloudMapSubComboBox->setEnabled(false); 480 | ui->densePointCloudMapTopicRefreshButton->setEnabled(false); 481 | rh->denseMapSub.shutdown(); 482 | SetOutputString("关闭稠密点云监视器"); 483 | } 484 | } 485 | 486 | void MainWindow::on_sparsePointCloudMapEnableCheckbox_stateChanged(int arg1) 487 | { 488 | if(arg1==2) //Enable 489 | { 490 | ui->sparsePointCloudMapSubComboBox->setEnabled(true); 491 | ui->sparsePointCloudMapTopicRefreshButton->setEnabled(true); 492 | rh->SparseMapSubscribe(sparsePointCloudTopicString); 493 | on_sparsePointCloudMapTopicRefreshButton_clicked(); 494 | 495 | SetOutputString("打开稀疏点云监视器"); 496 | } 497 | else if(arg1==0) //Disable 498 | { 499 | ui->sparsePointCloudMapSubComboBox->setEnabled(false); 500 | ui->sparsePointCloudMapTopicRefreshButton->setEnabled(false); 501 | rh->sparseMapSub.shutdown(); 502 | SetOutputString("关闭稀疏点云监视器"); 503 | } 504 | } 505 | 506 | void MainWindow::on_navigationMapEnableCheckbox_stateChanged(int arg1) 507 | { 508 | if(arg1==2) //Enable 509 | { 510 | ui->navigationMapSubComboBox->setEnabled(true); 511 | ui->navigationMapTopicRefreshButton->setEnabled(true); 512 | rh->NavigationSubscribe(navigationTopicString); 513 | on_navigationMapTopicRefreshButton_clicked(); 514 | SetOutputString("打开导航监视器"); 515 | } 516 | else if(arg1==0) //Disable 517 | { 518 | ui->navigationMapSubComboBox->setEnabled(false); 519 | ui->navigationMapTopicRefreshButton->setEnabled(false); 520 | rh->navigationSub.shutdown(); 521 | cv::Mat imgRand = cv::Mat::zeros(cv::Size(640, 480), CV_8UC3); 522 | cv::randu(imgRand, cv::Scalar::all(0), cv::Scalar::all(255)); 523 | ui->navigationMap->setPixmap(QPixmap::fromImage(Mat2QImage(imgRand))); 524 | SetOutputString("关闭导航监视器"); 525 | } 526 | } 527 | 528 | void MainWindow::on_pointSizeSlider_valueChanged(int value) 529 | { 530 | pointSize=value; 531 | ui->pointSizeLabel->setNum(value); 532 | } 533 | 534 | void MainWindow::on_pointSizeSlider_sliderReleased() 535 | { 536 | densePointCloudViewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, pointSize, "cloud"); 537 | ui->densePointCloudMap->update(); 538 | sparsePointCloudViewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, pointSize, "cloud"); 539 | ui->sparsePointCloudMap->update(); 540 | } 541 | 542 | void MainWindow::on_densePointCloudMapInstanceCheckbox_stateChanged(int arg1) 543 | { 544 | if(arg1==2) //Enable 545 | { 546 | ShowInstance(densePointCloudViewer); 547 | SetOutputString("稠密地图显示实例"); 548 | } 549 | else if(arg1==0) //Disable 550 | { 551 | HideInstance(densePointCloudViewer); 552 | SetOutputString("稠密地图隐藏实例"); 553 | } 554 | } 555 | 556 | void MainWindow::on_sparsePointCloudMapInstanceCheckbox_stateChanged(int arg1) 557 | { 558 | if(arg1==2) //Enable 559 | { 560 | ShowInstance(sparsePointCloudViewer); 561 | SetOutputString("稀疏地图显示实例"); 562 | } 563 | else if(arg1==0) //Disable 564 | { 565 | HideInstance(sparsePointCloudViewer); 566 | SetOutputString("稀疏地图隐藏实例"); 567 | } 568 | } 569 | 570 | 571 | 572 | void MainWindow::on_rawImageTopicRefreshButton_clicked() 573 | { 574 | ui->rawImageSubComboBox->clear(); 575 | 576 | QSet message_types; 577 | message_types.insert("sensor_msgs/Image"); 578 | message_types.insert("sensor_msgs/CompressedImage"); 579 | QList topicList=rh->GetSpecificTopics(message_types); 580 | 581 | if(topicList.length()<1){ 582 | SetOutputString("未监听到数据源"); 583 | return; 584 | } 585 | 586 | SetOutputString("监听到的数据源:"); 587 | for (QList::const_iterator it = topicList.begin(); it != topicList.end(); it++) 588 | { 589 | QString label(*it); 590 | label.replace(" ", "/"); 591 | ui->rawImageSubComboBox->addItem(label, QVariant(*it)); 592 | SetOutputString(label); 593 | } 594 | ui->rawImageSubComboBox->setCurrentIndex(0);//default 595 | rawImageTopicString=ui->rawImageSubComboBox->currentText(); 596 | } 597 | 598 | void MainWindow::on_rawImageSubComboBox_currentIndexChanged(const QString &arg1) 599 | { 600 | if(arg1.length()<2) 601 | return; 602 | rawImageTopicString = arg1; 603 | if(ui->rawImageEnableCheckbox->checkState() == Qt::CheckState::Checked){ 604 | SetOutputString("设置数据源的主题为:"+rawImageTopicString); 605 | rh->RawImageSubscribe(rawImageTopicString); 606 | } 607 | else{ 608 | SetOutputString("数据源监视器未打开"); 609 | } 610 | } 611 | 612 | 613 | void MainWindow::on_instanceSegmentationImageTopicRefreshButton_clicked() 614 | { 615 | ui->instanceSegmentationImageSubComboBox->clear(); 616 | 617 | QSet message_types; 618 | message_types.insert("sensor_msgs/Image"); 619 | message_types.insert("sensor_msgs/CompressedImage"); 620 | QList topicList=rh->GetSpecificTopics(message_types); 621 | 622 | if(topicList.length()<1){ 623 | SetOutputString("未监听到实例分割"); 624 | return; 625 | } 626 | 627 | SetOutputString("监听到的实例分割"); 628 | 629 | for (QList::const_iterator it = topicList.begin(); it != topicList.end(); it++) 630 | { 631 | QString label(*it); 632 | label.replace(" ", "/"); 633 | ui->instanceSegmentationImageSubComboBox->addItem(label, QVariant(*it)); 634 | SetOutputString(label); 635 | } 636 | ui->instanceSegmentationImageSubComboBox->setCurrentIndex(0);//default 637 | instanceImageTopicString=ui->instanceSegmentationImageSubComboBox->currentText(); 638 | } 639 | 640 | 641 | void MainWindow::on_instanceSegmentationImageSubComboBox_currentIndexChanged(const QString &arg1) 642 | { 643 | if(arg1.length()<2) 644 | return; 645 | instanceImageTopicString = arg1; 646 | if(ui->instanceSegmentationImageEnableCheckbox->checkState() == Qt::CheckState::Checked){ 647 | SetOutputString("设置实例分割的主题为:"+instanceImageTopicString); 648 | rh->InstanceImageSubscribe(instanceImageTopicString); 649 | } 650 | else{ 651 | SetOutputString("实例分割监视器未打开"); 652 | } 653 | } 654 | 655 | void MainWindow::on_densePointCloudMapTopicRefreshButton_clicked() 656 | { 657 | ui->densePointCloudMapSubComboBox->clear(); 658 | 659 | QSet message_types; 660 | message_types.insert("sensor_msgs/PointCloud2"); 661 | QList topicList=rh->GetSpecificTopics(message_types); 662 | 663 | if(topicList.length()<1){ 664 | SetOutputString("未监听到稠密点云"); 665 | return; 666 | } 667 | 668 | SetOutputString("监听到的稠密点云"); 669 | 670 | for (QList::const_iterator it = topicList.begin(); it != topicList.end(); it++) 671 | { 672 | QString label(*it); 673 | label.replace(" ", "/"); 674 | ui->densePointCloudMapSubComboBox->addItem(label, QVariant(*it)); 675 | SetOutputString(label); 676 | } 677 | ui->densePointCloudMapSubComboBox->setCurrentIndex(0);//default 678 | densePointCloudTopicString=ui->densePointCloudMapSubComboBox->currentText(); 679 | } 680 | 681 | void MainWindow::on_densePointCloudMapSubComboBox_currentIndexChanged(const QString &arg1) 682 | { 683 | if(arg1.length()<2) 684 | return; 685 | densePointCloudTopicString = arg1; 686 | if(ui->densePointCloudMapEnableCheckbox->checkState() == Qt::CheckState::Checked){ 687 | SetOutputString("设置稠密点云的主题为:"+densePointCloudTopicString); 688 | rh->DenseMapSubscribe(densePointCloudTopicString); 689 | } 690 | else{ 691 | SetOutputString("稠密点云监视器未打开"); 692 | } 693 | } 694 | 695 | void MainWindow::on_sparsePointCloudMapTopicRefreshButton_clicked() 696 | { 697 | ui->sparsePointCloudMapSubComboBox->clear(); 698 | 699 | QSet message_types; 700 | message_types.insert("sensor_msgs/PointCloud2"); 701 | QList topicList=rh->GetSpecificTopics(message_types); 702 | 703 | if(topicList.length()<1){ 704 | SetOutputString("未监听到稀疏点云"); 705 | return; 706 | } 707 | 708 | SetOutputString("监听到的稀疏点云"); 709 | for (QList::const_iterator it = topicList.begin(); it != topicList.end(); it++) 710 | { 711 | QString label(*it); 712 | label.replace(" ", "/"); 713 | ui->sparsePointCloudMapSubComboBox->addItem(label, QVariant(*it)); 714 | SetOutputString(label); 715 | } 716 | ui->sparsePointCloudMapSubComboBox->setCurrentIndex(0);//default 717 | sparsePointCloudTopicString=ui->sparsePointCloudMapSubComboBox->currentText(); 718 | } 719 | 720 | void MainWindow::on_sparsePointCloudMapSubComboBox_currentIndexChanged(const QString &arg1) 721 | { 722 | if(arg1.length()<2) 723 | return; 724 | sparsePointCloudTopicString = arg1; 725 | if(ui->sparsePointCloudMapEnableCheckbox->checkState() == Qt::CheckState::Checked){ 726 | SetOutputString("设置稀疏点云的主题为:"+sparsePointCloudTopicString); 727 | rh->SparseMapSubscribe(sparsePointCloudTopicString); 728 | } 729 | else{ 730 | SetOutputString("稀疏点云监视器未打开"); 731 | } 732 | } 733 | 734 | void MainWindow::on_navigationMapTopicRefreshButton_clicked() 735 | { 736 | ui->navigationMapSubComboBox->clear(); 737 | 738 | QSet message_types; 739 | message_types.insert("nav_msgs/OccupancyGrid"); 740 | QList topicList=rh->GetSpecificTopics(message_types); 741 | 742 | if(topicList.length()<1){ 743 | SetOutputString("未监听到导航地图"); 744 | return; 745 | } 746 | 747 | SetOutputString("监听到的导航地图"); 748 | for (QList::const_iterator it = topicList.begin(); it != topicList.end(); it++) 749 | { 750 | QString label(*it); 751 | label.replace(" ", "/"); 752 | ui->navigationMapSubComboBox->addItem(label, QVariant(*it)); 753 | SetOutputString(label); 754 | } 755 | ui->navigationMapSubComboBox->setCurrentIndex(0);//default 756 | navigationTopicString=ui->navigationMapSubComboBox->currentText(); 757 | } 758 | 759 | void MainWindow::on_navigationMapSubComboBox_currentIndexChanged(const QString &arg1) 760 | { 761 | if(arg1.length()<2) 762 | return; 763 | navigationTopicString = arg1; 764 | if(ui->navigationMapEnableCheckbox->checkState() == Qt::CheckState::Checked){ 765 | SetOutputString("设置导航地图的主题为:"+navigationTopicString); 766 | rh->NavigationSubscribe(navigationTopicString); 767 | } 768 | else{ 769 | SetOutputString("导航地图监视器未打开"); 770 | } 771 | } 772 | 773 | void MainWindow::on_interactSendButton_clicked() 774 | { 775 | QString s=ui->interactInputLineEdit->text(); 776 | 777 | if(s=="") 778 | return; 779 | 780 | ui->interactInputLineEdit->clear(); 781 | ui->interactInputLineEdit->setFocus(); 782 | SetOutputString("我:"+s); 783 | 784 | QString result=rh->SendOrder(s); 785 | SetOutputString("系统:"+result); 786 | } 787 | 788 | 789 | 790 | void MainWindow::on_interactOutpuClearButton_clicked() 791 | { 792 | interactString=""; 793 | ui->interactOutputLabel->clear(); 794 | } 795 | 796 | 797 | void MainWindow::on_pushButton_clicked() 798 | { 799 | QString s=rh->GetAllTopics(); 800 | SetOutputString(s); 801 | } 802 | 803 | void MainWindow::on_densePointCloudMapTrackCheckbox_stateChanged(int arg1) 804 | { 805 | if(arg1==2) //Enable 806 | { 807 | if(trackPointCloud->size()<2) 808 | return; 809 | PointXYZ lastPoint=trackPointCloud->points[0]; 810 | for(int i=1;isize();i++){ 811 | PointXYZ currentPoint=trackPointCloud->points[i]; 812 | densePointCloudViewer->addLine(lastPoint,currentPoint,"track"+std::to_string(i)); 813 | lastPoint=currentPoint; 814 | } 815 | ui->densePointCloudMap->update(); 816 | SetOutputString("稠密显示轨迹"); 817 | } 818 | else if(arg1==0) //Disable 819 | { 820 | densePointCloudViewer->removeAllShapes(); 821 | ui->densePointCloudMap->update(); 822 | SetOutputString("稠密隐藏轨迹"); 823 | } 824 | } 825 | 826 | void MainWindow::on_sparsePointCloudMapTrackCheckbox_stateChanged(int arg1) 827 | { 828 | if(arg1==2) //Enable 829 | { 830 | if(trackPointCloud->size()<2) 831 | return; 832 | PointXYZ lastPoint=trackPointCloud->points[0]; 833 | for(int i=1;isize();i++){ 834 | PointXYZ currentPoint=trackPointCloud->points[i]; 835 | sparsePointCloudViewer->addLine(lastPoint,currentPoint,"track"+std::to_string(i)); 836 | lastPoint=currentPoint; 837 | } 838 | ui->sparsePointCloudMap->update(); 839 | SetOutputString("稀疏显示轨迹"); 840 | } 841 | else if(arg1==0) //Disable 842 | { 843 | sparsePointCloudViewer->removeAllShapes(); 844 | ui->sparsePointCloudMap->update(); 845 | SetOutputString("稀疏隐藏轨迹"); 846 | } 847 | } 848 | 849 | void MainWindow::on_densePointCloudMapShowLabelCheckbox_stateChanged(int arg1) 850 | { 851 | if(arg1==2) //Enable 852 | { 853 | ShowInstanceLabel(densePointCloudViewer); 854 | SetOutputString("稠密地图显示标签"); 855 | } 856 | else if(arg1==0) //Disable 857 | { 858 | HideInstanceLabel(densePointCloudViewer); 859 | SetOutputString("稠密地图隐藏标签"); 860 | } 861 | } 862 | 863 | 864 | void MainWindow::on_sparsePointCloudMapShowLabelCheckbox_stateChanged(int arg1) 865 | { 866 | if(arg1==2) //Enable 867 | { 868 | ShowInstanceLabel(sparsePointCloudViewer); 869 | SetOutputString("稀疏地图显示标签"); 870 | } 871 | else if(arg1==0) //Disable 872 | { 873 | HideInstanceLabel(sparsePointCloudViewer); 874 | SetOutputString("稀疏地图隐藏标签"); 875 | } 876 | } 877 | 878 | void MainWindow::on_rawImageSubComboBox_currentTextChanged(const QString &arg1) 879 | { 880 | 881 | } 882 | 883 | void MainWindow::on_interactVoiceButton_clicked() 884 | { 885 | if(ui->voiceInputCheckbox->checkState()==Qt::CheckState::Checked) 886 | { 887 | SetOutputString("请开始说话"); 888 | } 889 | else 890 | { 891 | 892 | SetOutputString("语音输入未打开"); 893 | } 894 | } 895 | 896 | void MainWindow::on_voiceInputCheckbox_stateChanged(int arg1) 897 | { 898 | if(arg1==2) //Enable 899 | { 900 | 901 | SetOutputString("打开语音输入"); 902 | } 903 | else if(arg1==0) //Disable 904 | { 905 | 906 | SetOutputString("关闭语音输入"); 907 | } 908 | } 909 | 910 | void MainWindow::on_voiceOutputCheckbox_stateChanged(int arg1) 911 | { 912 | if(arg1==2) //Enable 913 | { 914 | SetOutputString("打开语音输出"); 915 | } 916 | else if(arg1==0) //Disable 917 | { 918 | SetOutputString("关闭语音输出"); 919 | } 920 | } 921 | -------------------------------------------------------------------------------- /src/mainwindow.ui: -------------------------------------------------------------------------------- 1 | 2 | 3 | MainWindow 4 | 5 | 6 | 7 | 0 8 | 0 9 | 1939 10 | 1067 11 | 12 | 13 | 14 | MainWindow 15 | 16 | 17 | 18 | 19 | 20 | 0 21 | 7 22 | 1931 23 | 1016 24 | 25 | 26 | 27 | 28 | 29 | 30 | QLayout::SetMinimumSize 31 | 32 | 33 | 10 34 | 35 | 36 | 37 | 38 | 39 | 400 40 | 25 41 | 42 | 43 | 44 | 交互终端 45 | 46 | 47 | Qt::AlignCenter 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 0 56 | 600 57 | 58 | 59 | 60 | 61 | 400 62 | 16777215 63 | 64 | 65 | 66 | 67 | 黑体 68 | 69 | 70 | 71 | IBeamCursor 72 | 73 | 74 | background-color: rgb(0, 0, 0); 75 | color: rgb(243, 243, 243); 76 | 77 | 78 | 终端 79 | 80 | 81 | Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft 82 | 83 | 84 | false 85 | 86 | 87 | 10 88 | 89 | 90 | 91 | 92 | 93 | 94 | 1 95 | 96 | 97 | QLayout::SetMinimumSize 98 | 99 | 100 | 0 101 | 102 | 103 | 0 104 | 105 | 106 | 107 | 108 | 109 | 300 110 | 50 111 | 112 | 113 | 114 | 请输入指令 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 50 123 | 50 124 | 125 | 126 | 127 | 发送 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 50 136 | 50 137 | 138 | 139 | 140 | 语音 141 | 142 | 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | 1000 151 | 50 152 | 153 | 154 | 155 | 数据源 156 | 157 | 158 | Qt::AlignCenter 159 | 160 | 161 | 162 | 163 | 164 | 165 | 166 | 400 167 | 300 168 | 169 | 170 | 171 | 172 | 400 173 | 300 174 | 175 | 176 | 177 | 178 | 179 | 180 | 181 | 182 | 183 | 184 | 185 | 186 | 187 | 188 | 稀疏点云地图 189 | 190 | 191 | Qt::AlignCenter 192 | 193 | 194 | 195 | 196 | 197 | 198 | 199 | 586 200 | 440 201 | 202 | 203 | 204 | 205 | 586 206 | 440 207 | 208 | 209 | 210 | 211 | 212 | 213 | 214 | 215 | 586 216 | 440 217 | 218 | 219 | 220 | 221 | 586 222 | 440 223 | 224 | 225 | 226 | 227 | 228 | 229 | 230 | 231 | 232 | 233 | 导航地图 234 | 235 | 236 | Qt::AlignCenter 237 | 238 | 239 | 240 | 241 | 242 | 243 | 244 | 586 245 | 440 246 | 247 | 248 | 249 | 250 | 586 251 | 440 252 | 253 | 254 | 255 | 256 | 黑体 257 | 258 | 259 | 260 | ArrowCursor 261 | 262 | 263 | false 264 | 265 | 266 | 267 | 268 | 269 | 270 | 271 | 272 | 273 | 274 | 586 275 | 440 276 | 277 | 278 | 279 | 280 | 586 281 | 440 282 | 283 | 284 | 285 | 286 | 287 | 288 | 289 | 实例分割 290 | 291 | 292 | Qt::AlignCenter 293 | 294 | 295 | 296 | 297 | 298 | 299 | 稠密点云地图 300 | 301 | 302 | Qt::AlignCenter 303 | 304 | 305 | 306 | 307 | 308 | 309 | 310 | 311 | 0 312 | 313 | 314 | 10 315 | 316 | 317 | 0 318 | 319 | 320 | 10 321 | 322 | 323 | 324 | 325 | 配置菜单 326 | 327 | 328 | Qt::AlignCenter 329 | 330 | 331 | 332 | 333 | 334 | 335 | false 336 | 337 | 338 | 339 | 340 | 0 341 | -22 342 | 307 343 | 1300 344 | 345 | 346 | 347 | 348 | 3 349 | 0 350 | 351 | 352 | 353 | 354 | 0 355 | 1080 356 | 357 | 358 | 359 | 360 | 361 | 10 362 | 0 363 | 302 364 | 1294 365 | 366 | 367 | 368 | 369 | QLayout::SetDefaultConstraint 370 | 371 | 372 | 373 | 374 | 375 | 0 376 | 0 377 | 378 | 379 | 380 | 381 | 0 382 | 180 383 | 384 | 385 | 386 | 387 | 16777215 388 | 160 389 | 390 | 391 | 392 | 监视器 393 | 394 | 395 | Qt::AlignCenter 396 | 397 | 398 | 399 | 400 | 10 401 | 20 402 | 141 403 | 151 404 | 405 | 406 | 407 | 408 | 1 409 | 410 | 411 | 412 | 413 | 数据源 414 | 415 | 416 | 417 | 418 | 419 | 420 | 实例分割 421 | 422 | 423 | 424 | 425 | 426 | 427 | 稠密点云地图 428 | 429 | 430 | 431 | 432 | 433 | 434 | 稀疏点云地图 435 | 436 | 437 | 438 | 439 | 440 | 441 | 导航地图 442 | 443 | 444 | 445 | 446 | 447 | 448 | 449 | 450 | 451 | 452 | 453 | 0 454 | 100 455 | 456 | 457 | 458 | 459 | 16777215 460 | 100 461 | 462 | 463 | 464 | 常用工具 465 | 466 | 467 | Qt::AlignCenter 468 | 469 | 470 | 471 | 472 | 10 473 | 30 474 | 151 475 | 70 476 | 477 | 478 | 479 | 480 | 481 | 482 | 清空终端 483 | 484 | 485 | 486 | 487 | 488 | 489 | 查看所有主题 490 | 491 | 492 | 493 | 494 | 495 | 496 | 497 | 498 | 499 | 500 | 501 | 0 502 | 0 503 | 504 | 505 | 506 | 507 | 0 508 | 380 509 | 510 | 511 | 512 | 消息订阅 513 | 514 | 515 | Qt::AlignCenter 516 | 517 | 518 | 519 | 520 | 10 521 | 30 522 | 231 523 | 351 524 | 525 | 526 | 527 | 528 | 1 529 | 530 | 531 | 532 | 533 | Refresh 534 | 535 | 536 | 537 | 538 | 539 | 540 | 导航地图 541 | 542 | 543 | 544 | 545 | 546 | 547 | 稀疏点云地图 548 | 549 | 550 | 551 | 552 | 553 | 554 | 555 | 556 | 557 | Refresh 558 | 559 | 560 | 561 | 562 | 563 | 564 | Refresh 565 | 566 | 567 | 568 | 569 | 570 | 571 | 实例分割 572 | 573 | 574 | 575 | 576 | 577 | 578 | 579 | 580 | 581 | Refresh 582 | 583 | 584 | 585 | 586 | 587 | 588 | 589 | 590 | 591 | 数据源 592 | 593 | 594 | 595 | 596 | 597 | 598 | 599 | 600 | 601 | 602 | 603 | 604 | 稠密点云地图 605 | 606 | 607 | 608 | 609 | 610 | 611 | 612 | 80 613 | 16777215 614 | 615 | 616 | 617 | Refresh 618 | 619 | 620 | 621 | 622 | 623 | 624 | 625 | 626 | 627 | 628 | 629 | 0 630 | 0 631 | 632 | 633 | 634 | 635 | 100 636 | 70 637 | 638 | 639 | 640 | 641 | 16777215 642 | 60 643 | 644 | 645 | 646 | 点云大小 647 | 648 | 649 | Qt::AlignCenter 650 | 651 | 652 | 653 | 654 | 10 655 | 30 656 | 175 657 | 31 658 | 659 | 660 | 661 | 662 | 663 | 664 | 665 | 100 666 | 0 667 | 668 | 669 | 670 | 1 671 | 672 | 673 | 5 674 | 675 | 676 | Qt::Horizontal 677 | 678 | 679 | 680 | 681 | 682 | 683 | 1 684 | 685 | 686 | Qt::AlignCenter 687 | 688 | 689 | 690 | 691 | 692 | 693 | 694 | 695 | 696 | 697 | 698 | 0 699 | 0 700 | 701 | 702 | 703 | 704 | 0 705 | 100 706 | 707 | 708 | 709 | 710 | 16777215 711 | 80 712 | 713 | 714 | 715 | 显示实例 716 | 717 | 718 | Qt::AlignCenter 719 | 720 | 721 | 722 | 723 | 10 724 | 30 725 | 151 726 | 61 727 | 728 | 729 | 730 | 731 | 1 732 | 733 | 734 | 735 | 736 | 稠密点云地图 737 | 738 | 739 | 740 | 741 | 742 | 743 | 稀疏点云地图 744 | 745 | 746 | 747 | 748 | 749 | 750 | 751 | 752 | 753 | 754 | 755 | 0 756 | 0 757 | 758 | 759 | 760 | 761 | 0 762 | 100 763 | 764 | 765 | 766 | 767 | 16777215 768 | 100 769 | 770 | 771 | 772 | 显示轨迹 773 | 774 | 775 | Qt::AlignCenter 776 | 777 | 778 | 779 | 780 | 10 781 | 30 782 | 151 783 | 61 784 | 785 | 786 | 787 | 788 | 1 789 | 790 | 791 | 792 | 793 | 稠密点云地图 794 | 795 | 796 | 797 | 798 | 799 | 800 | 稀疏点云地图 801 | 802 | 803 | 804 | 805 | 806 | 807 | 808 | 809 | 810 | 811 | 812 | 0 813 | 100 814 | 815 | 816 | 817 | 818 | 16777215 819 | 100 820 | 821 | 822 | 823 | 显示标签 824 | 825 | 826 | Qt::AlignCenter 827 | 828 | 829 | 830 | 831 | 10 832 | 20 833 | 160 834 | 80 835 | 836 | 837 | 838 | 839 | 840 | 841 | 稠密点云地图 842 | 843 | 844 | 845 | 846 | 847 | 848 | 稀疏点云地图 849 | 850 | 851 | 852 | 853 | 854 | 855 | 856 | 857 | 858 | 859 | 860 | 0 861 | 100 862 | 863 | 864 | 865 | 866 | 16777215 867 | 500 868 | 869 | 870 | 871 | 语音控制 872 | 873 | 874 | Qt::AlignCenter 875 | 876 | 877 | 878 | 879 | 10 880 | 30 881 | 161 882 | 61 883 | 884 | 885 | 886 | 887 | 1 888 | 889 | 890 | 891 | 892 | 语音输入 893 | 894 | 895 | 896 | 897 | 898 | 899 | 语音输出 900 | 901 | 902 | 903 | 904 | 905 | 906 | 907 | 908 | 909 | 910 | 911 | 912 | 913 | 914 | 915 | 916 | 917 | 918 | 919 | 920 | 0 921 | 0 922 | 1939 923 | 28 924 | 925 | 926 | 927 | 928 | 929 | 930 | 931 | QVTKWidget 932 | QWidget 933 |
QVTKWidget.h
934 |
935 |
936 | 937 | 938 |
939 | --------------------------------------------------------------------------------