pull/25/head
13195980010 3 years ago
parent 51cd0088d3
commit c2d15bf178

@ -1,233 +0,0 @@
cmake_minimum_required(VERSION 3.0.2)
project(Air_Ground_CEC)
## Compile as C++11, supported in ROS Kinetic and newer
add_compile_options(-std=c++11)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
roscpp
std_msgs
cv_bridge
image_transport
)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installedsudo sh -c 'echo "/usr/local/lib" > /etc/ld.so.conf.d/opencv.conf'
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()
################################################
## Declare ROS messages, services and actions ##
################################################
## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend tag for "message_generation"
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a exec_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# )
## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )
## Generate added messages and services with any dependencies listed here
# generate_messages(
# DEPENDENCIES
# std_msgs # Or other packages containing msgs
# )
################################################
## Declare ROS dynamic reconfigure parameters ##
################################################
## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed
## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES Air_Ground_CEC
# CATKIN_DEPENDS roscpp
# DEPENDS system_lib
)
###########
## Build ##
###########
find_package(OpenCV REQUIRED)
find_package(Qt5 REQUIRED COMPONENTS Widgets )
set(CMAKE_AUTOMOC ON)
set(CMAKE_AUTOUIC ON)
set(CMAKE_INCLUDE_CURRENT_DIR ON)
set(SOURCES
src/include/qnode.hpp
src/main/main.cpp
src/main/mainwindow.cpp
src/main/qnode.cpp
src/ui/mainwindow.hpp
src/ui/mainwindow.ui
)
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
include/Air_Ground_CEC
${catkin_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
)
add_executable(Air_Ground_CEC ${SOURCES})
target_link_libraries(Air_Ground_CEC
Qt5::Widgets
${catkin_LIBRARIES}
${OpenCV_LIBRARIES}
)
## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/Air_Ground_CEC.cpp
# )
## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
# add_executable(${PROJECT_NAME}_node src/Air_Ground_CEC_node.cpp)
## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Specify libraries to link a library or executable target against
# target_link_libraries(${PROJECT_NAME}_node
# ${catkin_LIBRARIES}
# )
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# catkin_install_python(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
# install(TARGETS ${PROJECT_NAME}_node
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark libraries for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
# install(TARGETS ${PROJECT_NAME}
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_Air_Ground_CEC.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)

@ -1,3 +0,0 @@
# Air-ground-CEC
test

Binary file not shown.

@ -1,73 +0,0 @@
<?xml version="1.0"?>
<package format="2">
<name>Air_Ground_CEC</name>
<version>0.1.0</version>
<description>The Air_Ground_CEC package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="jackyma@todo.todo">jackyma</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>Apache 2.0</license>
<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/Air_Ground_CEC</url> -->
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_export_depend>roscpp</build_export_depend>
<exec_depend>roscpp</exec_depend>
<build_depend>opencv2</build_depend>
<build_export_depend>opencv2</build_export_depend>
<exec_depend>opencv2</exec_depend>
<build_depend>message_generation</build_depend>
<build_export_depend>message_generation</build_export_depend>
<exec_depend>message_runtime</exec_depend>
<build_depend>std_msgs sensor_msgs cv_bridge image_transport</build_depend>
<build_export_depend>std_msgs sensor_msgs cv_bridge image_transport</build_export_depend>
<exec_depend>std_msgs sensor_msgs cv_bridge image_transport</exec_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>

