diff --git a/CMakeLists.txt b/CMakeLists.txt index ec4c611..5fbf8b1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -11,6 +11,7 @@ find_package(catkin REQUIRED COMPONENTS roscpp std_msgs cv_bridge + sensor_msgs image_transport ) @@ -122,12 +123,12 @@ set(CMAKE_INCLUDE_CURRENT_DIR ON) set(SOURCES src/include/qnode.hpp - src/include/roskeyboardteleopnode.h + src/main/main.cpp src/main/mainwindow.cpp src/main/qnode.cpp - src/main/roskeyboardteleopnode.cpp + src/ui/mainwindow.hpp src/ui/mainwindow.ui diff --git a/src/include/qnode.hpp b/src/include/qnode.hpp index 8585220..8e43ba7 100644 --- a/src/include/qnode.hpp +++ b/src/include/qnode.hpp @@ -4,6 +4,8 @@ #ifndef Q_MOC_RUN #include #endif +#include + #include #include @@ -17,6 +19,8 @@ #include #include +using namespace std; + class QNode : public QThread{ Q_OBJECT @@ -25,25 +29,16 @@ public: virtual ~QNode(); bool init(); void SubAndPubTopic(); - void KeyboardMove(char key); - //void myCallback_img(const sensor_msgs::ImageConstPtr& msg);//camera callback function - //QImage image; - + void KeyboardMove(char key, float speed_linear, float speed_trun); -//Q_SIGNALS: - //void loggingCamera();//发出设置相机图片信号 private: int init_argc; char **init_argv; ros::Subscriber cmdVel_sub; - ros::Publisher cmd_pub; - //ros::Publisher chatter_publisher; - //QStringList logging_model; - //image_transport::Subscriber image_sub; + ros::Publisher KeyboardControl_cmd_pub; -//cv::Mat img; }; #endif diff --git a/src/main/mainwindow.cpp b/src/main/mainwindow.cpp index 46c1caa..7a22062 100644 --- a/src/main/mainwindow.cpp +++ b/src/main/mainwindow.cpp @@ -23,58 +23,80 @@ void MainWindow::slot_keyboard_control(){ QPushButton *btn = qobject_cast(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); + + if (btn_name == "↙") + key = '1'; + else if (btn_name == "↓") + key = '2'; + else if (btn_name == "↘") + key = '3'; + else if (btn_name == "←") + key = '4'; + //else if (btn_name == "") + // key = '5'; + else if (btn_name == "→") + key = '6'; + else if (btn_name == "↖") + key = '7'; + else if (btn_name == "↑") + key = '8'; + else if (btn_name == "↗") + key = '9'; + + //速度 + 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<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())); - // - //QObject::connect(&qnode, SIGNAL(loggingCamera()), this, SLOT(slot_updateCamera())); -} + // 8 -> Forward:↑ + ui->pushButton_Forward->setShortcut(Qt::Key_8); + connect(ui->pushButton_Forward, SIGNAL(clicked()), this, SLOT(slot_keyboard_control())); + + ui->pushButton_Back->setShortcut(Qt::Key_2); + connect(ui->pushButton_Back, SIGNAL(clicked()), this, SLOT(slot_keyboard_control())); + + ui->pushButton_Left->setShortcut(Qt::Key_4); + connect(ui->pushButton_Left, SIGNAL(clicked()), this, SLOT(slot_keyboard_control())); + + 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())); -/* -void MainWindow::slot_dispalyCamera(const QImage &image){ - qimage_mutex.lock(); - qimage = image.copy(); - ui->UGV_Vedio->setPixmap(QPixmap::fromImage(qimage)); - ui->UGV_Vedio->resize(ui->UGV_Vedio->pixmap()->size()); - qimage_mutex.unlock(); + ui->pushButton_Left_Back->setShortcut(Qt::Key_1); + connect(ui->pushButton_Left_Back, SIGNAL(clicked()), this, SLOT(slot_keyboard_control())); + + ui->pushButton_Right_Back->setShortcut(Qt::Key_3); + connect(ui->pushButton_Right_Back, SIGNAL(clicked()), this, SLOT(slot_keyboard_control())); + + + 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() -{ - slot_dispalyCamera(qnode.image); +//滑动条处理槽函数 +void MainWindow::Slider_raw_valueChanged(int v) { + ui->label_raw->setText(QString::number(v)); +} +//滑动条处理槽函数 +void MainWindow::Slider_linear_valueChanged(int v) { + ui->label_linear->setText(QString::number(v)); } -*/ diff --git a/src/main/qnode.cpp b/src/main/qnode.cpp index 35c7ed5..8829c44 100644 --- a/src/main/qnode.cpp +++ b/src/main/qnode.cpp @@ -27,40 +27,38 @@ bool QNode::init() { void QNode::SubAndPubTopic(){ ros::NodeHandle n; - cmd_pub = n.advertise("cmd_vel", 1); + KeyboardControl_cmd_pub = n.advertise("cmd_vel", 1); } -void QNode::KeyboardMove(char key){ +void QNode::KeyboardMove(char key, float speed_linear, float speed_trun){ std::map> 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}} + // {'key', {x, y, z, th}} + {'7', {1, 1, 0, 0}}, {'8', {1, 0, 0, 0}}, {'9', {1, -1, 0, 0}}, + {'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 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; - twist.linear.x = x; - twist.angular.z = z; - cmd_pub.publish(twist); + twist.linear.x = x * speed; + twist.linear.y = y * speed; + 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(); } -/* -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()); - } -} -*/ diff --git a/src/ui/mainwindow.hpp b/src/ui/mainwindow.hpp index 3254020..9f5189d 100644 --- a/src/ui/mainwindow.hpp +++ b/src/ui/mainwindow.hpp @@ -22,15 +22,17 @@ public: public slots: void slot_keyboard_control(); - //void slot_updateCamera(); - //void slot_dispalyCamera(const QImage& image); + //void slot_command_control(int linear, int angular); + void Slider_raw_valueChanged(int v); + void Slider_linear_valueChanged(int v); + + private: Ui::MainWindow *ui; void connections(); QNode qnode; - //QImage qimage; - //mutable QMutex qimage_mutex; + }; diff --git a/src/ui/mainwindow.ui b/src/ui/mainwindow.ui index a3c59f5..5460ecb 100644 --- a/src/ui/mainwindow.ui +++ b/src/ui/mainwindow.ui @@ -15,151 +15,6 @@ - - - 1160 - 240 - 314 - 164 - - - - - - - - 100 - 50 - - - - - 100 - 50 - - - - - 15 - - - - - - - - - - - - 100 - 50 - - - - - 100 - 50 - - - - - 15 - - - - - - - - - - - - 100 - 50 - - - - - 100 - 50 - - - - - 15 - - - - - - - - - - - - 100 - 50 - - - - - 100 - 50 - - - - - 15 - - - - - - - - - - - - 100 - 50 - - - - - 100 - 50 - - - - - 15 - - - - 加速 - - - - - - - - - 610 - 60 - 321 - 211 - - - - TextLabel - - - 60 @@ -231,6 +86,333 @@ + + + + 760 + 70 + 100 + 50 + + + + + 100 + 50 + + + + + 100 + 50 + + + + + 15 + + + + 加速 + + + + + + 1020 + 271 + 316 + 172 + + + + + + + + + + 100 + 32 + + + + + 100 + 32 + + + + + 15 + + + + + + + + + + + + 100 + 32 + + + + + 100 + 32 + + + + + 15 + + + + + + + + + + + + 100 + 32 + + + + + 100 + 32 + + + + + 15 + + + + + + + + + + + + 100 + 32 + + + + + 100 + 32 + + + + + 15 + + + + + + + + + + + + 100 + 32 + + + + + 100 + 32 + + + + + 15 + + + + + + + + + + + + 100 + 32 + + + + + 100 + 32 + + + + + 15 + + + + + + + + + + + + 100 + 32 + + + + + 100 + 32 + + + + + 15 + + + + + + + + + + + + 100 + 32 + + + + + 100 + 32 + + + + + 15 + + + + + + + + + + + + 100 + 32 + + + + + 100 + 32 + + + + + 12 + + + + 狂暴模式 + + + + + + + + + + + 线速度(cm/s): + + + + + + + 100 + + + 1 + + + 50 + + + Qt::Horizontal + + + + + + + 100 + + + + + + + + + + + 角速度(cm/s): + + + + + + + 100 + + + 100 + + + Qt::Horizontal + + + + + + + 100 + + + + + + +