键盘控制ros,在 gui 界面中实现

pull/9/head
大耳刮子 3 years ago
parent 72649e60fb
commit 01c3158d4e

@ -1,8 +1,29 @@
#include <opencv2/core.hpp>
#include <opencv2/highgui.hpp>
#include <opencv2/imgproc.hpp>
#include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h>
#include <QImage>
#ifndef Air_Ground_CEC_QNODE_HPP_
#define Air_Ground_CEC_QNODE_HPP_
#ifndef Q_MOC_RUN
#include <ros/ros.h>
#endif
#include <geometry_msgs/Twist.h>
#include <QThread>
class QNode : public QThread{
Q_OBJECT
public:
QNode(int argc, char **argv);
virtual ~QNode();
bool init();
void KeyboardMove(char key);
private:
int init_argc;
char **init_argv;
ros::NodeHandle n;
ros::Subscriber cmdVel_sub;
ros::Publisher cmd_pub;
};
#endif

@ -1,13 +1,24 @@
#include "../include/roskeyboardteleopnode.h"
#include "../ui/mainwindow.hpp"
#include <QApplication>
#include <ros/ros.h>
int main(int argc, char** argv)
{
ros::init(argc,argv,"tbk", ros::init_options::AnonymousName | ros::init_options::NoSigintHandler);
QApplication app(argc, argv);
MainWindow CEC(0,0,0);
CEC.show();
return app.exec();
/*
RosKeyboardTeleopNode tbk;
boost::thread t = boost::thread(boost::bind(&RosKeyboardTeleopNode::keyboardLoop, &tbk));
@ -18,7 +29,7 @@ int main(int argc, char** argv)
t.join();
tbk.stopRobot();
tcsetattr(kfd, TCSANOW, &cooked);
*/
return(0);
}

@ -1,14 +1,59 @@
#include "../ui/mainwindow.hpp"
MainWindow::MainWindow(QWidget *parent) :
QMainWindow(parent),
MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
QMainWindow(parent), qnode(argc, argv),
ui(new Ui::MainWindow)
{
ui->setupUi(this);
connections();
}
MainWindow::~MainWindow()
{
delete ui;
}
void MainWindow::slot_keyboard_control(){
QPushButton *btn = qobject_cast<QPushButton *>(sender());
std::string btn_name = btn->text().toStdString();
char key = ' ';
if (btn_name == ""){
key = 'a';
}
else if (btn_name == "") {
key = 'd';
}
else if (btn_name == "") {
key = 'w';
}
else if (btn_name == "") {
key = 's';
}
/*
else if (btn_name == "加速") {
key = 'f';
}
*/
qnode.KeyboardMove(key);
std::cout<<key<<std::endl;
}
void MainWindow::connections(){
//绑定速度控制按钮
ui->pushButton_W->setShortcut(Qt::Key_W);
connect(ui->pushButton_W, SIGNAL(clicked()), this, SLOT(slot_keyboard_control()));
ui->pushButton_S->setShortcut(Qt::Key_S);
connect(ui->pushButton_S, SIGNAL(clicked()), this, SLOT(slot_keyboard_control()));
ui->pushButton_A->setShortcut(Qt::Key_A);
connect(ui->pushButton_A, 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()));
connect(ui->pushButton_shift, SIGNAL(clicked()), this, SLOT(slot_keyboard_control()));
}

@ -1 +1,47 @@
#include "../include/qnode.hpp"
#include <ros/ros.h>
#include <std_msgs/String.h>
#include <ros/network.h>
QNode::QNode(int argc, char **argv) : init_argc(argc), init_argv(argv){
cmd_pub = n.advertise<geometry_msgs::Twist>("cmd_vel", 1);
}
QNode::~QNode() {
if (ros::isStarted()) {
ros::shutdown(); // explicitly needed since we use ros::start();
ros::waitForShutdown();
}
wait();
}
bool QNode::init() {
ros::init(init_argc, init_argv, "cyrobot_monitor",
ros::init_options::AnonymousName);
if (!ros::master::check()) {
return false;
}
ros::start(); // explicitly needed since our nodehandle is going out of
// scope.
start();
return true;
}
void QNode::KeyboardMove(char key){
std::map<char, std::vector<float>> moveBindings {
// {'key', {speed, turn}}
{'w', {1, 0}}, {'s', {-1, 0}}, {'a', {0, 1}}, {'d', {0, -1}},
{'W', {1, 0}}, {'S', {-1, 0}}, {'A', {0, 1}}, {'D', {0, -1}}
};
float x = moveBindings[key][0];
float z = moveBindings[key][1];
geometry_msgs::Twist twist;
twist.linear.x = x;
twist.angular.z = z;
cmd_pub.publish(twist);
ros::spinOnce();
}

@ -3,6 +3,8 @@
#include <QMainWindow>
#include "ui_mainwindow.h"
#include "../include/qnode.hpp"
namespace Ui {
class MainWindow;
}
@ -12,11 +14,17 @@ class MainWindow : public QMainWindow
Q_OBJECT
public:
explicit MainWindow(QWidget *parent = nullptr);
explicit MainWindow(int argc, char **argv, QWidget *parent = 0);
~MainWindow();
public slots:
void slot_keyboard_control();
private:
Ui::MainWindow *ui;
void connections();
QNode qnode;
};
#endif // MAINWINDOW_H

@ -1,24 +1,216 @@
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<author/>
<comment/>
<exportmacro/>
<class>MainWindow</class>
<widget name="MainWindow" class="QMainWindow">
<widget class="QMainWindow" name="MainWindow">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>800</width>
<height>600</height>
<width>1600</width>
<height>900</height>
</rect>
</property>
<property name="windowTitle">
<string>MainWindow</string>
</property>
<widget name="menubar" class="QMenuBar"/>
<widget name="centralwidget" class="QWidget"/>
<widget name="statusbar" class="QStatusBar"/>
<widget class="QWidget" name="centralwidget">
<widget class="QWidget" name="">
<property name="geometry">
<rect>
<x>410</x>
<y>260</y>
<width>314</width>
<height>164</height>
</rect>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="0">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<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="0" column="2">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</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="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>
<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="2" column="0">
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</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="2" column="2">
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</widget>
<widget class="QMenuBar" name="menubar">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>1600</width>
<height>22</height>
</rect>
</property>
</widget>
<widget class="QStatusBar" name="statusbar"/>
</widget>
<pixmapfunction/>
<resources/>
<connections/>
</ui>

Loading…
Cancel
Save