@ -1,146 +0,0 @@
#include"Djitellowhite.h"
#include<iostream>
#include<opencv2/opencv.hpp>
#include<stdio.h>
#include<sys/socket.h>
#include<string.h>
#include<arpa/inet.h>
#include<sys/types.h>
using namespace cv;
using namespace std;
Tello::Tello(const char* IP) {
this->stream_on=false;
this->host = inet_addr(IP);
cout << "create successfully!" << endl;
}
Tello::~Tello() {}
void Tello::set_conf(int socket){
this->sock = socket;
}
void Tello::get_connect(sockaddr_in serveraddr) {
char tmp[10] = {"command"};
send_message(tmp,serveraddr,0);// 0 -> timeout
cout << "connect successfully!" <<endl;
}
unsigned long Tello::gethost(){
return this->host;
}
void Tello::takeoff(sockaddr_in serveraddr) {
char tmp[10] = {"takeoff"};
send_message(tmp,serveraddr,0);// 0 -> timeout
cout << "takeoff successfully!" <<endl;
}
void Tello::land(sockaddr_in serveraddr) {
char tmp[10] = {"land"};
send_message(tmp,serveraddr,0);// 0 -> timeout
cout << "land successfully!" <<endl;
}
bool Tello::send_message(char* msg,sockaddr_in server_addr,int timeout){
char buffer[BUFFER_SIZE];
memset(buffer,0,sizeof(buffer));
strcpy(buffer,msg);
//cout << buffer;
sendto(this->sock,buffer,strlen(buffer),0,(struct sockaddr *)&server_addr, sizeof(server_addr));
return true;
}
void* Tello::udp_response_receiver(void* arg){
//int m_SockServer; //创建socket对象
//sockaddr_in serveraddr; //创建sockaddr_in对象储存自身信息(当有多个端口,可以多个绑定)
//sockaddr_in serveraddrfrom;
//serveraddr.sin_family = AF_INET; //设置服务器地址家族
//serveraddr.sin_port = htons(8889); //设置服务器端口号
//serveraddr.sin_addr.s_addr = inet_addr("0.0.0.0");
//m_SockServer = socket(AF_INET, SOCK_DGRAM, 0); //创建一个临时变量并赋值给m_SockServer
//int i = bind(m_SockServer, (sockaddr*)&serveraddr, sizeof(serveraddr)); //把名字和套接字绑定
//std::cout << "bind:" << i << std::endl;
int socket = *(int *)arg;
cout << "receive start" << endl;
while(1){
char buffer[20];
int iret;
memset(buffer,0,sizeof(buffer));
iret = recv(socket, buffer,20,MSG_WAITALL);
if(iret > 0 && iret <10){
printf("Message from tello: %s\n", buffer);
}
}
}
void Tello::forward(sockaddr_in serveraddr){
char tmp[15] = {"forward 20"};
send_message(tmp,serveraddr,0);// 0 -> timeout
cout << "forward successfully!" <<endl;
}
void Tello::back(sockaddr_in serveraddr){
char tmp[15] = {"back 20"};
send_message(tmp,serveraddr,0);// 0 -> timeout
cout << "back successfully!" <<endl;
}
void Tello::left(sockaddr_in serveraddr){
char tmp[15] = {"left 20"};
send_message(tmp,serveraddr,0);// 0 -> timeout
cout << "left successfully!" <<endl;
}
void Tello::right(sockaddr_in serveraddr){
char tmp[15] = {"right 20"};
send_message(tmp,serveraddr,0);// 0 -> timeout
cout << "right successfully!" <<endl;
}
void Tello::up(sockaddr_in serveraddr){
char tmp[15] = {"up 20"};
send_message(tmp,serveraddr,0);// 0 -> timeout
cout << "up successfully!" <<endl;
}
void Tello::down(sockaddr_in serveraddr){
char tmp[15] = {"down 20"};
send_message(tmp,serveraddr,0);// 0 -> timeout
cout << "down successfully!" <<endl;
}
void Tello::cw(sockaddr_in serveraddr){
char tmp[15] = {"cw 20"};
send_message(tmp,serveraddr,0);// 0 -> timeout
cout << "cw successfully!" <<endl;
}
void Tello::ccw(sockaddr_in serveraddr){
char tmp[15] = {"ccw 20"};
send_message(tmp,serveraddr,0);// 0 -> timeout
cout << "ccw successfully!" <<endl;
}
void Tello::get_video(sockaddr_in serveraddr){
char tmp[15] = {"streamon"};
send_message(tmp,serveraddr,0);
cout << "stream_on successfully!" <<endl;
this->stream_on = true;
cout << "vid";
VideoCapture cap("udp://@0.0.0.0:11111");
cout << "cap";
if(!cap.isOpened()){
cout << "fuck off";
return;
}
Mat frame;
cout << "continue!";
while(1){
cap>>frame;
if(frame.empty())
break;
imshow("video",frame);
waitKey(20);
}
cap.release();
}

