#include "MainWindow1.h"
#include <iostream>
#include "ros/ros.h"
#include "geometry_msgs/Twist.h"
using namespace std;
MainWindow1::MainWindow1(ros::NodeHandle *node, QWidget *parent) : QWidget(parent) {
this->node = node;
//初始化控件和布局
initWidgets();
}
MainWindow1::~MainWindow1() = default;
void MainWindow1::initWidgets() {
//窗体设置
setWindowTitle("小乌龟控制");
//设置窗体大小
resize(400, 120);
//设置布局
layout = new QFormLayout();
setLayout(layout);
//添加输入框
editLinear = new QLineEdit();
layout->addRow("线速度", editLinear);
//添加输入框
editAngular = new QLineEdit();
layout->addRow("角速度", editAngular);
//添加按钮
btnSend = new QPushButton("发送");
layout->addRow(btnSend);
//添加事件
btnSend->connect(btnSend, &QPushButton::clicked, this, &MainWindow1::clickSend);
//初始化publisher
string topicName = "/turtle1/cmd_vel";
publisher = node->advertise<geometry_msgs::Twist>(topicName, 1000);
}
void MainWindow1::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);
}