pull/25/head
13195980010 3 years ago
parent c2d15bf178
commit d26d56759c

@ -1,50 +0,0 @@
#ifndef Air_Ground_CEC_QNODE_HPP_
#define Air_Ground_CEC_QNODE_HPP_
#ifndef Q_MOC_RUN
#include <ros/ros.h>
#endif
#include <QImage>
#include <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <std_msgs/String.h>
#include <ros/network.h>
#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>
#include <geometry_msgs/Twist.h>
#include <QThread>
class QNode : public QThread{
Q_OBJECT
public:
QNode(int argc, char **argv);
virtual ~QNode();
bool init();
void SubAndPubTopic();
void KeyboardMove(char key);
//void myCallback_img(const sensor_msgs::ImageConstPtr& msg);//camera callback function
//QImage image;
//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;
//cv::Mat img;
};
#endif

@ -1,24 +0,0 @@
#include "../ui/mainwindow.hpp"
#include <QApplication>
#include <ros/ros.h>
int main(int argc, char** argv)
{
QApplication app(argc, argv);
MainWindow CEC(0,0,0);
CEC.show();
return app.exec();
return(0);
}

@ -1,66 +0,0 @@
#include "../include/qnode.hpp"
#include "sensor_msgs/image_encodings.h"
QNode::QNode(int argc, char **argv) : init_argc(argc), init_argv(argv){
}
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,"Air_Ground_CEC",
ros::init_options::AnonymousName | ros::init_options::NoSigintHandler);
SubAndPubTopic();
return true;
}
void QNode::SubAndPubTopic(){
ros::NodeHandle n;
cmd_pub = n.advertise<geometry_msgs::Twist>("cmd_vel", 1);
}
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();
}
/*
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());
}
}
*/

@ -1,275 +0,0 @@
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>MainWindow</class>
<widget class="QMainWindow" name="MainWindow">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>1600</width>
<height>900</height>
</rect>
</property>
<property name="windowTitle">
<string>MainWindow</string>
</property>
<widget class="QWidget" name="centralwidget">
<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="layoutWidget">
<property name="geometry">
<rect>
<x>60</x>
<y>30</y>
<width>502</width>
<height>654</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QLabel" name="UAV_Vedio">
<property name="minimumSize">
<size>
<width>500</width>
<height>300</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>500</width>
<height>300</height>
</size>
</property>
<property name="mouseTracking">
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="text">
<string>UAV_VEDIO</string>
</property>
<property name="scaledContents">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="UAV_Path">
<property name="minimumSize">
<size>
<width>500</width>
<height>300</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>500</width>
<height>300</height>
</size>
</property>
<property name="text">
<string>PATH</string>
</property>
</widget>
</item>
</layout>
</widget>
<widget class="QLabel" name="StreamReceive">
<property name="geometry">
<rect>
<x>720</x>
<y>500</y>
<width>431</width>
<height>301</height>
</rect>
</property>
<property name="text">
<string/>
</property>
</widget>
<widget class="QPushButton" name="PLAY">
<property name="geometry">
<rect>
<x>1250</x>
<y>570</y>
<width>89</width>
<height>25</height>
</rect>
</property>
<property name="text">
<string>PLAY</string>
</property>
</widget>
</widget>
<widget class="QMenuBar" name="menubar">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>1600</width>
<height>27</height>
</rect>
</property>
</widget>
<widget class="QStatusBar" name="statusbar"/>
</widget>
<resources/>
<connections/>
</ui>
Loading…
Cancel
Save