@ -1,80 +0,0 @@
#ifndef _DJITELLOWHITE_H
#define _DJITELLOWHITE_H
#include<iostream>
#include<sys/socket.h>
#include<arpa/inet.h>
#include<pthread.h>
#include<cstring>
#include<unistd.h>
/*Library for interacting with DJI Ryze Tello drones.*/
//coding = utf - 8
/* """C++ wrapper to interact with the Ryze Tello drone using the official Tello api.
Tello API documentation:
[1.3](https://dl-cdn.ryzerobotics.com/downloads/tello/20180910/Tello%20SDK%20Documentation%20EN_1.3.pdf)
*/
#define RESPONSE_TIMEOUT 7 //in seconds
#define TAKEOFF_TIMEOUT 20 //in seconds
#define FRAME_GRAB_TIMEOUT 3
#define TIME_BTW_COMMANDS 0.1 //in seconds
#define TIME_BTW_RC_CONTROL_COMMANDS 0.001 //in seconds
#define RETRY_COUNT 3 //number of retries after a failed command
//Video stream, server socket
#define VS_UDP_IP "0.0.0.0"
#define VS_UDP_PORT 11111
#define CONTROL_UDP_PORT 8889
#define STATE_UDP_PORT 8890
#define BUFFER_SIZE 1024
//Constants for video settings
#define BITRATE_AUTO 0
#define BITRATE_1MBPS 1
#define BITRATE_2MBPS 2
#define BITRATE_3MBPS 3
#define BITRATE_4MBPS 4
#define BITRATE_5MBPS 5
#define RESOLUTION_480P "low"
#define RESOLUTION_720P "high"
#define FPS_5 "low"
#define FPS_15 "middle"
#define FPS_30 "high"
#define CAMERA_FORWARD 0
#define CAMERA_DOWNWARD 1
//日志模块暂时不写
class Tello {
private:
int sock;
bool stream_on;
unsigned long host;
public:
Tello(const char* IP);
~Tello();
void set_conf(int socket);
unsigned long gethost();
void get_connect(sockaddr_in serveraddr);
void takeoff(sockaddr_in serveraddr);
void land(sockaddr_in serveraddr);
void forward(sockaddr_in serveraddr);
void back(sockaddr_in serveraddr);
void left(sockaddr_in serveraddr);
void right(sockaddr_in serveraddr);
void up(sockaddr_in serveraddr);
void down(sockaddr_in serveraddr);
void cw(sockaddr_in serveraddr);
void ccw(sockaddr_in serveraddr);
bool send_message(char* msg,sockaddr_in server_addr,int timeout = RESPONSE_TIMEOUT);
static void *udp_response_receiver(void* arg);
void get_video(sockaddr_in serveraddr);
};
#endif

Binary file not shown.

@ -1,6 +0,0 @@
#ifndef _HARDWARELISTENER_H
#define _HARDWARELISTENER_H
#include "Djitellowhite.h"
int listenkeyboard(Tello T,sockaddr_in serveraddr);
int scanKeyboard();
#endif

@ -1,45 +0,0 @@
#include"Djitellowhite.h"
#include"Hardwarelistener.h"
#include<iostream>
using namespace std;
int main(void){
Tello T("192.168.10.1");
int socket_fd, err;
if((socket_fd = socket(PF_INET,SOCK_DGRAM,IPPROTO_UDP))==-1)
{
cout << "initialized error" << endl;
cout << 0;
return -1;
}
//cout << 1 << socket_fd;
T.set_conf(socket_fd);
pthread_t thread_receive;
err = pthread_create(&thread_receive,nullptr,T.udp_response_receiver,&socket_fd);
sleep(3);
struct sockaddr_in serveraddr;
memset(&serveraddr,0,sizeof(serveraddr));
serveraddr.sin_family=AF_INET;
serveraddr.sin_addr.s_addr=T.gethost();
serveraddr.sin_port=htons(CONTROL_UDP_PORT);
if(err!=0)
{
cout << err << " " << "can't create thread";
}
T.get_connect(serveraddr);
//sleep(1);
//T.takeoff(serveraddr);
T.get_video(serveraddr);
sleep(5);
//T.land(serveraddr);
pthread_join(thread_receive,NULL);
listenkeyboard(T,serveraddr);
return 0;
}

@ -1,57 +0,0 @@
#include <termio.h>
#include <stdio.h>
#include "Hardwarelistener.h"
#include <iostream>
using namespace std;
int scanKeyboard()
{
int in;
struct termios new_settings;
struct termios stored_settings;
//设置终端参数
tcgetattr(0,&stored_settings);
new_settings = stored_settings;
new_settings.c_lflag &= (~ICANON);
new_settings.c_cc[VTIME] = 0;
tcgetattr(0,&stored_settings);
new_settings.c_cc[VMIN] = 1;
tcsetattr(0,TCSANOW,&new_settings);
in = getchar();
tcsetattr(0,TCSANOW,&stored_settings);
return in;
}
//测试函数
int listenkeyboard(Tello T, sockaddr_in serveraddr){
while(1){
switch(scanKeyboard())
{
case (int)'w':
cout << "forward"<< endl;
T.forward(serveraddr);
break;
case (int)'s':
cout << "back" << endl;
T.back(serveraddr);
break;
case (int)'a':
cout << "left" <<endl;
T.left(serveraddr);
break;
case (int)'d':
cout << "right"<<endl;
T.right(serveraddr);
break;
}
}
return 0;
// while(1){
// printf("%d\n",scanKeyboard());
// }
}

