优化键盘控制界面

pull/12/head
大耳刮子 3 years ago
parent 545537255b
commit f9de4ae955

@ -11,6 +11,7 @@ find_package(catkin REQUIRED COMPONENTS
roscpp roscpp
std_msgs std_msgs
cv_bridge cv_bridge
sensor_msgs
image_transport image_transport
) )
@ -122,12 +123,12 @@ set(CMAKE_INCLUDE_CURRENT_DIR ON)
set(SOURCES set(SOURCES
src/include/qnode.hpp src/include/qnode.hpp
src/include/roskeyboardteleopnode.h
src/main/main.cpp src/main/main.cpp
src/main/mainwindow.cpp src/main/mainwindow.cpp
src/main/qnode.cpp src/main/qnode.cpp
src/main/roskeyboardteleopnode.cpp
src/ui/mainwindow.hpp src/ui/mainwindow.hpp
src/ui/mainwindow.ui src/ui/mainwindow.ui

@ -4,6 +4,8 @@
#ifndef Q_MOC_RUN #ifndef Q_MOC_RUN
#include <ros/ros.h> #include <ros/ros.h>
#endif #endif
#include <iostream>
#include <QImage> #include <QImage>
#include <opencv2/core/core.hpp> #include <opencv2/core/core.hpp>
@ -17,6 +19,8 @@
#include <geometry_msgs/Twist.h> #include <geometry_msgs/Twist.h>
#include <QThread> #include <QThread>
using namespace std;
class QNode : public QThread{ class QNode : public QThread{
Q_OBJECT Q_OBJECT
@ -25,25 +29,16 @@ public:
virtual ~QNode(); virtual ~QNode();
bool init(); bool init();
void SubAndPubTopic(); void SubAndPubTopic();
void KeyboardMove(char key); void KeyboardMove(char key, float speed_linear, float speed_trun);
//void myCallback_img(const sensor_msgs::ImageConstPtr& msg);//camera callback function
//QImage image;
//Q_SIGNALS:
//void loggingCamera();//发出设置相机图片信号
private: private:
int init_argc; int init_argc;
char **init_argv; char **init_argv;
ros::Subscriber cmdVel_sub; ros::Subscriber cmdVel_sub;
ros::Publisher cmd_pub; ros::Publisher KeyboardControl_cmd_pub;
//ros::Publisher chatter_publisher;
//QStringList logging_model;
//image_transport::Subscriber image_sub;
//cv::Mat img;
}; };
#endif #endif

@ -23,58 +23,80 @@ void MainWindow::slot_keyboard_control(){
QPushButton *btn = qobject_cast<QPushButton *>(sender()); QPushButton *btn = qobject_cast<QPushButton *>(sender());
std::string btn_name = btn->text().toStdString(); std::string btn_name = btn->text().toStdString();
char key = ' '; char key = ' ';
if (btn_name == ""){
key = 'a'; if (btn_name == "")
} key = '1';
else if (btn_name == "") { else if (btn_name == "")
key = 'd'; key = '2';
} else if (btn_name == "")
else if (btn_name == "") { key = '3';
key = 'w'; else if (btn_name == "")
} key = '4';
else if (btn_name == "") { //else if (btn_name == "")
key = 's'; // key = '5';
} else if (btn_name == "")
/* key = '6';
else if (btn_name == "加速") { else if (btn_name == "")
key = 'f'; key = '7';
} else if (btn_name == "")
*/ key = '8';
else if (btn_name == "")
key = '9';
qnode.KeyboardMove(key);
//速度
float liner = ui->horizontalSlider_linear->value() * 0.01;
float turn = ui->horizontalSlider_raw->value() * 0.01;
//bool is_rage_mode = ui->checkBox_rage_mode->isChecked();
std::cout<<liner<<" "<<turn<<std::endl;
qnode.KeyboardMove(key, liner, turn);
} }
void MainWindow::connections(){ void MainWindow::connections(){
//绑定速度控制按钮 //绑定速度控制按钮
ui->pushButton_W->setShortcut(Qt::Key_W); // 8 -> Forward:↑
connect(ui->pushButton_W, SIGNAL(clicked()), this, SLOT(slot_keyboard_control())); ui->pushButton_Forward->setShortcut(Qt::Key_8);
ui->pushButton_S->setShortcut(Qt::Key_S); connect(ui->pushButton_Forward, SIGNAL(clicked()), this, SLOT(slot_keyboard_control()));
connect(ui->pushButton_S, SIGNAL(clicked()), this, SLOT(slot_keyboard_control()));
ui->pushButton_A->setShortcut(Qt::Key_A); ui->pushButton_Back->setShortcut(Qt::Key_2);
connect(ui->pushButton_A, SIGNAL(clicked()), this, SLOT(slot_keyboard_control())); connect(ui->pushButton_Back, SIGNAL(clicked()), this, SLOT(slot_keyboard_control()));
ui->pushButton_D->setShortcut(Qt::Key_D);
connect(ui->pushButton_D, SIGNAL(clicked()), this, SLOT(slot_keyboard_control())); ui->pushButton_Left->setShortcut(Qt::Key_4);
connect(ui->pushButton_shift, SIGNAL(clicked()), this, SLOT(slot_keyboard_control())); connect(ui->pushButton_Left, SIGNAL(clicked()), this, SLOT(slot_keyboard_control()));
//
//QObject::connect(&qnode, SIGNAL(loggingCamera()), this, SLOT(slot_updateCamera())); ui->pushButton_Right->setShortcut(Qt::Key_6);
} connect(ui->pushButton_Right, SIGNAL(clicked()), this, SLOT(slot_keyboard_control()));
ui->pushButton_Left_Forward->setShortcut(Qt::Key_7);
connect(ui->pushButton_Left_Forward, SIGNAL(clicked()), this, SLOT(slot_keyboard_control()));
ui->pushButton_Right_Forward->setShortcut(Qt::Key_9);
connect(ui->pushButton_Right_Forward, SIGNAL(clicked()), this, SLOT(slot_keyboard_control()));
/* ui->pushButton_Left_Back->setShortcut(Qt::Key_1);
void MainWindow::slot_dispalyCamera(const QImage &image){ connect(ui->pushButton_Left_Back, SIGNAL(clicked()), this, SLOT(slot_keyboard_control()));
qimage_mutex.lock();
qimage = image.copy(); ui->pushButton_Right_Back->setShortcut(Qt::Key_3);
ui->UGV_Vedio->setPixmap(QPixmap::fromImage(qimage)); connect(ui->pushButton_Right_Back, SIGNAL(clicked()), this, SLOT(slot_keyboard_control()));
ui->UGV_Vedio->resize(ui->UGV_Vedio->pixmap()->size());
qimage_mutex.unlock();
ui->pushButton_shift->setShortcut(Qt::ShiftModifier);
connect(ui->pushButton_shift, SIGNAL(clicked()), this, SLOT(slot_keyboard_control()));
//绑定slider的函数
connect(ui->horizontalSlider_raw, SIGNAL(valueChanged(int)), this,
SLOT(Slider_raw_valueChanged(int)));
connect(ui->horizontalSlider_linear, SIGNAL(valueChanged(int)), this,
SLOT(Slider_linear_valueChanged(int)));
} }
void MainWindow::slot_updateCamera() //滑动条处理槽函数
{ void MainWindow::Slider_raw_valueChanged(int v) {
slot_dispalyCamera(qnode.image); ui->label_raw->setText(QString::number(v));
}
//滑动条处理槽函数
void MainWindow::Slider_linear_valueChanged(int v) {
ui->label_linear->setText(QString::number(v));
} }
*/

@ -27,40 +27,38 @@ bool QNode::init() {
void QNode::SubAndPubTopic(){ void QNode::SubAndPubTopic(){
ros::NodeHandle n; ros::NodeHandle n;
cmd_pub = n.advertise<geometry_msgs::Twist>("cmd_vel", 1); KeyboardControl_cmd_pub = n.advertise<geometry_msgs::Twist>("cmd_vel", 1);
} }
void QNode::KeyboardMove(char key){ void QNode::KeyboardMove(char key, float speed_linear, float speed_trun){
std::map<char, std::vector<float>> moveBindings { std::map<char, std::vector<float>> moveBindings {
// {'key', {speed, turn}} // {'key', {x, y, z, th}}
{'w', {1, 0}}, {'s', {-1, 0}}, {'a', {0, 1}}, {'d', {0, -1}}, {'7', {1, 1, 0, 0}}, {'8', {1, 0, 0, 0}}, {'9', {1, -1, 0, 0}},
{'W', {1, 0}}, {'S', {-1, 0}}, {'A', {0, 1}}, {'D', {0, -1}} {'4', {0, 0, 0, 1}}, {'5', {0, 0, 0, 0}}, {'6', {0, 0, 0, -1}},
{'1', {-1, 1, 0, 0}}, {'2', {-1, 0, 0, 0}}, {'3', {-1, -1, 0, 0}}
}; };
float x = moveBindings[key][0]; float x = moveBindings[key][0];
float z = moveBindings[key][1]; float y = moveBindings[key][1];
float z = moveBindings[key][2];
float th = moveBindings[key][3];
//计算线速度和角速度
float speed = speed_linear;
float turn = speed_trun;
geometry_msgs::Twist twist; geometry_msgs::Twist twist;
twist.linear.x = x; twist.linear.x = x * speed;
twist.angular.z = z; twist.linear.y = y * speed;
cmd_pub.publish(twist); twist.linear.z = z * speed;
twist.angular.x = 0;
twist.angular.y = 0;
twist.angular.z = th * turn;
KeyboardControl_cmd_pub.publish(twist);
ros::spinOnce(); ros::spinOnce();
} }
/*
void QNode::myCallback_img(const sensor_msgs::ImageConstPtr &msg)
{
try
{
cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::RGB8);
img = cv_ptr->image;
image = QImage(img.data,img.cols,img.rows,img.step[0],QImage::Format_RGB888);//change to QImage format
ROS_INFO("I'm setting picture in mul_t callback function!");
Q_EMIT loggingCamera();
}
catch (cv_bridge::Exception& e)
{
ROS_ERROR("Could not convert from '%s' to 'bgr8'.", msg->encoding.c_str());
}
}
*/

@ -22,15 +22,17 @@ public:
public slots: public slots:
void slot_keyboard_control(); void slot_keyboard_control();
//void slot_updateCamera(); //void slot_command_control(int linear, int angular);
//void slot_dispalyCamera(const QImage& image); void Slider_raw_valueChanged(int v);
void Slider_linear_valueChanged(int v);
private: private:
Ui::MainWindow *ui; Ui::MainWindow *ui;
void connections(); void connections();
QNode qnode; QNode qnode;
//QImage qimage;
//mutable QMutex qimage_mutex;
}; };

@ -15,151 +15,6 @@
</property> </property>
<widget class="QWidget" name="centralwidget"> <widget class="QWidget" name="centralwidget">
<widget class="QWidget" name="layoutWidget"> <widget class="QWidget" name="layoutWidget">
<property name="geometry">
<rect>
<x>1160</x>
<y>240</y>
<width>314</width>
<height>164</height>
</rect>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="1">
<widget class="QPushButton" name="pushButton_W">
<property name="minimumSize">
<size>
<width>100</width>
<height>50</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>50</height>
</size>
</property>
<property name="font">
<font>
<pointsize>15</pointsize>
</font>
</property>
<property name="text">
<string>前</string>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QPushButton" name="pushButton_D">
<property name="minimumSize">
<size>
<width>100</width>
<height>50</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>50</height>
</size>
</property>
<property name="font">
<font>
<pointsize>15</pointsize>
</font>
</property>
<property name="text">
<string>右</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QPushButton" name="pushButton_A">
<property name="minimumSize">
<size>
<width>100</width>
<height>50</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>50</height>
</size>
</property>
<property name="font">
<font>
<pointsize>15</pointsize>
</font>
</property>
<property name="text">
<string>左</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QPushButton" name="pushButton_S">
<property name="minimumSize">
<size>
<width>100</width>
<height>50</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>50</height>
</size>
</property>
<property name="font">
<font>
<pointsize>15</pointsize>
</font>
</property>
<property name="text">
<string>后</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QPushButton" name="pushButton_shift">
<property name="minimumSize">
<size>
<width>100</width>
<height>50</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>50</height>
</size>
</property>
<property name="font">
<font>
<pointsize>15</pointsize>
</font>
</property>
<property name="text">
<string>加速</string>
</property>
</widget>
</item>
</layout>
</widget>
<widget class="QLabel" name="UGV_Vedio">
<property name="geometry">
<rect>
<x>610</x>
<y>60</y>
<width>321</width>
<height>211</height>
</rect>
</property>
<property name="text">
<string>TextLabel</string>
</property>
</widget>
<widget class="QWidget" name="">
<property name="geometry"> <property name="geometry">
<rect> <rect>
<x>60</x> <x>60</x>
@ -231,6 +86,333 @@
</item> </item>
</layout> </layout>
</widget> </widget>
<widget class="QPushButton" name="pushButton_shift">
<property name="geometry">
<rect>
<x>760</x>
<y>70</y>
<width>100</width>
<height>50</height>
</rect>
</property>
<property name="minimumSize">
<size>
<width>100</width>
<height>50</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>50</height>
</size>
</property>
<property name="font">
<font>
<pointsize>15</pointsize>
</font>
</property>
<property name="text">
<string>加速</string>
</property>
</widget>
<widget class="QWidget" name="">
<property name="geometry">
<rect>
<x>1020</x>
<y>271</y>
<width>316</width>
<height>172</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="1">
<widget class="QPushButton" name="pushButton_Forward">
<property name="minimumSize">
<size>
<width>100</width>
<height>32</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>32</height>
</size>
</property>
<property name="font">
<font>
<pointsize>15</pointsize>
</font>
</property>
<property name="text">
<string>↑</string>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QPushButton" name="pushButton_Right">
<property name="minimumSize">
<size>
<width>100</width>
<height>32</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>32</height>
</size>
</property>
<property name="font">
<font>
<pointsize>15</pointsize>
</font>
</property>
<property name="text">
<string>→</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QPushButton" name="pushButton_Left">
<property name="minimumSize">
<size>
<width>100</width>
<height>32</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>32</height>
</size>
</property>
<property name="font">
<font>
<pointsize>15</pointsize>
</font>
</property>
<property name="text">
<string>←</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QPushButton" name="pushButton_Back">
<property name="minimumSize">
<size>
<width>100</width>
<height>32</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>32</height>
</size>
</property>
<property name="font">
<font>
<pointsize>15</pointsize>
</font>
</property>
<property name="text">
<string>↓</string>
</property>
</widget>
</item>
<item row="0" column="0">
<widget class="QPushButton" name="pushButton_Left_Forward">
<property name="minimumSize">
<size>
<width>100</width>
<height>32</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>32</height>
</size>
</property>
<property name="font">
<font>
<pointsize>15</pointsize>
</font>
</property>
<property name="text">
<string>↖</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QPushButton" name="pushButton_Right_Forward">
<property name="minimumSize">
<size>
<width>100</width>
<height>32</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>32</height>
</size>
</property>
<property name="font">
<font>
<pointsize>15</pointsize>
</font>
</property>
<property name="text">
<string>↗</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QPushButton" name="pushButton_Left_Back">
<property name="minimumSize">
<size>
<width>100</width>
<height>32</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>32</height>
</size>
</property>
<property name="font">
<font>
<pointsize>15</pointsize>
</font>
</property>
<property name="text">
<string>↙</string>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QPushButton" name="pushButton_Right_Back">
<property name="minimumSize">
<size>
<width>100</width>
<height>32</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>32</height>
</size>
</property>
<property name="font">
<font>
<pointsize>15</pointsize>
</font>
</property>
<property name="text">
<string>↘</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QCheckBox" name="checkBox">
<property name="minimumSize">
<size>
<width>100</width>
<height>32</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>32</height>
</size>
</property>
<property name="font">
<font>
<pointsize>12</pointsize>
</font>
</property>
<property name="text">
<string>狂暴模式</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_21">
<item>
<widget class="QLabel" name="label_linear_">
<property name="text">
<string>线速度(cm/s)</string>
</property>
</widget>
</item>
<item>
<widget class="QSlider" name="horizontalSlider_linear">
<property name="maximum">
<number>100</number>
</property>
<property name="singleStep">
<number>1</number>
</property>
<property name="value">
<number>50</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_linear">
<property name="text">
<string>100</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_20">
<item>
<widget class="QLabel" name="label_raw_">
<property name="text">
<string>角速度(cm/s)</string>
</property>
</widget>
</item>
<item>
<widget class="QSlider" name="horizontalSlider_raw">
<property name="maximum">
<number>100</number>
</property>
<property name="value">
<number>100</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_raw">
<property name="text">
<string>100</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</widget> </widget>
<widget class="QMenuBar" name="menubar"> <widget class="QMenuBar" name="menubar">
<property name="geometry"> <property name="geometry">

Loading…
Cancel
Save