简易C++实现Qt
Qt 环境配置
C++ 开发ROS项目过程中,如果要引入Qt,需要进行依赖的配置。
以新建的demo_turtle
package为例,我们就要对CMakeLists.txt
进行依赖配置。
1. 添加c++ 11编译的支持
Tip
默认的时候,这个配置是被注释起来的,我们只要解开注释就可以。
2. 添加Qt的环境配置
| ##############################################################################
# Qt Environment
##############################################################################
set(CMAKE_INCLUDE_CURRENT_DIR ON)
set(CMAKE_AUTOMOC ON)
find_package(Qt5 COMPONENTS Core Gui Widgets PrintSupport)
##############################################################################
|
Tip
find_package中,都是要加载的Qt模块,后续如果还需要添加其他的Qt模块,可以在后面追加。
Node 创建流程
1. 创建node启动的cpp文件
在src
目录下创建turtle_control.cpp
,代码如下:
| #include "ros/ros.h"
#include <iostream>
using namespace std;
int main(int argc, char *argv[]) {
string nodeName = "qt_turtle_ctrl";
// 创建节点
ros::init(argc,argv,nodeName);
ros::NodeHandle node;
return 0;
}
|
2. 配置CMake
来到CMakeLists.txt
文件中,添加如下:
| add_executable(turtle_control src/turtle_control.cpp)
target_link_libraries(turtle_control
${catkin_LIBRARIES}
Qt5::Core
Qt5::Gui
Qt5::Widgets
Qt5::PrintSupport
)
|
Tip
add_executable
是把turtle_control.cpp
标记为可执行的
target_link_libraries
是为turtle_control.cpp
提供链接库的,值得注意的是,${catkin_LIBRARIES}
是ros的依赖库,Qt5::Core
,Qt5::Gui
,Qt5::Wigets
,Qt5::PrintSupport
是qt的依赖库。
Qt UI的创建
1. Qt库的引入
| #include <QtWidgets>
#include <QApplication>
|
Tip
QtWidgets
是qt的组件模块,提供大量的ui控件
QApplication
是Qt应用入口
2. 编写Qt窗体
| // 创建Qt Application
QApplication app(argc, argv);
// 创建窗体
QWidget window;
// 设置窗体为当前激活窗体
app.setActiveWindow(&window);
//显示窗体
window.show();
// Qt程序执行
app.exec();
|
3. 根据需求进行UI布局
1
2
3
4
5
6
7
8
9
10
11
12
13
14 | // 设置布局
QFormLayout *layout = new QFormLayout();
window.setLayout(layout);
//线速度
editLinear = new QLineEdit();
editLinear->setText("0.0");
layout->addRow("线速度", editLinear);
//角速度
editDegrees = new QLineEdit();
editDegrees->setText("0.0");
layout->addRow("角速度", editDegrees);
//发送
btnSend = new QPushButton("发送");
layout->addRow(btnSend);
|
4. 事件添加
| btnSend->connect(btnSend, &QPushButton::clicked, &window, btnClicked);
void btnClicked() {
std::cout << "clicked" << std::endl;
}
|
Publisher创建
1. 创建publisher对象
| const ros::Publisher &publisher = node.advertise(topicName, 1000);
|
Tip
值得注意的是,在创建publisher对象时,这里要去确定的有两个点,第一就是topicName,第二就是传递的消息类型。
此处我们只能确定topic 的名称,给小乌龟发送数据的topic为/turtle1/cmd_vel
2. 确定消息传递的数据类型
通过rostopic命令查询主题对应的消息类型
| rostopic type /turtle1/cmd_vel
|
得到的结果为geometry_msgs/Twist
接下来我们需要导入这个消息类型对应的库
| #include "geometry_msgs/Twist.h"
|
接下来就是确定publisher创建时候的类型
| const ros::Publisher &publisher = node.advertise<geometry_msgs::Twist>(topicName, 1000);
|
Tip
一些规律的掌握,消息类型为geometry_msgs/Twist
,需要导入的头文件为geometry_msgs/Twist.h
,需要确定的编码类型为geometry_msgs::Twist
3. 发送消息
| //创建消息
geometry_msgs::Twist twist;
//填充消息数据
twist.linear.x = linearX;
twist.angular.z = angularZ * M_PI / 180;
//发送消息
publisherPtr->publish(twist);
|
完整实例代码
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69 | #include <iostream>
#include "ros/ros.h"
#include "std_msgs/String.h"
#include "geometry_msgs/Twist.h"
#include <QtWidgets>
#include <QApplication>
using namespace std;
const ros::Publisher *publisherPtr;
QLineEdit *editLinear;
QLineEdit *editDegrees;
QPushButton *btnSend;
void btnClicked() {
double linearX = editLinear->text().toDouble();
double angularZ = editDegrees->text().toDouble();
//创建消息
geometry_msgs::Twist twist;
//填充消息
twist.linear.x = linearX;
twist.angular.z = angularZ * M_PI / 180;
//发送消息
publisherPtr->publish(twist);
}
int main(int argc, char **argv) {
// 创建节点
string nodeName = "turtle_ctrl";
ros::init(argc, argv, nodeName);
ros::NodeHandle node;
//通过节点创建发布者
string topicName = "/turtle1/cmd_vel";
const ros::Publisher &publisher = node.advertise<geometry_msgs::Twist>(topicName, 1000);
publisherPtr = &publisher;
//创建Qt Application
QApplication app(argc, argv);
QWidget window;
// 设置窗体样式
window.resize(400, 0);
window.setWindowTitle("小乌龟控制器");
// 设置布局
QFormLayout *layout = new QFormLayout();
window.setLayout(layout);
editLinear = new QLineEdit();
editLinear->setText("0.0");
layout->addRow("线速度", editLinear);
editDegrees = new QLineEdit();
editDegrees->setText("0.0");
layout->addRow("角速度", editDegrees);
btnSend = new QPushButton("发送");
layout->addRow(btnSend);
//显示窗体
window.show();
//点击事件
btnSend->connect(btnSend, &QPushButton::clicked, &window, btnClicked);
return app.exec();
}
|