@ -1,21 +0,0 @@
obj = Djitellowhite.o keyboard.cpp Triplet.cpp
CXXFLAGS += -c -Wall $(shell pkg-config --cflags opencv4)
LDFLAGS += $(shell pkg-config --libs --static opencv4)
test : $(obj)
$(CXX) -o test $(obj) $(LDFLAGS)
Djitellowhite.o : Djitellowhite.h
$(CXX) -c Djitellowhite.cpp $(CXXFLAGS)
keyboard.o : Hardwarelistener.h
$(CXX) -c keyboard.cpp $(CXXFLAGS)
Triplet : Djitellowhite.h Hardwarelistener.h
$(CXX) -c Triplet.cpp -lpthread $(CXXFLAGS)
.PHONY : clean
clean :
rm test $(obj)

@ -1,58 +0,0 @@
#include <stdio.h>
#include <stdlib.h>
#include <unistd.h>
#include <errno.h>
#include <sys/types.h>
#include <sys/socket.h>
#include <netinet/in.h>
#include <string.h>
#define PORT 8890
void udp_server(int sockfd)
{
socklen_t len;
char buf[1024] = {0};
struct sockaddr_in server_addr;
int n;
int opt = 1;
len = sizeof(server_addr);
memset(&buf, 0, sizeof(buf));
server_addr.sin_family = AF_INET;
server_addr.sin_addr.s_addr = htonl(INADDR_ANY);
server_addr.sin_port = htons(PORT);
setsockopt(sockfd, SOL_SOCKET, SO_REUSEADDR, &opt, sizeof(opt)); //当服务器非正常断开的时候重启服务器不会进入TIME_WAIT状态
if (bind(sockfd, (struct sockaddr *)&server_addr, sizeof(server_addr)) < 0) {
printf("can not bind\n");
exit(1);
}
while (1) {
printf("========wait for client's request========\n");
n = recvfrom(sockfd, buf, sizeof(buf), 0, (struct sockaddr *)&server_addr, &len);
buf[n] = '\0';
printf("receive client's data: %s\n", buf);
sendto(sockfd, buf, n, 0, (struct sockaddr *)&server_addr, len);
printf("send data to client: %s\n", buf);
}
close(sockfd);
}
int main(int argc, char **argv)
{
int sockfd;
if ((sockfd = socket(PF_INET, SOCK_DGRAM, 0)) < 0) {
printf("create socket false\n");
exit(1);
}
udp_server(sockfd);
exit(0);
}

Binary file not shown.

@ -1,92 +0,0 @@
#include "../ui/mainwindow.hpp"
MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
QMainWindow(parent), qnode(argc, argv),
ui(new Ui::MainWindow)
{
qnode.init();
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);
}
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()));
//
//QObject::connect(&qnode, SIGNAL(loggingCamera()), this, SLOT(slot_updateCamera()));
}
void MainWindow::importFrame()
{
capture >> frame;
cvtColor(frame, frame, CV_BGR2RGB);
QImage srcQImage = QImage((uchar*)(frame.data), frame.cols, frame.rows, QImage::Format_RGB888);
ui->StreamReceive->setPixmap(QPixmap::fromImage(srcQImage));
ui->StreamReceive->resize(srcQImage.size());
ui->StreamReceive->show();
}
void MainWindow::on_PLAY_clicked()
{
capture.open("udp://@0.0.0.0:11111");
timer->start(30);
}
/*
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();
}
void MainWindow::slot_updateCamera()
{
slot_dispalyCamera(qnode.image);
}
*/

@ -1,43 +0,0 @@
#ifndef MAINWINDOW_H
#define MAINWINDOW_H
#include <QMainWindow>
#include <QImage>
#include <QMutex>
#include <QTimer>
#include "ui_mainwindow.h"
#include "../include/qnode.hpp"
using namespace cv;
namespace Ui {
class MainWindow;
}
class MainWindow : public QMainWindow
{
Q_OBJECT
public:
explicit MainWindow(int argc, char **argv, QWidget *parent = 0);
~MainWindow();
public slots:
void slot_keyboard_control();
void importFrame();//read video
void on_PLAY_clicked();//start video
//void slot_updateCamera();
//void slot_dispalyCamera(const QImage& image);
private:
Ui::MainWindow *ui;
void connections();
QNode qnode;
//QImage qimage;
//mutable QMutex qimage_mutex;
VideoCapture capture;
QTimer *timer;
Mat frame;
bool isCamerea = 0;
};
#endif // MAINWINDOW_H
Loading…
Cancel
Save