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
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109 | #include "MainWindow2.h"
#include <iostream>
#include "ros/ros.h"
#include "geometry_msgs/Twist.h"
#include <math.h>
using namespace std;
MainWindow2::MainWindow2(ros::NodeHandle *node, QWidget *parent) : QWidget(parent), node(node) {
//初始化控件和布局
initWidgets();
}
MainWindow2::~MainWindow2() = default;
void MainWindow2::initWidgets() {
updateTimer = new QTimer(this);
updateTimer->setInterval(16);
updateTimer->start();
connect(updateTimer, &QTimer::timeout, this, &MainWindow2::onUpdate);
//窗体设置
setWindowTitle("小乌龟控制");
//设置窗体大小
resize(400, 120);
//设置布局
layout = new QFormLayout();
setLayout(layout);
//添加输入框
editLinear = new QLineEdit();
layout->addRow("线速度", editLinear);
//添加输入框
editAngular = new QLineEdit();
layout->addRow("角速度", editAngular);
//添加显示
labelX = new QLabel();
layout->addRow("当前X坐标", labelX);
labelY = new QLabel();
layout->addRow("当前Y坐标", labelY);
labelLinear = new QLabel();
layout->addRow("当前线速度", labelLinear);
labelAngular = new QLabel();
layout->addRow("当前角速度", labelAngular);
labelDegrees = new QLabel();
layout->addRow("当前角度", labelDegrees);
//添加按钮
btnSend = new QPushButton("发送");
layout->addRow(btnSend);
//添加事件
btnSend->connect(btnSend, &QPushButton::clicked, this, &MainWindow2::clickSend);
//初始化publisher
string topicName = "/turtle1/cmd_vel";
publisher = node->advertise<geometry_msgs::Twist>(topicName, 1000);
//初始化subscriber
string poseTopicName = "/turtle1/pose";
subscriber = node->subscribe(poseTopicName, 1000, &MainWindow2::poseCallback, this);
}
void MainWindow2::clickSend() {
double linearX = editLinear->text().toDouble();
double angularZ = editAngular->text().toDouble();
cout << "linear.x: " << linearX << endl;
cout << "angular.z: " << angularZ << endl;
//创建消息
geometry_msgs::Twist twist;
//填充消息
twist.linear.x = linearX;
twist.angular.z = angularZ * M_PI / 180;
//发送消息
publisher.publish(twist);
}
void MainWindow2::poseCallback(const turtlesim::Pose::ConstPtr &message) {
double x = message->x;
double y = message->y;
float linear = message->linear_velocity;
float angular = message->angular_velocity;
float theta = message->theta;
labelX->setText(QString::fromStdString(to_string(x)));
labelY->setText(QString::fromStdString(to_string(y)));
labelLinear->setText(QString::fromStdString(to_string(linear)));
labelAngular->setText(QString::fromStdString(to_string(angular)));
labelDegrees->setText(QString::fromStdString(to_string(theta * 180 / M_PI)));
}
void MainWindow2::onUpdate() {
ros::spinOnce();
update();
if (!ros::ok()) {
close();
}
}
|