diff --git a/CMakeLists.txt b/CMakeLists.txt index 33bf6f1..e0ea6a7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -10,17 +10,36 @@ set(CMAKE_CXX_STANDARD 17) set(CMAKE_CXX_STANDARD_REQUIRED ON) find_package(QT NAMES Qt6 Qt5 REQUIRED COMPONENTS Widgets) -find_package(Qt${QT_VERSION_MAJOR} REQUIRED COMPONENTS Widgets) -find_package(Qt${QT_VERSION_MAJOR} REQUIRED COMPONENTS Charts) -find_package(Qt${QT_VERSION_MAJOR} REQUIRED COMPONENTS Core Network) -find_package(Qt${QT_VERSION_MAJOR} REQUIRED COMPONENTS Sql) -find_package(Qt${QT_VERSION_MAJOR} REQUIRED COMPONENTS Gui) -find_package(Qt${QT_VERSION_MAJOR} REQUIRED COMPONENTS WebEngineWidgets) -find_package(Qt5 REQUIRED COMPONENTS Widgets Quick QuickControls2 Positioning Location) +find_package(Qt${QT_VERSION_MAJOR} REQUIRED COMPONENTS + Widgets + Charts + Core + Network + Sql + Gui + WebEngineWidgets + Positioning +) +find_package(Qt5 REQUIRED COMPONENTS Quick QuickControls2 Location) +find_package(X11 REQUIRED) + +# === GStreamer === +find_package(PkgConfig REQUIRED) +pkg_check_modules(GST REQUIRED + gstreamer-1.0 + gstreamer-video-1.0 + gstreamer-app-1.0 +) + +# === Python конфигурация === +find_package(Python3 REQUIRED COMPONENTS Interpreter Development) -find_package(Qt5 REQUIRED COMPONENTS Core Widgets Location) +# Добавляем пути к заголовочным файлам GStreamer +include_directories(${GST_INCLUDE_DIRS}) +include_directories(${Python3_INCLUDE_DIRS}) +# Пути к вашим собственным заголовочным файлам include_directories("${PROJECT_SOURCE_DIR}/compass") include_directories("${PROJECT_SOURCE_DIR}/remote_control") include_directories("${PROJECT_SOURCE_DIR}/uv") @@ -32,15 +51,9 @@ include_directories("${PROJECT_SOURCE_DIR}/missions") include_directories("${PROJECT_SOURCE_DIR}/tabs") include_directories("${PROJECT_SOURCE_DIR}/mods") include_directories("${PROJECT_SOURCE_DIR}/Diagnostic_bord_UI/Diagnostic_bord") +include_directories("${PROJECT_SOURCE_DIR}/videowidget") include_directories("${PROJECT_SOURCE_DIR}") -include_directories(${Python3_INCLUDE_DIRS}) - - -find_package(Python3 REQUIRED COMPONENTS Interpreter Development) -find_package(Qt5 REQUIRED COMPONENTS Widgets Quick QuickWidgets Positioning Location) - -include_directories(${Python3_INCLUDE_DIRS}) set(PROJECT_SOURCES main.cpp @@ -89,26 +102,21 @@ set(PROJECT_SOURCES Diagnostic_bord_UI/Diagnostic_bord/diagnostic_board.cpp Diagnostic_bord_UI/Diagnostic_bord/diagnostic_board.h Diagnostic_bord_UI/Diagnostic_bord/diagnostic_board.ui + videowidget/videowidget.cpp + videowidget/videowidget.h + videowidget/videowidget.ui ) - - if(${QT_VERSION_MAJOR} GREATER_EQUAL 6) qt_add_executable(UMAS_GUI MANUAL_FINALIZATION ${PROJECT_SOURCES} ) -# Define target properties for Android with Qt 6 as: -# set_property(TARGET UMAS_GUI APPEND PROPERTY QT_ANDROID_PACKAGE_SOURCE_DIR -# ${CMAKE_CURRENT_SOURCE_DIR}/android) -# For more information, see https://doc.qt.io/qt-6/qt-add-executable.html#target-creation else() if(ANDROID) add_library(UMAS_GUI SHARED ${PROJECT_SOURCES} ) -# Define properties for Android with Qt 5 after find_package() calls as: -# set(ANDROID_PACKAGE_SOURCE_DIR "${CMAKE_CURRENT_SOURCE_DIR}/android") else() add_executable(UMAS_GUI ${PROJECT_SOURCES} @@ -116,6 +124,7 @@ else() endif() endif() +# Подключаем все библиотеки в одном месте target_link_libraries(UMAS_GUI PRIVATE sfml-graphics sfml-window sfml-system Qt${QT_VERSION_MAJOR}::Widgets @@ -126,12 +135,10 @@ target_link_libraries(UMAS_GUI PRIVATE Qt${QT_VERSION_MAJOR}::WebEngineWidgets Qt${QT_VERSION_MAJOR}::Positioning Python3::Python + ${GST_LIBRARIES} # <-- КЛЮЧЕВОЕ ИЗМЕНЕНИЕ: подключаем GStreamer и все его зависимости + ${X11_LIBRARIES} ) - -target_link_libraries(UMAS_GUI PRIVATE Qt5::Core Qt5::Widgets Qt5::Location) - - set_target_properties(UMAS_GUI PROPERTIES MACOSX_BUNDLE_GUI_IDENTIFIER my.example.com MACOSX_BUNDLE_BUNDLE_VERSION ${PROJECT_VERSION} diff --git a/UMAS_GUI-develop/.gitignore b/UMAS_GUI-develop/.gitignore deleted file mode 100755 index 4a0b530..0000000 --- a/UMAS_GUI-develop/.gitignore +++ /dev/null @@ -1,74 +0,0 @@ -# This file is used to ignore files which are generated -# ---------------------------------------------------------------------------- - -*~ -*.autosave -*.a -*.core -*.moc -*.o -*.obj -*.orig -*.rej -*.so -*.so.* -*_pch.h.cpp -*_resource.rc -*.qm -.#* -*.*# -core -!core/ -tags -.DS_Store -.directory -*.debug -Makefile* -*.prl -*.app -moc_*.cpp -ui_*.h -qrc_*.cpp -Thumbs.db -*.res -*.rc -/.qmake.cache -/.qmake.stash - -# qtcreator generated files -*.pro.user* -CMakeLists.txt.user* - -# xemacs temporary files -*.flc - -# Vim temporary files -.*.swp - -# Visual Studio generated files -*.ib_pdb_index -*.idb -*.ilk -*.pdb -*.sln -*.suo -*.vcproj -*vcproj.*.*.user -*.ncb -*.sdf -*.opensdf -*.vcxproj -*vcxproj.* - -# MinGW generated files -*.Debug -*.Release - -# Python byte code -*.pyc - -# Binaries -# -------- -*.dll -*.exe - diff --git a/UMAS_GUI-develop/.vscode/launch.json b/UMAS_GUI-develop/.vscode/launch.json deleted file mode 100755 index 97b986a..0000000 --- a/UMAS_GUI-develop/.vscode/launch.json +++ /dev/null @@ -1,10 +0,0 @@ -{ - // Use IntelliSense to learn about possible attributes. - // Hover to view descriptions of existing attributes. - // For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387 - "version": "0.2.0", - "configurations": [ - - - ] -} \ No newline at end of file diff --git a/UMAS_GUI-develop/.vscode/settings.json b/UMAS_GUI-develop/.vscode/settings.json deleted file mode 100755 index 25d4a7b..0000000 --- a/UMAS_GUI-develop/.vscode/settings.json +++ /dev/null @@ -1,15 +0,0 @@ -{ -"cmake.configureArgs": [ - "-DCMAKE_PREFIX_PATH=/home/shakuevda/Qt/6.4.2/gcc_64/lib/cmake" // my - // "-DCMAKE_PREFIX_PATH=/home/hydro/Qt/5.15.2/gcc_64/lib/cmake" // laptop - // "-DCMAKE_PREFIX_PATH=/home/hydronautics/Qt/5.15.2/gcc_64/lib/cmake" // station - -], -"files.associations": { - "qabstractseries": "cpp", - "qabstractaxis": "cpp", - "qpainter": "cpp", - "qchartview": "cpp", - "qtmath": "cpp" -} -} \ No newline at end of file diff --git a/UMAS_GUI-develop/CMakeLists.txt b/UMAS_GUI-develop/CMakeLists.txt deleted file mode 100755 index 338e136..0000000 --- a/UMAS_GUI-develop/CMakeLists.txt +++ /dev/null @@ -1,134 +0,0 @@ -cmake_minimum_required(VERSION 3.5) - -project(UMAS_GUI VERSION 0.1 LANGUAGES CXX) - -set(CMAKE_AUTOUIC ON) -set(CMAKE_AUTOMOC ON) -set(CMAKE_AUTORCC ON) - -set(CMAKE_CXX_STANDARD 17) -set(CMAKE_CXX_STANDARD_REQUIRED ON) - -find_package(QT NAMES Qt6 Qt5 REQUIRED COMPONENTS Widgets) -find_package(Qt${QT_VERSION_MAJOR} REQUIRED COMPONENTS Widgets Charts Core Network Sql Gui) - -# === GStreamer и GLib === -find_package(PkgConfig REQUIRED) - -pkg_check_modules(GSTREAMER REQUIRED gstreamer-1.0>=1.0) -pkg_check_modules(GSTREAMER_VIDEO REQUIRED gstreamer-video-1.0>=1.0) -pkg_check_modules(GLIB REQUIRED glib-2.0>=2.0) - -include_directories( - ${GSTREAMER_INCLUDE_DIRS} - ${GSTREAMER_VIDEO_INCLUDE_DIRS} - ${GLIB_INCLUDE_DIRS} -) - -link_directories( - ${GSTREAMER_LIBRARY_DIRS} - ${GSTREAMER_VIDEO_LIBRARY_DIRS} - ${GLIB_LIBRARY_DIRS} -) -# ============================ - -include_directories( - "${PROJECT_SOURCE_DIR}/compass" - "${PROJECT_SOURCE_DIR}/remote_control" - "${PROJECT_SOURCE_DIR}/uv" - "${PROJECT_SOURCE_DIR}/interface" - "${PROJECT_SOURCE_DIR}/map" - "${PROJECT_SOURCE_DIR}/communication" - "${PROJECT_SOURCE_DIR}/ui_utils" - "${PROJECT_SOURCE_DIR}" -) - -set(PROJECT_SOURCES - main.cpp - mainwindow.cpp - mainwindow.h - mainwindow.ui - remote_control/remote_control.h - remote_control/remote_control.cpp - compass/compass.cpp - compass/compass.h - compass/compass.ui - uv/uv_state.cpp - uv/uv_state.h - interface/i_control_data.cpp - interface/i_control_data.h - interface/i_basic_data.cpp - interface/i_basic_data.h - interface/i_user_interface_data.cpp - interface/i_user_interface_data.h - interface/i_server_data.h - interface/i_server_data.cpp - communication/pc_protocol.h - communication/udp_protocol.h - ui_utils/setup_imu.h - ui_utils/setup_imu.cpp - ui_utils/setup_imu.ui - ui_utils/setupimu_start.h - ui_utils/setupimu_start.cpp - ui_utils/setupimu_start.ui - map/map.h - map/map.cpp - map/map.ui - img.qrc - ui_utils/setupimu_check.h - ui_utils/setupimu_check.cpp - ui_utils/setupimu_check.ui - ui_utils/database.h - ui_utils/database.cpp - remote_control/key_board.h - remote_control/key_board.cpp - remote_control/joy_stick.h - remote_control/joy_stick.cpp -) - -if(${QT_VERSION_MAJOR} GREATER_EQUAL 6) - qt_add_executable(UMAS_GUI - MANUAL_FINALIZATION - ${PROJECT_SOURCES} - ) -else() - if(ANDROID) - add_library(UMAS_GUI SHARED - ${PROJECT_SOURCES} - ) - else() - add_executable(UMAS_GUI - ${PROJECT_SOURCES} - ) - endif() -endif() - -target_link_libraries(UMAS_GUI PRIVATE - sfml-graphics sfml-window sfml-system - Qt${QT_VERSION_MAJOR}::Widgets - Qt${QT_VERSION_MAJOR}::Charts - Qt${QT_VERSION_MAJOR}::Network - Qt${QT_VERSION_MAJOR}::Sql - Qt${QT_VERSION_MAJOR}::Gui - ${GSTREAMER_LIBRARIES} - ${GSTREAMER_VIDEO_LIBRARIES} - ${GLIB_LIBRARIES} -) - -set_target_properties(UMAS_GUI PROPERTIES - MACOSX_BUNDLE_GUI_IDENTIFIER my.example.com - MACOSX_BUNDLE_BUNDLE_VERSION ${PROJECT_VERSION} - MACOSX_BUNDLE_SHORT_VERSION_STRING ${PROJECT_VERSION_MAJOR}.${PROJECT_VERSION_MINOR} - MACOSX_BUNDLE TRUE - WIN32_EXECUTABLE TRUE -) - -install(TARGETS UMAS_GUI - BUNDLE DESTINATION . - LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} - RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} -) - -if(QT_VERSION_MAJOR EQUAL 6) - qt_finalize_executable(UMAS_GUI) -endif() diff --git a/UMAS_GUI-develop/communication/pc_protocol.h b/UMAS_GUI-develop/communication/pc_protocol.h deleted file mode 100755 index 4e8b44d..0000000 --- a/UMAS_GUI-develop/communication/pc_protocol.h +++ /dev/null @@ -1,62 +0,0 @@ -#ifndef PC_PROTOCOL_H -#define PC_PROTOCOL_H - -#include "udp_protocol.h" -#include "uv_state.h" -#include "i_server_data.h" - - -namespace Pult { -class PC_Protocol: public QObject, public MetaUdpProtocol { - Q_OBJECT -public: -explicit PC_Protocol(QHostAddress _receiverIP, int _receiverPort, QHostAddress _senderIP, \ - int _senderPort, int freq, int selectAgent, QObject *parent = 0) -{ - udpProtocol = new UdpProtocol (_receiverIP, _receiverPort, _senderIP, _senderPort, \ - freq, selectAgent, parent); - connect(timer,SIGNAL(timeout()),SLOT(sendData())); - connect(udpProtocol->getReceiveSocket(),SIGNAL(readyRead()),SLOT(receiveData())); - set_ip_receiver(udpProtocol->ip_receiver()); - set_ip_sender (udpProtocol->ip_sender()); - set_port_receiver(udpProtocol->port_receiver()); - set_port_sender (udpProtocol->port_sender()); - nmbAgent = selectAgent; -} - int nmbAgent; -signals: - void dataReceived(); -public slots: - //запуск обмена - void startExchange(){ - timer->start(1000/udpProtocol->getFrequency()); - } - //остановить обмен - void stopExhange(){ - timer->stop(); - } - void sendData(){ - send_data = uv_server.generateFullMessage(nmbAgent); - udpProtocol->send_data = send_data; - udpProtocol->sendData(); - } - - void receiveData(){ - udpProtocol->receiveData(); - rec_data = udpProtocol->rec_data; - uv_server.parseFullMessage(rec_data, nmbAgent); - emit dataReceived(); - } - -public: - ToPult rec_data; - FromPult send_data; - UdpProtocol *udpProtocol; - IServerData uv_server; - - bool bindState(){return udpProtocol->bindState();} -}; -} //namespace Pult - - -#endif // PC_PROTOCOL_H diff --git a/UMAS_GUI-develop/communication/udp_protocol.h b/UMAS_GUI-develop/communication/udp_protocol.h deleted file mode 100755 index 30be5dc..0000000 --- a/UMAS_GUI-develop/communication/udp_protocol.h +++ /dev/null @@ -1,176 +0,0 @@ -#ifndef UDP_PROTOCOL_H -#define UDP_PROTOCOL_H - -#include -#include -#include -#include - - -template - -class UdpProtocol : public QObject { -public: - ReceiveStruct rec_data; //структура для приема данных - SendStruct send_data; //структура для отпарвки данных - explicit UdpProtocol(QHostAddress _receiverIP, int _receiverPort, QHostAddress _senderIP, \ - int _senderPort, int freq, int selectAgent, QObject *parent = 0) : QObject(parent) { - m_ip_sender = _senderIP; //ip ПУ - m_ip_receiver = _receiverIP; //ip ROV_Model - m_port_sender = _senderPort; //порт ПУ - m_port_receiver = _receiverPort; //порт ROV_Model - m_frequency = freq; //частота передачи данных - - qInfo() << "Sender (ROV) ip:" << m_ip_sender << "port:" << m_port_sender; - qInfo() << "Receiver (Pult) ip:" << m_ip_receiver << "port:" << m_port_receiver; - qInfo() << "Frequency:" << m_frequency; - - receiveSocket = new QUdpSocket(); //создаем сокет на прием данных - bindState_ = receiveSocket->bind(m_ip_receiver, m_port_receiver); - qInfo() << "bind receive socket: " << bindState_; - qInfo() << "socket error: " << receiveSocket->errorString(); - //слушаем данные приходящие на ip-адрес ip_receiver, - //на порт port_receiver - sendSocket = new QUdpSocket(); //создаем сокет на передачу данных - qInfo() << "Sends to ip:" << m_ip_sender << "port:" << m_port_sender; - //соединим сигнал таймера с функцией sendData, отсылающей данные - //connect(timer, SIGNAL(timeout()), SLOT(sendData())); - //соединим сигнал сокета receiveSocket о том, что данные готовы для - //чтения с функцией receiveData() - //connect(receiveSocket, SIGNAL(readyRead()),SLOT(receiveData())); - - //send_data.mode=Ruchnoi; - } - - ~UdpProtocol(){ - delete receiveSocket; - delete sendSocket; - } - - float getFrequency(){ - return m_frequency; - } - - QUdpSocket *getReceiveSocket(){ - return receiveSocket; - } - - QHostAddress ip_receiver(){return m_ip_receiver;} - QHostAddress ip_sender(){return m_ip_sender;} - int port_receiver(){return m_port_receiver;} - int port_sender(){return m_port_sender;} - float frequency(){return m_frequency;} - bool bindState(){return bindState_;} - void setCheckState(bool state) {checkState = state;} - -private: - bool bindState_=false; - bool checkState = true; - QUdpSocket *receiveSocket; //UDP-socket для приема данных - QUdpSocket *sendSocket; //UDP-socket для отпарвки данных - QHostAddress m_ip_receiver, m_ip_sender; - int m_port_receiver, m_port_sender; //номера портов приема и передачи - float m_frequency; //частота обмена данными ТНПА с ПУ - //функция вычисления контрольной суммы - uint checksum_i(const void * data, int size){ // function for checksum (uint) - uint c = 0; - for (int i = 0; i < size; ++i) - c += ((const uchar*)data)[i]; - return ~(c + 1); - } - - //проверка верна ли контрольная сумма - bool validate(const ReceiveStruct & data) { - if (!checkState) {return true;} - else { - uint crc= checksum_i(&data, sizeof(data) - 4); - return (data.checksum == crc); - } - } - bool validate(const SendStruct & data) { - if (!checkState) {return true;} - else return (data.checksum == checksum_i(&data, sizeof(data) - 4)); - } - void aboutSend() { - send_data.checksum = checksum_i(&send_data, sizeof(send_data) - 4); - } //функция, которая вычисляет контрольную сумму и записывает - //ее в переменную checksum структуры отправки - -public slots: - void sendData(){ - aboutSend();//считаем контрольную сумму и записываем ее в переменную checksum структуры send_data (типа SendStruct) - //Отсылаем структуру send_data на ip_sender на порт port_sender - sendSocket->writeDatagram((char *)&send_data, sizeof(send_data),m_ip_sender, m_port_sender); - // qDebug() <<"send to ip:" << m_ip_sender << "port:" << m_port_sender; - } //метод для отправки данных, который можно вызывать по сигналу таймера - void receiveData(){ - while(receiveSocket->hasPendingDatagrams()) { - ReceiveStruct rec;// создаем локальную переменную для приема данных до проверки - receiveSocket->pendingDatagramSize(); - receiveSocket->readDatagram((char *)&rec, sizeof(rec)); //считываем данные - - if (!validate(rec)) { - //Функция validate возвращает true - если контрольная сумма верна - //и возвращает false, если это не так - //в этой части функции контрольная сумма не верна - qDebug() << "Checksum validate" << validate(rec); - continue; - //оператор continue выполняет пропуск оставшейся части кода - // тела цикла и переходит к следующей итерации цикла - } - rec_data = rec;//Если контрльная сумма верна, то записываем - //принятые данные в структуру rec_data - } - } //слот для приема данных, который соединим с - //сигналом readyRead() сокета receiveSocket, который создается - //при наличии принятых пакетов - - - - int sendMessage(QByteArray ba){ - return (sendSocket->writeDatagram(ba,m_ip_sender,m_port_sender)); - } - }; - - class MetaUdpProtocol { - public: - MetaUdpProtocol(){ - timer = new QTimer(); - } - virtual QHostAddress ip_receiver(){ - return m_ip_receiver; - } - virtual QHostAddress ip_sender(){ - return m_ip_sender; - } - virtual int port_receiver(){ - return m_port_receiver; - } - virtual int port_sender(){ - return m_port_sender; - } - virtual QString errorReceiverPort(){ - return m_errorReceiverPort; - } - virtual QString errorSenderPort(){ - return m_errorSenderPort; - } - virtual int frequency(){ - return m_frequency; - } - QTimer *timer; //таймер для отправки данных с определенной частотой - virtual void set_ip_receiver (QHostAddress ip) {m_ip_receiver = ip;} - virtual void set_ip_sender (QHostAddress ip) {m_ip_sender = ip; } - virtual void set_port_receiver (int port) {m_port_receiver=port;} - virtual void set_port_sender (int port) {m_port_sender = port;} - private: - QString m_errorReceiverPort, m_errorSenderPort; - QHostAddress m_ip_receiver, m_ip_sender; //receiver - наше приложение - //sender - модель ТНПА - int m_port_receiver, m_port_sender; //номера портов приема и передачи - float m_frequency; //частота обмена данными ТНПА с ПУ - - -}; - -#endif // UDP_PROTOCOL_H diff --git a/UMAS_GUI-develop/compass/compass.cpp b/UMAS_GUI-develop/compass/compass.cpp deleted file mode 100755 index e4f9790..0000000 --- a/UMAS_GUI-develop/compass/compass.cpp +++ /dev/null @@ -1,60 +0,0 @@ -#include "compass.h" - -Compass::Compass(QWidget *parent) : - QFrame(parent) { - setupUi(this); - setYaw(0); - setYawDesirable(0, 0, e_CSMode::MODE_MANUAL); -} - -void Compass::paintEvent(QPaintEvent *e) { - QPainter painter; - painter.begin(this); - QFont font; - painter.setRenderHint(QPainter::Antialiasing, true); // сглаживание - painter.translate(width() / 2, height() / 2); // перенос системы координат - int side = qMin(width(), height()); - painter.scale(side / 170, side / 170); // масштабирование СК - painter.save(); - painter.rotate(yaw); - painter.drawConvexPolygon(arrowCompass, 6); - painter.restore(); - painter.save(); - painter.setPen(Qt::NoPen); - painter.setBrush(Qt::red); - painter.rotate(yawDesirable); - painter.drawConvexPolygon(arrowDesirable, 4); - painter.restore(); - painter.save(); - painter.drawEllipse(-60, -60, 120, 120); - painter.drawEllipse(-70, -70, 140, 140); - for (int i = 0; i < 60; i++) { - if ((i % 5) != 0) - painter.drawLine(0, -55, 0, -60); - else { - painter.drawLine(0, -50, 0, -60); - font.setPointSize(5); - painter.setFont(font); - painter.drawText(-20, -85, 40, 40, Qt::AlignCenter | Qt::AlignTop, QString::number(i * 6)); - } - painter.rotate(6.0); - } - painter.setBrush(Qt::gray); - painter.drawRect(-15, -5, 30, 10); - font.setPointSize(10); - painter.drawText(-20, -10, 40, 20, Qt::AlignCenter, QString::number(yaw)); - painter.restore(); -} - -void Compass::setYaw(double yawNew) { - yaw = yawNew; - update(); -} - -void Compass::setYawDesirable(double yawDesirableNew, double YawFromIMU, e_CSMode mode) { - if (mode == e_CSMode::MODE_AUTOMATED) - yawDesirable = yawDesirableNew + YawFromIMU; - else - yawDesirable = yawDesirableNew; - update(); -} diff --git a/UMAS_GUI-develop/compass/compass.h b/UMAS_GUI-develop/compass/compass.h deleted file mode 100755 index 50a0850..0000000 --- a/UMAS_GUI-develop/compass/compass.h +++ /dev/null @@ -1,53 +0,0 @@ -#ifndef COMPASS_H -#define COMPASS_H - -#include -#include -#include -#include -#include -#include "uv_state.h" - -class Compass : public QFrame, private Ui::Compass{ -Q_OBJECT - -public: - explicit Compass(QWidget *parent = nullptr); - -public slots: - /*! - * \brief setYaw метод установки текущего значения компаса. - * \param yawNew текущее значение компаса. - */ - void setYaw(double yawNew); - /*! - * \brief setYawDesirable метод установки управляющего значения компаса. - * \param yawDesirableNew управляющего значения компаса - * \param YawFromIMU текущее значение курса. - * \param mode ручной или - */ - void setYawDesirable(double yawDesirableNew, double YawFromIMU, e_CSMode mode); - -protected: - void paintEvent(QPaintEvent *e); - -private: - double yaw; - double yawDesirable; - QPoint arrowCompass[6] = { - QPoint(0, 50), - QPoint(0, -50), - QPoint(3, -40), - QPoint(0, -50), - QPoint(-3, -40), - QPoint(0, -50), - }; - QPoint arrowDesirable[4] = { - QPoint(0, -70), - QPoint(5, -85), - QPoint(-5, -85), - QPoint(0, -70) - }; -}; - -#endif // COMPASS_H diff --git a/UMAS_GUI-develop/compass/compass.ui b/UMAS_GUI-develop/compass/compass.ui deleted file mode 100755 index 80e638e..0000000 --- a/UMAS_GUI-develop/compass/compass.ui +++ /dev/null @@ -1,19 +0,0 @@ - - - Compass - - - - 0 - 0 - 600 - 400 - - - - Frame - - - - - diff --git a/UMAS_GUI-develop/img.qrc b/UMAS_GUI-develop/img.qrc deleted file mode 100755 index cedf7f0..0000000 --- a/UMAS_GUI-develop/img.qrc +++ /dev/null @@ -1,5 +0,0 @@ - - - img/setupIMU_for_agent.png - - diff --git a/UMAS_GUI-develop/img/setupIMU_for_agent.png b/UMAS_GUI-develop/img/setupIMU_for_agent.png deleted file mode 100755 index c7a40b7..0000000 Binary files a/UMAS_GUI-develop/img/setupIMU_for_agent.png and /dev/null differ diff --git a/UMAS_GUI-develop/interface/i_basic_data.cpp b/UMAS_GUI-develop/interface/i_basic_data.cpp deleted file mode 100755 index 3f658d9..0000000 --- a/UMAS_GUI-develop/interface/i_basic_data.cpp +++ /dev/null @@ -1,9 +0,0 @@ -#include "i_basic_data.h" - -UVState IBasicData::agent[2]; -int IBasicData::currentAgent; - - -IBasicData::IBasicData(QObject *parent) - : QObject{parent} -{} diff --git a/UMAS_GUI-develop/interface/i_basic_data.h b/UMAS_GUI-develop/interface/i_basic_data.h deleted file mode 100755 index 61d0333..0000000 --- a/UMAS_GUI-develop/interface/i_basic_data.h +++ /dev/null @@ -1,24 +0,0 @@ -#ifndef IBASICDATA_H -#define IBASICDATA_H - -#include -#include - -#include "uv_state.h" - -/*! - * \brief IBasicData базовый информационный класс, имеющий глобальную переменную, - * которая хранит получаемую и передаваемую информацию о всех состояниях аппарата. - */ -class IBasicData : public QObject -{ - Q_OBJECT -public: - explicit IBasicData(QObject *parent = nullptr); - - // Static UV_State variable, which we will be accessing - static UVState agent[2]; - static int currentAgent; -}; - -#endif // IBASICDATA_H diff --git a/UMAS_GUI-develop/interface/i_control_data.cpp b/UMAS_GUI-develop/interface/i_control_data.cpp deleted file mode 100755 index 611cafc..0000000 --- a/UMAS_GUI-develop/interface/i_control_data.cpp +++ /dev/null @@ -1,70 +0,0 @@ -#include "i_control_data.h" - -IControlData::IControlData() : - IBasicData() { - -} - -void IControlData::setControlData(ControlData data) { - agent[getCurrentAgent()].control = data; -} - -void IControlData::setMarch(double march) { - agent[getCurrentAgent()].control.march = march; -} - -void IControlData::setLag(double lag) { - agent[getCurrentAgent()].control.lag = lag; -} - -void IControlData::setDepth(double depth) { - agent[getCurrentAgent()].control.depth = depth; -} - -void IControlData::setRoll(double roll) { - agent[getCurrentAgent()].control.roll = roll; -} - -void IControlData::setPitch(double pitch) { - agent[getCurrentAgent()].control.pitch = pitch; -} - -void IControlData::setYaw(double yaw) { - agent[getCurrentAgent()].control.yaw = yaw; -} - -void IControlData::setGripping(quint8 gripping) { - agent[getCurrentAgent()].control.gripping = gripping; -} - -void IControlData::setRotman(quint8 rotman) { - agent[getCurrentAgent()].control.rotman = rotman; -} - -void IControlData::setOffPower(quint8 offPower) { - agent[getCurrentAgent()].control.offPower = offPower; -} - - - -int IControlData::getCurrentAgent() -{ - return currentAgent; -} - -bool IControlData::getCSMode() -{ - if (agent[getCurrentAgent()].cSMode == e_CSMode::MODE_AUTOMATED) - return true; - else - return false; -} - -DataAH127C IControlData::getImuData() { - return agent[getCurrentAgent()].imuData; -} - -ControlData IControlData::getControlData() -{ - return agent[getCurrentAgent()].control; -} diff --git a/UMAS_GUI-develop/interface/i_control_data.h b/UMAS_GUI-develop/interface/i_control_data.h deleted file mode 100755 index 5a646e5..0000000 --- a/UMAS_GUI-develop/interface/i_control_data.h +++ /dev/null @@ -1,36 +0,0 @@ -#ifndef ICONTROLDATA_H -#define ICONTROLDATA_H - -#include "i_basic_data.h" - -/*! - * \brief IControlData class класс для получения и установки данных связанных - * с управляющими воздействиями и пультом управления. - */ -class IControlData : public IBasicData -{ -public: - IControlData(); - - - - void setControlData(ControlData data); - - void setMarch(double march); - void setLag(double lag); - void setDepth(double depth); - void setRoll(double roll); - void setPitch(double pitch); - void setYaw(double yaw); - - void setGripping(quint8 gripping); - void setRotman(quint8 rotman); - void setOffPower(quint8 offPower); - - int getCurrentAgent(); - bool getCSMode(); - DataAH127C getImuData(); - ControlData getControlData(); -}; - -#endif // ICONTROLDATA_H diff --git a/UMAS_GUI-develop/interface/i_server_data.cpp b/UMAS_GUI-develop/interface/i_server_data.cpp deleted file mode 100755 index a7c6cdb..0000000 --- a/UMAS_GUI-develop/interface/i_server_data.cpp +++ /dev/null @@ -1,40 +0,0 @@ -#include "i_server_data.h" - -IServerData::IServerData() -{ - -} - -FromPult IServerData::generateFullMessage(int nmbAgent) { - FromPult data; - - data.controlData = agent[nmbAgent].control; - data.cSMode = agent[nmbAgent].cSMode; - data.pultUWB = agent[nmbAgent].pultUWB; - data.controlContoursFlags = agent[nmbAgent].controlContoursFlags; - data.modeAUV_selection = agent[nmbAgent].modeAUV_selection; - data.pMode = agent[nmbAgent].pMode; - data.flagAH127C_pult = agent[nmbAgent].flagAH127C_pult; - - - agent[nmbAgent].checksum_msg_gui_send = sizeof(data); - - return data; -} - -void IServerData::parseFullMessage(ToPult message, int nmbAgent) { - agent[nmbAgent].header = message.header; - - agent[nmbAgent].imuData = message.dataAH127C; - agent[nmbAgent].dataPressure = message.dataPressure; - agent[nmbAgent].flagAH127C_bort = message.flagAH127C_bort; - - agent[nmbAgent].auvData.modeReal = message.auvData.modeReal; - agent[nmbAgent].auvData.controlReal = message.auvData.controlReal; - agent[nmbAgent].auvData.modeAUV_Real = message.auvData.modeAUV_Real; - agent[nmbAgent].auvData.signalVMA_real = message.auvData.signalVMA_real; - agent[nmbAgent].auvData.ControlDataReal = message.auvData.ControlDataReal; - - agent[nmbAgent].checksum_msg_agent_send = message.checksum; - agent[nmbAgent].checksum_msg_gui_received = sizeof(message); -} diff --git a/UMAS_GUI-develop/interface/i_server_data.h b/UMAS_GUI-develop/interface/i_server_data.h deleted file mode 100755 index ae65eee..0000000 --- a/UMAS_GUI-develop/interface/i_server_data.h +++ /dev/null @@ -1,31 +0,0 @@ -#ifndef ISERVERDATA_H -#define ISERVERDATA_H - -#include -#include -#include - -#include "i_basic_data.h" - -/*! - * \brief IServerData class класс обработки принимаемых и отправляемых значений. - */ -class IServerData : public IBasicData -{ -public: - IServerData(); - - /*! - * \brief generateFullMessage метод формирование посылки на агента. - * \return сформированная к отправке посылка. - */ - FromPult generateFullMessage(int nmbAgent); - - /*! - * \brief parseFullMessage метод распоковки посылки от агента. - * \param message посылка от агента. - */ - void parseFullMessage(ToPult message, int nmbAgent); -}; - -#endif // ISERVERDATA_H diff --git a/UMAS_GUI-develop/interface/i_user_interface_data.cpp b/UMAS_GUI-develop/interface/i_user_interface_data.cpp deleted file mode 100755 index 5c858b2..0000000 --- a/UMAS_GUI-develop/interface/i_user_interface_data.cpp +++ /dev/null @@ -1,225 +0,0 @@ -#include "i_user_interface_data.h" - -IUserInterfaceData::IUserInterfaceData() : IBasicData() -{ - -} - -// set-функции - -void IUserInterfaceData::setCurrentAgent(int newAgent) -{ - currentAgent = newAgent; -} - -void IUserInterfaceData::setFlagAH127C_pult(FlagAH127C_pult flagAH127C_pult) -{ - agent[getCurrentAgent()].flagAH127C_pult = flagAH127C_pult; -} - -void IUserInterfaceData::setPowerMode(power_Mode mode) { - agent[getCurrentAgent()].pMode = mode; - displayText_toConsole("Включен " + QString::number(static_cast(mode) + 2) + " режим питания"); -} - -void IUserInterfaceData::setControlContoursFlags(e_StabilizationContours contour, bool value) { - switch (contour) { - case e_StabilizationContours::CONTOUR_DEPTH: - agent[getCurrentAgent()].controlContoursFlags.depth = value; - if (value) - emit displayText_toConsole("Контур глубины замкнут"); - else - emit displayText_toConsole("Контур глубины разомкнут"); - break; - - case e_StabilizationContours::CONTOUR_LAG: - agent[getCurrentAgent()].controlContoursFlags.lag = value; - if (value){ - emit displayText_toConsole("Контур лага замкнут"); - }else - emit displayText_toConsole("Контур лага разомкнут"); - break; - - case e_StabilizationContours::CONTOUR_MARCH: - agent[getCurrentAgent()].controlContoursFlags.march = value; - if (value) - emit displayText_toConsole("Контур марша замкнут"); - else - emit displayText_toConsole("Контур марша разомкнут"); - break; - - case e_StabilizationContours::CONTOUR_PITCH: - agent[getCurrentAgent()].controlContoursFlags.pitch = value; - if (value) - emit displayText_toConsole("Контур дифферента замкнут"); - else - emit displayText_toConsole("Контур дифферента разомкнут"); - break; - - case e_StabilizationContours::CONTOUR_ROLL: - agent[getCurrentAgent()].controlContoursFlags.roll = value; - if (value) - emit displayText_toConsole("Контур крена замкнут"); - else - emit displayText_toConsole("Контур крена разомкнут"); - break; - - case e_StabilizationContours::CONTOUR_YAW: - agent[getCurrentAgent()].controlContoursFlags.yaw = value; - if (value) - emit displayText_toConsole("Контур курса замкнут"); - else - emit displayText_toConsole("Контур курса разомкнут"); - break; - } -} - -void IUserInterfaceData::setCSMode(e_CSMode mode) { - agent[getCurrentAgent()].cSMode = mode; - switch (static_cast(mode)) { - case 0: - emit displayText_toConsole("Включен ручной режим"); - break; - case 1: - emit displayText_toConsole("Включен автоматизированный режим"); - break; - case 2: - emit displayText_toConsole("Включен автоматический режим"); - break; - } -} - -void IUserInterfaceData::setModeSelection(bool mode) -{ - agent[getCurrentAgent()].modeAUV_selection = mode; - if (static_cast(mode)) - emit displayText_toConsole("Установлен вывод данных на модель"); - else - emit displayText_toConsole("Установлен вывод данных на агента"); -} - -void IUserInterfaceData::setDataPultUWB(PultUWB pultUWB) -{ - agent[getCurrentAgent()].pultUWB = pultUWB; -} - -void IUserInterfaceData::setMissionControl(mission_Control missionControl) -{ - agent[getCurrentAgent()].missionControl = missionControl; - switch (static_cast(missionControl)) { - case 0: - emit displayText_toConsole("Включен режим ожидания команд в автоматическом режиме"); - break; - case 1: - emit displayText_toConsole("Отправлен запрос на выполнение миссии"); - break; - case 2: - emit displayText_toConsole("Выполнение миссии отменено"); - break; - case 3: - emit displayText_toConsole("Выполнение миссии приостановлено"); - break; - } -} - -void IUserInterfaceData::setID_mission_AUV(quint8 ID_mission_AUV) -{ - agent[getCurrentAgent()].ID_mission_AUV = ID_mission_AUV; - switch (static_cast(ID_mission_AUV)) { - case 0: - emit displayText_toConsole("Миссия завершена, флаг сброшен"); - break; - case 1: - emit displayText_toConsole("Запущена миссия выхода в точку"); - break; - case 2: - emit displayText_toConsole("Запущена миссия следования"); - break; - case 3: - emit displayText_toConsole("Запущена миссия движения по траектории"); - break; - } -} - -// get-функции - -int IUserInterfaceData::getCurrentAgent() -{ - return currentAgent; -} - -int IUserInterfaceData::getChecksumMsgAgentSend() { - return agent[getCurrentAgent()].checksum_msg_agent_send; -} - -int IUserInterfaceData::getChecksumMsgGuiSend() { - return agent[getCurrentAgent()].checksum_msg_gui_send; -} - -int IUserInterfaceData::getChecksumMsgGuiReceived() { - return agent[getCurrentAgent()].checksum_msg_gui_received; -} - -ControlContoursFlags IUserInterfaceData::getControlContoursFlags() -{ - return agent[getCurrentAgent()].controlContoursFlags; -} - -bool IUserInterfaceData::getModeSelection() -{ - return agent[getCurrentAgent()].modeAUV_selection; -} - -FlagAH127C_bort IUserInterfaceData::getFlagAH127C_bort() -{ - return agent[getCurrentAgent()].flagAH127C_bort; -} - -FlagAH127C_pult IUserInterfaceData::getFlagAH127C_pult() -{ - return agent[getCurrentAgent()].flagAH127C_pult; -} - -power_Mode IUserInterfaceData::getPowerMode() -{ - return agent[getCurrentAgent()].pMode; -} - -e_CSMode IUserInterfaceData::getCSMode() -{ - return agent[getCurrentAgent()].cSMode; -} - -ControlData IUserInterfaceData::getControlData() { - return agent[getCurrentAgent()].control; -} - -DataAH127C IUserInterfaceData::getImuData() { - return agent[getCurrentAgent()].imuData; -} - -Header IUserInterfaceData::getHeader() { - return agent[getCurrentAgent()].header; -} - -AUVCurrentData IUserInterfaceData::getAUVCurrentData() { - return agent[getCurrentAgent()].auvData; -} - -DataPressure IUserInterfaceData::getDataPressure() { - return agent[getCurrentAgent()].dataPressure; -} - -DataUWB IUserInterfaceData::getDataUWB() { - return agent[getCurrentAgent()].dataUWB; -} - -DataUWB IUserInterfaceData::getDataUWB(int selectAgent) -{ - return agent[selectAgent].dataUWB; -} - -mission_Status IUserInterfaceData::getMissionStatus() -{ - return agent[getCurrentAgent()].missionStatus; -} diff --git a/UMAS_GUI-develop/interface/i_user_interface_data.h b/UMAS_GUI-develop/interface/i_user_interface_data.h deleted file mode 100755 index 98ffcd0..0000000 --- a/UMAS_GUI-develop/interface/i_user_interface_data.h +++ /dev/null @@ -1,53 +0,0 @@ -#ifndef IUSERINTERFACEDATA_H -#define IUSERINTERFACEDATA_H - -#include "i_basic_data.h" -#include - - -/*! - * \brief IUserInterfaceData class класс для взаимодействия глобальной переменной - * состояний с главной формой. - */ -class IUserInterfaceData : public IBasicData -{ - Q_OBJECT -signals: - void displayText_toConsole(QString str); - -public: - IUserInterfaceData(); - - void setCurrentAgent(int newAgent); - void setFlagAH127C_pult(FlagAH127C_pult flagAH127C_pult); - void setPowerMode(power_Mode mode); - void setControlContoursFlags(e_StabilizationContours contour, bool value); - void setCSMode(e_CSMode mode); - void setModeSelection(bool mode); - void setDataPultUWB(PultUWB pultUWB); - void setMissionControl(mission_Control missionControl); - void setID_mission_AUV(quint8 ID_mission_AUV); - - - int getCurrentAgent(); - int getChecksumMsgAgentSend(); - int getChecksumMsgGuiSend(); - int getChecksumMsgGuiReceived(); - ControlContoursFlags getControlContoursFlags(); - bool getModeSelection(); - FlagAH127C_bort getFlagAH127C_bort(); - FlagAH127C_pult getFlagAH127C_pult(); - power_Mode getPowerMode(); - e_CSMode getCSMode(); - ControlData getControlData(); - DataAH127C getImuData(); - Header getHeader(); - AUVCurrentData getAUVCurrentData(); - DataPressure getDataPressure(); - DataUWB getDataUWB(); - DataUWB getDataUWB(int selectAgent); - mission_Status getMissionStatus(); - -}; - -#endif // IUSERINTERFACEDATA_H diff --git a/UMAS_GUI-develop/main.cpp b/UMAS_GUI-develop/main.cpp deleted file mode 100755 index fd3e533..0000000 --- a/UMAS_GUI-develop/main.cpp +++ /dev/null @@ -1,11 +0,0 @@ -#include "mainwindow.h" - -#include - -int main(int argc, char *argv[]) -{ - QApplication a(argc, argv); - MainWindow w; - w.show(); - return a.exec(); -} diff --git a/UMAS_GUI-develop/mainwindow.cpp b/UMAS_GUI-develop/mainwindow.cpp deleted file mode 100755 index 74c0c78..0000000 --- a/UMAS_GUI-develop/mainwindow.cpp +++ /dev/null @@ -1,1049 +0,0 @@ - #include "mainwindow.h" -#include "./ui_mainwindow.h" - -MainWindow::MainWindow(QWidget *parent) - : QMainWindow(parent) - , ui(new Ui::MainWindow) -{ - ui->setupUi(this); - - setConsole(); - setTimer_updateImpact(20); - setBottom(); - setTab(); - setMap(); - setUpdateUI(); - - pipeline = nullptr; // Инициализируем пайплайн как неактивный - - // Инициализация GStreamer - gst_init(nullptr, nullptr); - - // Получаем "внутренний" идентификатор нашего виджета для видео - videoWindowId = ui->videoWidget->winId(); - - ui->pushButton_Play_Pause->setText("Начать прием"); -} - -// - -void MainWindow::on_pushButton_Play_Pause_clicked() -{ - // Отправка видео с Raspberry Pi - QString command = "ssh -X agent1@192.168.1.11 " - "\"gst-launch-1.0 v4l2src device=/dev/video0 ! " - "image/jpeg,width=100,height=100,framerate=30/1 ! " - "jpegparse ! rtpjpegpay ! udpsink host=192.168.1.6 port=5000\""; - - QProcess *sshProcess = new QProcess(this); - sshProcess->start(command); - - if (!pipeline) { // Если пайплайн не запущен, запускаем его - qDebug() << "Starting pipeline..."; - - // Приём видео на ПК через xvimagesink - const char *pipeline_str = - "udpsrc port=5000 ! application/x-rtp,encoding-name=JPEG,payload=96 ! " - "rtpjpegdepay ! jpegdec ! videoconvert ! xvimagesink name=sink"; - - GError *error = nullptr; - pipeline = gst_parse_launch(pipeline_str, &error); - - if (error) { - qWarning() << "Failed to create pipeline:" << error->message; - g_error_free(error); - return; - } - - // Находим элемент sink и привязываем к нашему QWidget - GstElement *sink = gst_bin_get_by_name(GST_BIN(pipeline), "sink"); - if (!sink) { - qWarning() << "Could not find sink element"; - gst_object_unref(pipeline); - pipeline = nullptr; - return; - } - - if (GST_IS_VIDEO_OVERLAY(sink)) { - gst_video_overlay_set_window_handle(GST_VIDEO_OVERLAY(sink), videoWindowId); - } else { - qWarning() << "Sink is not video overlay capable!"; - } - gst_object_unref(sink); - - // Запускаем пайплайн - gst_element_set_state(pipeline, GST_STATE_PLAYING); - ui->pushButton_Play_Pause->setText("Остановить прием"); - - } else { // Если пайплайн уже работает, останавливаем его - qDebug() << "Stopping pipeline..."; - gst_element_set_state(pipeline, GST_STATE_NULL); - gst_object_unref(pipeline); - pipeline = nullptr; - ui->pushButton_Play_Pause->setText("Начать прием"); - } -} - - -void MainWindow::setConsole() -{ - displayText("Приложение работает"); - displayText("Установите соединение для работы с агентом"); - - connect(&uv_interface, SIGNAL(displayText_toConsole(QString)), - this, SLOT(displayText(QString))); -} - -void MainWindow::displayText(QString str) -{ - QString currentTime = QTime::currentTime().toString("HH:mm:ss"); - qInfo() << currentTime << str; - ui->textEdit_console->append(currentTime + " " + str); -} - -// - -void MainWindow::setTimer_updateImpact(int periodUpdateMsec) -{ - joyStick = new JoyStick(this); - connect(ui->radioButton_useJoyStick, &QRadioButton::clicked, - this, &MainWindow::useJoyStick); - connect(ui->radioButton_useKeyBoard, &QRadioButton::clicked, - this, &MainWindow::useKeyBoard); - QTimer *updateTimer = new QTimer(this); - connect( - updateTimer, SIGNAL(timeout()), - this, SLOT(updateUi_fromControl()) - ); - updateTimer->start(periodUpdateMsec); - displayText("Таймер обновления джойстика запущен"); -} - -void MainWindow::useKeyBoard() -{ - delete joyStick; - - keyBoard = new KeyBoard(this); - displayText("Используемые клавиши(должна быть английская раскладка):\n" - "Клавиша O - вперед по маршу\n" - "Клавиша L - назад по маршу\n" - "Клавиша W - вниз по дифференту\n" - "Клавиша S - вверх по дифференту\n" - "Клавиша A - влево по курсу\n" - "Клавиша D - вправо по курсу\n" - "Клавиша C - вниз по глубине\n" - "Клавиша V - вверх по глубине\n" - "Клавиша Q - влево по крену\n" - "Клавиша E - вправо по крену\n" - "Клавиша K - влево по лагу\n" - "Клавиша ; - вправо по лагу\n"); - -} - -void MainWindow::useJoyStick() -{ - delete keyBoard; - - joyStick = new JoyStick(this); - - connect( - joyStick, SIGNAL(offPower()), - this, SLOT(pushButton_on_powerMode_2()) - ); -} - -void MainWindow::keyPressEvent(QKeyEvent *event) -{ - keyBoard->keyPressEvent(event); - -} - -void MainWindow::keyReleaseEvent(QKeyEvent *event) -{ - keyBoard->keyReleaseEvent(event); -} - -void MainWindow::updateUi_fromControl(){ - - ControlData control = uv_interface.getControlData(); - DataAH127C imuData = uv_interface.getImuData(); - - ui->label_impactDataDepth->setText(QString::number(control.depth, 'f', 2)); - ui->label_impactDataRoll->setText(QString::number(control.roll, 'f', 2)); - ui->label_impactDataPitch->setText(QString::number(control.pitch, 'f', 2)); - ui->label_impactDataYaw->setText(QString::number(control.yaw, 'f', 2)); - ui->label_impactDataMarch->setText(QString::number(control.march, 'f', 2)); - ui->label_impactDataLag->setText(QString::number(control.lag, 'f', 2)); - - ui->compass->setYawDesirable(control.yaw, imuData.yaw, uv_interface.getCSMode()); -} - -// - -void MainWindow::setBottom() -{ - setBottom_mode(); - setBottom_modeAutomated(); - setBottom_modeAutomatic(); - setBottom_powerMode(); - setBottom_connection(); - setBottom_modeSelection(); - setBottom_setupIMU(); - setBottom_setupIMU_check(); - setBottom_selectAgent(); -} - -void MainWindow::setBottom_mode() -{ - ui->pushButton_modeManual->setCheckable(true); - ui->pushButton_modeAutomated->setCheckable(true); - ui->pushButton_modeAutomatic->setCheckable(true); - QButtonGroup *mode = new QButtonGroup(this); - mode->addButton(ui->pushButton_modeManual); - mode->addButton(ui->pushButton_modeAutomated); - mode->addButton(ui->pushButton_modeAutomatic); - mode->setExclusive(true); - - ui->pushButton_modeManual->setChecked(true); - e_CSModeManualToggled(); - - connect( - ui->pushButton_modeManual, SIGNAL(clicked()), - this, SLOT(e_CSModeManualToggled())); - - connect( - ui->pushButton_modeAutomated, SIGNAL(clicked()), - this, SLOT(e_CSModeAutomatedToggled())); - - connect( - ui->pushButton_modeAutomatic, SIGNAL(clicked()), - this, SLOT(e_CSModeAutomaticToggled())); -} - -void MainWindow::e_CSModeManualToggled() { - uv_interface.setCSMode(e_CSMode::MODE_MANUAL); -} - -void MainWindow::e_CSModeAutomatedToggled() { - uv_interface.setCSMode(e_CSMode::MODE_AUTOMATED); -} - -void MainWindow::e_CSModeAutomaticToggled() -{ - uv_interface.setCSMode(e_CSMode::MODE_AUTOMATIC); - ui->stackedWidget_mode->setCurrentIndex(1); -} - -void MainWindow::setBottom_modeAutomatic() -{ - connect( - ui->pushButton_after, SIGNAL(clicked()), - this, SLOT(test_automatic_after())); - - connect( - ui->pushButton_missionControl_modeIdle, &QPushButton::clicked, - this, &MainWindow::slot_pushButton_missionControl_modeIdle); - connect( - ui->pushButton_missionControl_modeStart, &QPushButton::clicked, - this, &MainWindow::slot_pushButton_missionControl_modeStart); - connect( - ui->pushButton_missionControl_modeCancel, &QPushButton::clicked, - this, &MainWindow::slot_pushButton_missionControl_modeCancel); - connect( - ui->pushButton_missionControl_modeStop, &QPushButton::clicked, - this, &MainWindow::slot_pushButton_missionControl_modeStop); - connect( - ui->pushButton_missionControl_modeComplete, &QPushButton::clicked, - this, &MainWindow::slot_pushButton_missionControl_modeComplete); - - connect( - ui->pushButton_missionPlanning_goto, &QPushButton::clicked, - this, &MainWindow::slot_pushButton_missionPlanning_goto); - connect( - ui->pushButton_missionPlanning_goto_update, &QPushButton::clicked, - this, &MainWindow::slot_pushButton_missionPlanning_goto_update); - connect( - this, &MainWindow::signal_pushButton_missionPlanning_goto_updateMap, - ui->map, &Map::updateUi_missionPlanning_goto_goal); - connect( - ui->pushButton_missionPlanning_goto_back, &QPushButton::clicked, - this, &MainWindow::slot_pushButton_missionPlanning_goto_back); - connect( - ui->pushButton_missionPlanning_goto_clean, &QPushButton::clicked, - ui->map, &Map::updateUi_missionPlanning_goto_goal_clear); - connect( - ui->pushButton_missionPlanning_goto_on_trajectory, &QPushButton::clicked, - ui->map, &Map::updateUi_missionPlanning_goto_traj_onoff); - connect( - ui->pushButton_missionPlanning_goto_on_trajectory_clear, &QPushButton::clicked, - ui->map, &Map::updateUi_missionPlanning_goto_traj_clear); - - connect( - ui->pushButton_missionPlanning_go_trajectory_update, &QPushButton::clicked, - this, &MainWindow::slot_pushButton_missionPlanning_go_trajectory_update); - connect( - this, &MainWindow::signal_pushButton_missionPlanning_go_trajectory_updateMap, - ui->map, &Map::updateUi_missionPlanning_goto_goal); - connect( - ui->pushButton_missionPlanning_go_trajectory_back, &QPushButton::clicked, - this, &MainWindow::slot_pushButton_missionPlanning_go_trajectory_back); - connect( - ui->pushButton_missionPlanning_go_trajectory_clean, &QPushButton::clicked, - ui->map, &Map::updateUi_missionPlanning_goto_goal_clear); - - - connect( - ui->pushButton_missionPlanning_following, &QPushButton::clicked, - this, &MainWindow::slot_pushButton_missionPlanning_following); - connect( - ui->pushButton_missionPlanning_go_trajectory, &QPushButton::clicked, - this, &MainWindow::slot_pushButton_missionPlanning_go_trajectory); - -} - -void MainWindow::test_automatic_after() -{ - ui->stackedWidget_mode->setCurrentIndex(0); - ui->stackedWidget_missionPlanning->setCurrentIndex(0); -} - -void MainWindow::slot_pushButton_missionControl_modeIdle() -{ - uv_interface.setMissionControl(mission_Control::MODE_IDLE); -} -void MainWindow::slot_pushButton_missionControl_modeStart() -{ - uv_interface.setMissionControl(mission_Control::MODE_START); -} -void MainWindow::slot_pushButton_missionControl_modeCancel() -{ - uv_interface.setMissionControl(mission_Control::MODE_CANCEL); -} -void MainWindow::slot_pushButton_missionControl_modeStop() -{ - uv_interface.setMissionControl(mission_Control::MODE_STOP); -} -void MainWindow::slot_pushButton_missionControl_modeComplete() -{ - uv_interface.setMissionControl(mission_Control::MODE_COMPLETE); - uv_interface.setID_mission_AUV(0); -} - -void MainWindow::slot_pushButton_missionPlanning_goto() -{ - uv_interface.setID_mission_AUV(1); - ui->stackedWidget_missionPlanning->setCurrentIndex(2); - displayText("Задайте параметры для выхода в точку"); -} - -void MainWindow::slot_pushButton_missionPlanning_goto_update() -{ - double x = ui->doubleSpinBox_missionPlanning_goto_x->value(); - double y = ui->doubleSpinBox_missionPlanning_goto_y->value(); - double r = ui->doubleSpinBox_missionPlanning_goto_r->value(); - - emit signal_pushButton_missionPlanning_goto_updateMap(x,y,r,0); - displayText("Установлена координата для выхода в точку и" - " радиус удержания позиции"); -} - -void MainWindow::slot_pushButton_missionPlanning_goto_back() -{ - ui->stackedWidget_missionPlanning->setCurrentIndex(0); -} - -void MainWindow::slot_pushButton_missionPlanning_go_trajectory_update() -{ - double x1 = ui->doubleSpinBox_missionPlanning_go_trajectory_x_1->value(); - double y1 = ui->doubleSpinBox_missionPlanning_go_trajectory_y_1->value(); - double r1 = ui->doubleSpinBox_missionPlanning_go_trajectory_r_1->value(); - - double x2 = ui->doubleSpinBox_missionPlanning_go_trajectory_x_2->value(); - double y2 = ui->doubleSpinBox_missionPlanning_go_trajectory_y_2->value(); - double r2 = ui->doubleSpinBox_missionPlanning_go_trajectory_r_2->value(); - - double x3 = ui->doubleSpinBox_missionPlanning_go_trajectory_x_3->value(); - double y3 = ui->doubleSpinBox_missionPlanning_go_trajectory_y_3->value(); - double r3 = ui->doubleSpinBox_missionPlanning_go_trajectory_r_3->value(); - - emit signal_pushButton_missionPlanning_go_trajectory_updateMap(x1,y1,r1,0); - emit signal_pushButton_missionPlanning_go_trajectory_updateMap(x2,y2,r2,0); - emit signal_pushButton_missionPlanning_go_trajectory_updateMap(x3,y3,r3,0); - displayText("Установлены координаты для движения по траектории и" - " радиус удержания позиций"); -} - -void MainWindow::slot_pushButton_missionPlanning_go_trajectory_back() -{ - ui->stackedWidget_missionPlanning->setCurrentIndex(0); -} - -void MainWindow::slot_pushButton_missionPlanning_following() -{ - uv_interface.setID_mission_AUV(2); -} - -void MainWindow::slot_pushButton_missionPlanning_go_trajectory() -{ - uv_interface.setID_mission_AUV(3); - ui->stackedWidget_missionPlanning->setCurrentIndex(1); -} - -void MainWindow::updateUi_DataMission() -{ - int missionStatus = static_cast(uv_interface.getMissionStatus()); - switch (missionStatus) { - case 0: - ui->label_missonStatus->setText("ожидание"); - break; - case 1: - ui->label_missonStatus->setText("ошибка инициализации миссии"); - break; - case 2: - ui->label_missonStatus->setText("миссия запущена и выполняется"); - break; - case 3: - ui->label_missonStatus->setText("миссия приостановлена, на паузе"); - break; - case 4: - ui->label_missonStatus->setText("миссия завершена"); - break; - } -} - - - -void MainWindow::setBottom_modeAutomated() -{ - ui->pushButton_modeAutomated_march->setCheckable(true); - ui->pushButton_modeAutomated_lag->setCheckable(true); - ui->pushButton_modeAutomated_psi->setCheckable(true); - ui->pushButton_modeAutomated_tetta->setCheckable(true); - ui->pushButton_modeAutomated_gamma->setCheckable(true); - ui->pushButton_modeAutomated_depth->setCheckable(true); - QButtonGroup *modeAutomated = new QButtonGroup(this); - modeAutomated->addButton(ui->pushButton_modeAutomated_march); - modeAutomated->addButton(ui->pushButton_modeAutomated_lag); - modeAutomated->addButton(ui->pushButton_modeAutomated_psi); - modeAutomated->addButton(ui->pushButton_modeAutomated_tetta); - modeAutomated->addButton(ui->pushButton_modeAutomated_gamma); - modeAutomated->addButton(ui->pushButton_modeAutomated_depth); - modeAutomated->setExclusive(false); - - ui->pushButton_modeAutomated_gamma->setChecked(true); - ui->pushButton_modeAutomated_lag->setChecked(true); - ui->pushButton_modeAutomated_march->setChecked(true); - ui->pushButton_modeAutomated_psi->setChecked(true); - ui->pushButton_modeAutomated_tetta->setChecked(true); - ui->pushButton_modeAutomated_depth->setChecked(true); - - connect( - ui->pushButton_modeAutomated_gamma, SIGNAL(toggled(bool)), - this, SLOT(stabilizeRollToggled(bool))); - - connect( - ui->pushButton_modeAutomated_lag, SIGNAL(toggled(bool)), - this, SLOT(stabilizeLagToggled(bool))); - - connect( - ui->pushButton_modeAutomated_march, SIGNAL(toggled(bool)), - this, SLOT(stabilizeMarchToggled(bool))); - - connect( - ui->pushButton_modeAutomated_psi, SIGNAL(toggled(bool)), - this, SLOT(stabilizeYawToggled(bool))); - - connect( - ui->pushButton_modeAutomated_tetta, SIGNAL(toggled(bool)), - this, SLOT(stabilizePitchToggled(bool))); - - connect( - ui->pushButton_modeAutomated_depth, SIGNAL(toggled(bool)), - this, SLOT(stabilizeDepthToggled(bool))); -} - -void MainWindow::stabilizeRollToggled(bool state) { - uv_interface.setControlContoursFlags(e_StabilizationContours::CONTOUR_ROLL, state); -} - -void MainWindow::stabilizeLagToggled(bool state) { - uv_interface.setControlContoursFlags(e_StabilizationContours::CONTOUR_LAG, state); -} - -void MainWindow::stabilizeMarchToggled(bool state) { - uv_interface.setControlContoursFlags(e_StabilizationContours::CONTOUR_MARCH, state); -} - -void MainWindow::stabilizeYawToggled(bool state) { - uv_interface.setControlContoursFlags(e_StabilizationContours::CONTOUR_YAW, state); -} - -void MainWindow::stabilizePitchToggled(bool state) { - uv_interface.setControlContoursFlags(e_StabilizationContours::CONTOUR_PITCH, state); -} - -void MainWindow::stabilizeDepthToggled(bool state) { - uv_interface.setControlContoursFlags(e_StabilizationContours::CONTOUR_DEPTH, state); -} - -void MainWindow::setBottom_powerMode() -{ - QButtonGroup *powerMode = new QButtonGroup(this); - powerMode->addButton(ui->pushButton_powerMode_2); - powerMode->addButton(ui->pushButton_powerMode_3); - powerMode->addButton(ui->pushButton_powerMode_4); - powerMode->addButton(ui->pushButton_powerMode_5); - - ui->pushButton_powerMode_2->setCheckable(true); - ui->pushButton_powerMode_3->setCheckable(true); - ui->pushButton_powerMode_4->setCheckable(true); - ui->pushButton_powerMode_5->setCheckable(true); - - uv_interface.setPowerMode(power_Mode::MODE_2); - ui->pushButton_powerMode_2->setChecked(true); - - connect( - ui->pushButton_powerMode_2, SIGNAL(clicked()), - this, SLOT(pushButton_on_powerMode_2())); - - connect( - ui->pushButton_powerMode_3, SIGNAL(clicked()), - this, SLOT(pushButton_on_powerMode_3())); - - connect( - ui->pushButton_powerMode_4, SIGNAL(clicked()), - this, SLOT(pushButton_on_powerMode_4())); - - connect( - ui->pushButton_powerMode_5, SIGNAL(clicked()), - this, SLOT(pushButton_on_powerMode_5())); -} - -void MainWindow::pushButton_on_powerMode_2() -{ - uv_interface.setPowerMode(power_Mode::MODE_2); -} - -void MainWindow::pushButton_on_powerMode_3() -{ - uv_interface.setPowerMode(power_Mode::MODE_3); -} - -void MainWindow::pushButton_on_powerMode_4() -{ - uv_interface.setPowerMode(power_Mode::MODE_4); -} - -void MainWindow::pushButton_on_powerMode_5() -{ - before_powerMode = uv_interface.getPowerMode(); - uv_interface.setPowerMode(power_Mode::MODE_5); - - ui->pushButton_powerMode_2->setEnabled(false); - ui->pushButton_powerMode_3->setEnabled(false); - ui->pushButton_powerMode_4->setEnabled(false); - ui->pushButton_powerMode_5->setEnabled(false); - - timer_off_powerMode_5 = new QTimer(this); - connect( - timer_off_powerMode_5, SIGNAL(timeout()), - this, SLOT(off_powerMode_5())); - timer_off_powerMode_5->start(5000); -} - -void MainWindow::off_powerMode_5() -{ - timer_off_powerMode_5->stop(); - uv_interface.setPowerMode(before_powerMode); - - switch (before_powerMode) { - case power_Mode::MODE_2: - ui->pushButton_powerMode_2->setChecked(true); - break; - - case power_Mode::MODE_3: - ui->pushButton_powerMode_3->setChecked(true); - break; - - case power_Mode::MODE_4: - ui->pushButton_powerMode_4->setChecked(true); - break; - } - - ui->pushButton_powerMode_2->setEnabled(true); - ui->pushButton_powerMode_3->setEnabled(true); - ui->pushButton_powerMode_4->setEnabled(true); - ui->pushButton_powerMode_5->setEnabled(true); -} - -void MainWindow::setBottom_connection() -{ - ui->pushButton_breakConnection->setEnabled(false); - - connect( - ui->pushButton_connection, SIGNAL(clicked()), - this, SLOT(setConnection())); - connect( - ui->pushButton_breakConnection, SIGNAL(clicked()), - this, SLOT(breakConnection())); -} - -void MainWindow::setConnection() -{ - ui->pushButton_connection->setEnabled(false); - ui->pushButton_breakConnection->setEnabled(true); - communicationAgent1 = new Pult::PC_Protocol(QHostAddress("192.168.1.111"), 13053, - QHostAddress("192.168.1.11"), 13052, 10, 0); - communicationAgent2 = new Pult::PC_Protocol(QHostAddress("192.168.13.102"), 13057, - QHostAddress("192.168.13.3"), 13058, 10, 1); - -// communicationAgent1 = new Pult::PC_Protocol(QHostAddress("192.168.1.10"), 13055, -// QHostAddress("192.168.1.3"), 13054, 10, 0); -// communicationAgent2 = new Pult::PC_Protocol(QHostAddress("192.168.1.10"), 13053, -// QHostAddress("192.168.1.11"), 13052, 10, 1); - - - communicationAgent1->startExchange(); - communicationAgent2->startExchange(); - - if (communicationAgent1->bindState() || communicationAgent2->bindState()) { - displayText("Соединение установлено"); - - connect(communicationAgent1, SIGNAL(dataReceived()), - this, SLOT(updateUi_fromAgent1())); - connect(communicationAgent2, SIGNAL(dataReceived()), - this, SLOT(updateUi_fromAgent2())); - updateStatePushButton(); - - } else { - ui->pushButton_connection->setEnabled(true); - ui->pushButton_breakConnection->setEnabled(false); - displayText("Попробуйте снова"); - } - - if (communicationAgent1->bindState()){ - ui->pushButton_selectAgent1->setStyleSheet("background-color: green"); - displayText("Соединение c 1 агентом установлено"); - } else { - ui->pushButton_selectAgent1->setStyleSheet("background-color: red"); - displayText("Соединение c 1 агентом не установлено"); - } - if (communicationAgent2->bindState()){ - ui->pushButton_selectAgent2->setStyleSheet("background-color: green"); - displayText("Соединение c 2 агентом установлено"); - } else { - ui->pushButton_selectAgent2->setStyleSheet("background-color: red"); - displayText("Соединение c 2 агентом не установлено"); - } -} - -void MainWindow::updateUi_fromAgent1() { - DataAH127C imuData = uv_interface.getImuData(); - DataUWB dataUWB = uv_interface.getDataUWB(); - - emit updateCompass(imuData.yaw); - emit updateIMU(imuData); - emit updateSetupMsg(); - emit updateMap(dataUWB); - emit updateDataMission(); -} - -void MainWindow::updateUi_fromAgent2() -{ - DataUWB dataUWB_agent2 = uv_interface.getDataUWB(1); - emit updateMapForAgent2(dataUWB_agent2); -} - -void MainWindow::breakConnection() -{ - ui->pushButton_connection->setEnabled(true); - - displayText("Соединение разорвано"); - communicationAgent1->stopExhange(); - - delete communicationAgent1; - - ui->pushButton_breakConnection->setEnabled(false); -} - -// - -void MainWindow::setBottom_modeSelection() -{ - setModeSelection(0); - connect( - ui->comboBox_modeSelection, SIGNAL(activated(int)), - this, SLOT(setModeSelection(int))); -} - -void MainWindow::setModeSelection(int index) -{ - - if (index == 1){ - uv_interface.setModeSelection(0); //агент - } - else{ - uv_interface.setModeSelection(1); //модель - } -} - -void MainWindow::setBottom_setupIMU() -{ - connect( - ui->pushButton_setupIMU, SIGNAL(clicked()), - this, SLOT(getWindow_setupIMU())); -} - -void MainWindow::getWindow_setupIMU() -{ - SetupIMU window_setupIMU; - window_setupIMU.setModal(false); - window_setupIMU.exec(); -} - -// - -void MainWindow::setBottom_setupIMU_check() -{ - connect( - ui->pushButton_setupIMU_check, SIGNAL(clicked()), - this, SLOT(getWindow_setupIMU_check())); -} - -void MainWindow::setBottom_selectAgent() -{ - ui->pushButton_selectAgent1->setCheckable(true); - ui->pushButton_selectAgent2->setCheckable(true); - QButtonGroup *buttonGroup_selectAgent = new QButtonGroup(this); - buttonGroup_selectAgent->addButton(ui->pushButton_selectAgent1); - buttonGroup_selectAgent->addButton(ui->pushButton_selectAgent2); - buttonGroup_selectAgent->setExclusive(true); - - ui->pushButton_selectAgent1->setChecked(true); - - connect(ui->pushButton_selectAgent1, &QAbstractButton::toggled, - this, &MainWindow::pushButton_selectAgent1); - connect(ui->pushButton_selectAgent2, &QAbstractButton::toggled, - this, &MainWindow::pushButton_selectAgent2); - connect(this, &MainWindow::updateStatePushButton, - this, &MainWindow::updateUi_statePushButton); -} - -void MainWindow::pushButton_selectAgent1(bool stateBottom) -{ - if (stateBottom){ - uv_interface.setCurrentAgent(0); - displayText("Установлен ввод и вывод данных с агента 1"); - } - updateStatePushButton(); -} - -void MainWindow::pushButton_selectAgent2(bool stateBottom) -{ - if (stateBottom){ - uv_interface.setCurrentAgent(1); - displayText("Установлен ввод и вывод данных с агента 2"); - } - updateStatePushButton(); -} - -void MainWindow::updateUi_statePushButton() -{ - // вывод данных: модель/агент - if (uv_interface.getModeSelection()) - ui->comboBox_modeSelection->setCurrentIndex(0); - else - ui->comboBox_modeSelection->setCurrentIndex(1); - - // режим питания - switch (uv_interface.getPowerMode()) { - case power_Mode::MODE_2: - ui->pushButton_powerMode_2->setChecked(true); - break; - case power_Mode::MODE_3: - ui->pushButton_powerMode_3->setChecked(true); - break; - case power_Mode::MODE_4: - ui->pushButton_powerMode_4->setChecked(true); - break; - case power_Mode::MODE_5: - ui->pushButton_powerMode_5->setChecked(true); - break; - } - - // - switch (uv_interface.getCSMode()) { - case e_CSMode::MODE_MANUAL: - ui->pushButton_modeManual->setChecked(true); - break; - case e_CSMode::MODE_AUTOMATED: - ui->pushButton_modeAutomated->setChecked(true); - break; - case e_CSMode::MODE_AUTOMATIC: - ui->pushButton_modeAutomatic->setChecked(true); - break; - } - - ControlContoursFlags state_controlContoursFlags = uv_interface.getControlContoursFlags(); - if (state_controlContoursFlags.yaw) - ui->pushButton_modeAutomated_psi->setChecked(true); - else - ui->pushButton_modeAutomated_psi->setChecked(false); - if (state_controlContoursFlags.roll) - ui->pushButton_modeAutomated_gamma->setChecked(true); - else - ui->pushButton_modeAutomated_gamma->setChecked(false); - if (state_controlContoursFlags.pitch) - ui->pushButton_modeAutomated_tetta->setChecked(true); - else - ui->pushButton_modeAutomated_tetta->setChecked(false); - if (state_controlContoursFlags.march) - ui->pushButton_modeAutomated_march->setChecked(true); - else - ui->pushButton_modeAutomated_march->setChecked(false); - if (state_controlContoursFlags.lag) - ui->pushButton_modeAutomated_lag->setChecked(true); - else - ui->pushButton_modeAutomated_lag->setChecked(false); - if (state_controlContoursFlags.depth) - ui->pushButton_modeAutomated_depth->setChecked(true); - else - ui->pushButton_modeAutomated_depth->setChecked(false); - - - - -} - -void MainWindow::getWindow_setupIMU_check() -{ - SetupIMU_check window_setupIMU_check; - window_setupIMU_check.setModal(false); - window_setupIMU_check.exec(); -} - -// - -void MainWindow::setTab() -{ - ui->tabWidget->setTabText(0, "Карта"); - ui->tabWidget->setTabText(1, "БСО"); - ui->tabWidget->setTabText(2, "Контроль сообщений"); - ui->tabWidget->setTabText(3, "Режимы питания"); - ui->tabWidget->setTabText(4, "Видео"); // таб с видео -} - -// - -void MainWindow::setMap() -{ - connect(ui->map, SIGNAL(sendLocationUWB(double*,double*)), - this, SLOT(setLocationUWB(double*,double*))); -} - -void MainWindow::setLocationUWB(double *x, double *y) -{ - PultUWB pultUWB; - - for (int count = 0; count < 2; count++) - { - pultUWB.beacon_x[count] = *x; - pultUWB.beacon_y[count] = *y; - x++; - y++; - } - - uv_interface.setDataPultUWB(pultUWB); -} - -// - -void MainWindow::setUpdateUI() -{ - connect(this, SIGNAL(updateCompass(float)), - this, SLOT(updateUi_Compass(float))); - connect(this, SIGNAL(updateIMU(DataAH127C)), - this, SLOT(updateUi_IMU(DataAH127C))); - connect(this, SIGNAL(updateSetupMsg()), - this, SLOT(updateUi_SetupMsg())); - connect(this, SIGNAL(updateDataMission()), - this, SLOT(updateUi_DataMission())); - - connect(this, SIGNAL(updateMap(DataUWB)), - ui->map,SLOT(updateUi_map(DataUWB))); - connect(this, SIGNAL(updateMapForAgent2(DataUWB)), - ui->map,SLOT(updateUi_map2(DataUWB))); -} - -void MainWindow::updateUi_Compass(float yaw) { - ui->compass->setYaw(yaw); -} - -void MainWindow::updateUi_IMU(DataAH127C imuData){ - ui->label_IMUdata_accel_X->setText(QString::number(imuData.X_accel, 'f', 2)); - ui->label_IMUdata_accel_Y->setText(QString::number(imuData.Y_accel, 'f', 2)); - ui->label_IMUdata_accel_Z->setText(QString::number(imuData.Z_accel, 'f', 2)); - - ui->label_IMUdata_rate_X->setText(QString::number(imuData.X_rate, 'f', 2)); - ui->label_IMUdata_rate_Y->setText(QString::number(imuData.Y_rate, 'f', 2)); - ui->label_IMUdata_rate_Z->setText(QString::number(imuData.Z_rate, 'f', 2)); - - ui->label_IMUdata_magn_X->setText(QString::number(imuData.X_magn, 'f', 2)); - ui->label_IMUdata_magn_Y->setText(QString::number(imuData.Y_magn, 'f', 2)); - ui->label_IMUdata_magn_Z->setText(QString::number(imuData.Z_magn, 'f', 2)); - - ui->label_IMUdata_q0->setText(QString::number(imuData.quat[0], 'f', 2)); - ui->label_IMUdata_q1->setText(QString::number(imuData.quat[1], 'f', 2)); - ui->label_IMUdata_q2->setText(QString::number(imuData.quat[2], 'f', 2)); - ui->label_IMUdata_q3->setText(QString::number(imuData.quat[3], 'f', 2)); - - ui->label_IMUdata_yaw->setText(QString::number(imuData.yaw, 'f', 2)); - ui->label_IMUdata_pitch->setText(QString::number(imuData.pitch, 'f', 2)); - ui->label_IMUdata_roll->setText(QString::number(imuData.roll, 'f', 2)); -} - -void MainWindow::updateUi_SetupMsg() -{ - power_Mode pMode = uv_interface.getPowerMode(); - bool modeSelection = uv_interface.getModeSelection(); - - ControlContoursFlags controlContoursFlags = uv_interface.getControlContoursFlags(); - ControlData control = uv_interface.getControlData(); - AUVCurrentData auvData = uv_interface.getAUVCurrentData(); - FlagAH127C_bort flagAH127C_bort = uv_interface.getFlagAH127C_bort(); - FlagAH127C_pult flagAH127C_pult = uv_interface.getFlagAH127C_pult(); - int checksum_msg_gui_send = uv_interface.getChecksumMsgGuiSend(); - int checksum_msg_agent_send = uv_interface.getChecksumMsgAgentSend(); - int checksum_msg_gui_received = uv_interface.getChecksumMsgGuiReceived(); - -// send - - ui->label_tab_setupMsg_send_powerMode_count->setNum(2+static_cast(pMode)); - - if (modeSelection == 1) - ui->label_tab_setupMsg_send_modeAUV_selection_mode->setText("модель"); - else - ui->label_tab_setupMsg_send_modeAUV_selection_mode->setText("агент"); - - switch (uv_interface.getCSMode()) { - case e_CSMode::MODE_MANUAL: - ui->label_tab_setupMsg_send_cSMode_count->setText("ручной"); - break; - case e_CSMode::MODE_AUTOMATED: - ui->label_tab_setupMsg_send_cSMode_count->setText("автоматизированный"); - break; - case e_CSMode::MODE_AUTOMATIC: - ui->label_tab_setupMsg_send_cSMode_count->setText("автоматический"); - break; - } - - if (controlContoursFlags.yaw) { - ui->label_tab_setupMsg_send_controlContoursFlags_data_flags_yaw->setText("замкнут"); - } else { - ui->label_tab_setupMsg_send_controlContoursFlags_data_flags_yaw->setText("незамкнут"); - } - - if (controlContoursFlags.pitch) { - ui->label_tab_setupMsg_send_controlContoursFlags_data_flags_pitch->setText("замкнут"); - } else { - ui->label_tab_setupMsg_send_controlContoursFlags_data_flags_pitch->setText("незамкнут"); - } - - if (controlContoursFlags.roll) { - ui->label_tab_setupMsg_send_controlContoursFlags_data_flags_roll->setText("замкнут"); - } else { - ui->label_tab_setupMsg_send_controlContoursFlags_data_flags_roll->setText("незамкнут"); - } - - if (controlContoursFlags.march) { - ui->label_tab_setupMsg_send_controlContoursFlags_data_flags_march->setText("замкнут"); - } else { - ui->label_tab_setupMsg_send_controlContoursFlags_data_flags_march->setText("незамкнут"); - } - - if (controlContoursFlags.lag) { - ui->label_tab_setupMsg_send_controlContoursFlags_data_flags_lag->setText("замкнут"); - } else { - ui->label_tab_setupMsg_send_controlContoursFlags_data_flags_lag->setText("незамкнут"); - } - - ui->label_tab_setupMsg_send_Impact_data_count_yaw->setNum(control.yaw); - ui->label_tab_setupMsg_send_Impact_data_count_pitch->setNum(control.pitch); - ui->label_tab_setupMsg_send_Impact_data_count_roll->setNum(control.roll); - ui->label_tab_setupMsg_send_Impact_data_count_march->setNum(control.march); - ui->label_tab_setupMsg_send_Impact_data_count_lag->setNum(control.lag); - ui->label_tab_setupMsg_send_Impact_data_count_depth->setNum(control.depth); - -// received - - if (auvData.modeAUV_Real == 1) - ui->labelt_tab_setupMsg_received_modeAUV_selection_mode->setText("модель"); - else - ui->labelt_tab_setupMsg_received_modeAUV_selection_mode->setText("агент"); - - if (auvData.modeReal) { - ui->label_tab_setupMsg_received_cSMode_count->setText("автоматизированный"); - } else { - ui->label_tab_setupMsg_received_cSMode_count->setText("ручной"); - } - - if (auvData.controlReal.yaw) { - ui->label_tab_setupMsg_received_controlContoursFlags_data_flags_yaw->setText("замкнут"); - } else { - ui->label_tab_setupMsg_received_controlContoursFlags_data_flags_yaw->setText("незамкнут"); - } - - if (auvData.controlReal.pitch) { - ui->label_tab_setupMsg_received_controlContoursFlags_data_flags_pitch->setText("замкнут"); - } else { - ui->label_tab_setupMsg_received_controlContoursFlags_data_flags_pitch->setText("незамкнут"); - } - - if (auvData.controlReal.roll) { - ui->label_tab_setupMsg_received_controlContoursFlags_data_flags_roll->setText("замкнут"); - } else { - ui->label_tab_setupMsg_received_controlContoursFlags_data_flags_roll->setText("незамкнут"); - } - - if (auvData.controlReal.march) { - ui->label_tab_setupMsg_received_controlContoursFlags_data_flags_march->setText("замкнут"); - } else { - ui->label_tab_setupMsg_received_controlContoursFlags_data_flags_march->setText("незамкнут"); - } - - if (auvData.controlReal.lag) { - ui->label_tab_setupMsg_received_controlContoursFlags_data_flags_lag->setText("замкнут"); - } else { - ui->label_tab_setupMsg_received_controlContoursFlags_data_flags_lag->setText("незамкнут"); - } - - ui->label_tab_setupMsg_received_Impact_data_count_vma1->setNum(auvData.signalVMA_real.VMA1); - ui->label_tab_setupMsg_received_Impact_data_count_vma2->setNum(auvData.signalVMA_real.VMA2); - ui->label_tab_setupMsg_received_Impact_data_count_vma3->setNum(auvData.signalVMA_real.VMA3); - ui->label_tab_setupMsg_received_Impact_data_count_vma4->setNum(auvData.signalVMA_real.VMA4); - ui->label_tab_setupMsg_received_Impact_data_count_vma5->setNum(auvData.signalVMA_real.VMA5); - ui->label_tab_setupMsg_received_Impact_data_count_vma6->setNum(auvData.signalVMA_real.VMA6); - -// флаги для настройки БСО - - ui->label_tab_setupMsg_flagsSetupIMU_pult_init->setNum(flagAH127C_pult.initCalibration); - ui->label_tab_setupMsg_flagsSetupIMU_pult_save->setNum(flagAH127C_pult.saveCalibration); - ui->label_tab_setupMsg_flagsSetupIMU_bort_end->setNum(flagAH127C_bort.startCalibration); - ui->label_tab_setupMsg_flagsSetupIMU_bort_start->setNum(flagAH127C_bort.endCalibration); - -// количество посылок - - ui->label_tab_setupMsg_send_checksum_count->setNum(checksum_msg_gui_send); - ui->label_tab_setupMsg_received_checksum_send_count->setNum(checksum_msg_agent_send); - ui->labe_tab_setupMsg_received_checksum_received_count_->setNum(checksum_msg_gui_received); -} - -MainWindow::~MainWindow() -{ - if (pipeline) { - gst_element_set_state(pipeline, GST_STATE_NULL); - gst_object_unref(pipeline); - pipeline = nullptr; - } - delete ui; -} diff --git a/UMAS_GUI-develop/mainwindow.h b/UMAS_GUI-develop/mainwindow.h deleted file mode 100755 index 4b4febf..0000000 --- a/UMAS_GUI-develop/mainwindow.h +++ /dev/null @@ -1,182 +0,0 @@ -#ifndef MAINWINDOW_H -#define MAINWINDOW_H - -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include - -#include "remote_control.h" -#include "uv_state.h" -#include "i_user_interface_data.h" -#include "pc_protocol.h" -#include "i_server_data.h" - -#include "setup_imu.h" -#include "setupimu_check.h" -#include "map.h" - -#include "i_basic_data.h" - -#include "joy_stick.h" -#include "key_board.h" - -QT_BEGIN_NAMESPACE -namespace Ui { class MainWindow; } -QT_END_NAMESPACE - -/*! - * \brief MainWindow - класс формы главного окна, в котором - * реализованы основные методы для работы с ним. - */ -class MainWindow : public QMainWindow -{ - Q_OBJECT - -public: - /*! - * \brief MainWindow конструктор, в котором создается главная UI форма. - */ - MainWindow(QWidget *parent = nullptr); - ~MainWindow(); - - /*! - * \brief setConsole устанавливает настройки для консоли. - */ - void setConsole(); - -private: - /*! - * \brief setTimer_updateImpact устанавливает таймер - * обработки пульта управления. - * \param periodUpdateMsec период обновления таймера - * обработки значений пульта управления. - */ - void setTimer_updateImpact(int periodUpdateMsec); - - /*! - * \brief setBottom устанавливает все используемые кнопки. - */ - void setBottom(); - void setBottom_mode(); - void setBottom_modeAutomated(); - void setBottom_modeAutomatic(); - void setBottom_powerMode(); - void setBottom_connection(); - void setBottom_modeSelection(); - void setBottom_setupIMU(); - void setBottom_setupIMU_check(); - void setBottom_selectAgent(); - - void setTab(); - void setMap(); - void setUpdateUI(); - -private slots: - void displayText(QString str); - void test_automatic_after(); - void setLocationUWB(double *x, double *y); - void updateUi_fromControl(); - - void e_CSModeManualToggled(); - void e_CSModeAutomatedToggled(); - void e_CSModeAutomaticToggled(); - - void stabilizeYawToggled(bool state); - void stabilizePitchToggled(bool state); - void stabilizeRollToggled(bool state); - void stabilizeMarchToggled(bool state); - void stabilizeLagToggled(bool state); - void stabilizeDepthToggled(bool state); - - void pushButton_on_powerMode_2(); - void pushButton_on_powerMode_3(); - void pushButton_on_powerMode_4(); - void pushButton_on_powerMode_5(); - void off_powerMode_5(); - - void setConnection(); - void updateUi_fromAgent1(); - void updateUi_fromAgent2(); - void breakConnection(); - - void setModeSelection(int index); - - void getWindow_setupIMU(); - void getWindow_setupIMU_check(); - - void updateUi_Compass(float yaw); - void updateUi_IMU(DataAH127C imuData); - void updateUi_SetupMsg(); - - void useKeyBoard(); - void useJoyStick(); - - void pushButton_selectAgent1(bool stateBottom); - void pushButton_selectAgent2(bool stateBottom); - - void slot_pushButton_missionControl_modeIdle(); - void slot_pushButton_missionControl_modeStart(); - void slot_pushButton_missionControl_modeCancel(); - void slot_pushButton_missionControl_modeStop(); - void slot_pushButton_missionControl_modeComplete(); - - void slot_pushButton_missionPlanning_goto(); - void slot_pushButton_missionPlanning_goto_update(); - void slot_pushButton_missionPlanning_goto_back(); - - void slot_pushButton_missionPlanning_go_trajectory_update(); - void slot_pushButton_missionPlanning_go_trajectory_back(); - - void slot_pushButton_missionPlanning_following(); - void slot_pushButton_missionPlanning_go_trajectory(); - - void updateUi_DataMission(); - void updateUi_statePushButton(); - - void on_pushButton_Play_Pause_clicked(); - -signals: - void updateCompass(float yaw); - void updateIMU(DataAH127C imuData); - void updateSetupMsg(); - void updateDataMission(); - void updateMap(DataUWB dataUWB); - void updateMapForAgent2(DataUWB dataUWB_agent2); - void signal_pushButton_missionPlanning_goto_updateMap(double x, double y, double r, int flag_clear); - void signal_pushButton_missionPlanning_go_trajectory_updateMap(double x, double y, double r, int flag_clear); - void updateStatePushButton(); - -protected: - Ui::MainWindow *ui; - - QTimer *updateTimer = nullptr; - - JoyStick *joyStick = nullptr; - KeyBoard *keyBoard = nullptr; - void keyPressEvent(QKeyEvent *event); - void keyReleaseEvent(QKeyEvent *event); - - QTimer *timer_off_powerMode_5; - power_Mode before_powerMode; - - IUserInterfaceData uv_interface; - Pult::PC_Protocol *communicationAgent1; - Pult::PC_Protocol *communicationAgent2; - - RemoteControl pult; - - // === Добавлено из второго файла === - GstElement *pipeline = nullptr; - WId videoWindowId = 0; - // =================================== -}; - -#endif // MAINWINDOW_H diff --git a/UMAS_GUI-develop/mainwindow.ui b/UMAS_GUI-develop/mainwindow.ui deleted file mode 100755 index 0320463..0000000 --- a/UMAS_GUI-develop/mainwindow.ui +++ /dev/null @@ -1,3822 +0,0 @@ - - - MainWindow - - - - 0 - 0 - 1920 - 1080 - - - - UMAS GUI - - - - - - - - - - - - 0 - 0 - - - - - Модель - - - - - Агент - - - - - - - - - 0 - 0 - - - - Установить соединение - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Разорвать соединение - - - - - - - - - - - - - true - - - - 0 - 0 - - - - - 50 - 50 - - - - 1 - - - - - - - true - - - - 0 - 0 - - - - - 50 - 50 - - - - 2 - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - - - - 4 - - - - Tab 1 - - - - - - - - - - Tab 2 - - - - - 9 - 9 - 351 - 241 - - - - - - - - - Bx = - - - - - - - 0 - - - - - - - By = - - - - - - - 0 - - - - - - - Bz = - - - - - - - 0 - - - - - - - - - Гироскоп: - - - - - - - - - Ax = - - - - - - - 0 - - - - - - - Ay = - - - - - - - 0 - - - - - - - Az = - - - - - - - 0 - - - - - - - - - - - Wx = - - - - - - - 0 - - - - - - - 0 - - - - - - - Wz = - - - - - - - 0 - - - - - - - Wy = - - - - - - - - - - - q0 = - - - - - - - 0 - - - - - - - q1 = - - - - - - - 0 - - - - - - - q2 = - - - - - - - 0 - - - - - - - q3 = - - - - - - - 0 - - - - - - - - - Акселерометр: - - - - - - - Магнитометр: - - - - - - - Кватернионы: - - - - - - - - - 10 - 280 - 351 - 51 - - - - - 0 - 0 - - - - Настроить БСО - - - - - - 10 - 340 - 351 - 51 - - - - - 0 - 0 - - - - Проверить настройку БСО - - - - - - Page - - - - - - - - Qt::Horizontal - - - - - - - - - - 0 - 0 - - - - Количество отправленных: - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - - Qt::Horizontal - - - - - - - - 0 - 0 - - - - Полученные - - - Qt::AlignCenter - - - - - - - 5 - - - QLayout::SetDefaultConstraint - - - - - - 0 - 0 - - - - Количество: - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - - Флаги настройки БСО - - - Qt::AlignCenter - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - - - - 0 - 0 - - - - Текущий режим: - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - - - - - 0 - 0 - - - - Замкнутые контуры: - - - - - - - - - - 0 - 0 - - - - ψ: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - θ: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - γ: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - x: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - y: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - - - - Qt::Horizontal - - - - - - - - 0 - 0 - - - - Отправленные - - - Qt::AlignCenter - - - - - - - - - - 0 - 0 - - - - Задающие воздействия: - - - - - - - - - - 0 - 0 - - - - ψ: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - θ: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - γ: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - x: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - y: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - z: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - - - - Qt::Vertical - - - - - - - Qt::Horizontal - - - - - - - Qt::Vertical - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - Qt::Vertical - - - - - - - Qt::Horizontal - - - - - - - - - - 0 - 0 - - - - Количество полученных: - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - - - - - 0 - 0 - - - - Режим: - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - - - - - 0 - 0 - - - - Текущий вывод данных: - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - - Qt::Vertical - - - - - - - 5 - - - QLayout::SetDefaultConstraint - - - - - - 0 - 0 - - - - Режим питания: - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - - Qt::Vertical - - - - - - - - - - - pult_init: - - - - - - - нет сигнала - - - - - - - pult_save: - - - - - - - нет сигнала - - - - - - - - - - - bort_start: - - - - - - - нет сигнала - - - - - - - bort_end: - - - - - - - нет сигнала - - - - - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - Qt::Vertical - - - - - - - - - - 0 - 0 - - - - Текущие замкнутые контуры: - - - - - - - - - - 0 - 0 - - - - ψ: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - θ: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - γ: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - x: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - y: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - Qt::Vertical - - - - - - - Qt::Vertical - - - - - - - - - - 0 - 0 - - - - Текущие воздействия на ВМА: - - - - - - - - - - 0 - 0 - - - - ВМА1: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - ВМА2: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - ВМА3: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - ВМА4: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - ВМА5: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - ВМА6: - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - - - - - - - 0 - 0 - - - - Вывод данных: - - - - - - - - 0 - 0 - - - - нет сигнала - - - Qt::AlignCenter - - - - - - - - - Qt::Horizontal - - - - - - - Qt::Vertical - - - - - - - Qt::Vertical - - - - - - - - - - Page - - - - - - - - - 0 - 0 - - - - Перезагрузка -5 секунд - - - - - - - <html><head/><body><p align="center"><span style=" font-size:28pt; color:#73d216;">+</span></p></body></html> - - - Qt::AlignCenter - - - false - - - - - - - Qt::Vertical - - - - - - - <html><head/><body><p align="center"><span style=" font-size:28pt; color:#73d216;">+</span></p></body></html> - - - Qt::AlignCenter - - - false - - - - - - - <html><head/><body><p align="center"><span style=" font-size:28pt; color:#73d216;">+</span></p></body></html> - - - Qt::AlignCenter - - - false - - - - - - - Qt::Vertical - - - - - - - Qt::Vertical - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - Qt::Vertical - - - - - - - <html><head/><body><p align="center"><span style=" font-size:28pt; color:#73d216;">+</span></p></body></html> - - - Qt::AlignCenter - - - false - - - - - - - Qt::Vertical - - - - - - - Qt::Horizontal - - - - - - - <html><head/><body><p align="center"><span style=" font-size:28pt; color:#73d216;">+</span></p></body></html> - - - Qt::AlignCenter - - - false - - - - - - - Qt::Vertical - - - - - - - Qt::Vertical - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - Qt::Vertical - - - - - - - <html><head/><body><p align="center"><span style=" font-size:28pt; color:#73d216;">+</span></p></body></html> - - - Qt::AlignCenter - - - false - - - - - - - - 0 - 0 - - - - 2 - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - - 0 - 0 - - - - 4 - - - - - - - <html><head/><body><p align="center"><span style=" font-size:28pt; color:#cc0000;">-</span></p></body></html> - - - Qt::AlignCenter - - - false - - - - - - - Qt::Vertical - - - - - - - Qt::Vertical - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - Qt::Vertical - - - - - - - Qt::Vertical - - - - - - - Qt::Horizontal - - - - - - - Qt::Vertical - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - <html><head/><body><p align="center"><span style=" font-size:28pt; color:#cc0000;">-</span></p></body></html> - - - Qt::AlignCenter - - - false - - - - - - - Qt::Vertical - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - <html><head/><body><p align="center"><span style=" font-size:28pt; color:#73d216;">+</span></p></body></html> - - - Qt::AlignCenter - - - false - - - - - - - Вычислитель - - - Qt::AlignCenter - - - - - - - ВМА - - - Qt::AlignCenter - - - - - - - Qt::Vertical - - - - - - - Qt::Horizontal - - - - - - - Qt::Vertical - - - - - - - Qt::Vertical - - - - - - - <html><head/><body><p align="center"><span style=" font-size:28pt; color:#73d216;">+</span></p></body></html> - - - Qt::AlignCenter - - - false - - - - - - - Qt::Vertical - - - - - - - - 0 - 0 - - - - 3 - - - - - - - Qt::Vertical - - - - - - - Qt::Vertical - - - - - - - Wi-fi - - - Qt::AlignCenter - - - - - - - <html><head/><body><p align="center"><span style=" font-size:28pt; color:#73d216;">+</span></p></body></html> - - - Qt::AlignCenter - - - false - - - - - - - <html><head/><body><p align="center"><span style=" font-size:28pt; color:#cc0000;">-</span></p></body></html> - - - Qt::AlignCenter - - - false - - - - - - - Qt::Horizontal - - - - - - - <html><head/><body><p align="center"><span style=" font-size:28pt; color:#cc0000;">-</span></p></body></html> - - - Qt::AlignCenter - - - false - - - - - - - Гидроакустика - - - Qt::AlignCenter - - - - - - - <html><head/><body><p align="center"><span style=" font-size:28pt; color:#cc0000;">-</span></p></body></html> - - - Qt::AlignCenter - - - false - - - - - - - <html><head/><body><p align="center"><span style=" font-size:28pt; color:#73d216;">+</span></p></body></html> - - - Qt::AlignCenter - - - false - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - Qt::Vertical - - - - - - - <html><head/><body><p align="center"><span style=" font-size:28pt; color:#cc0000;">-</span></p></body></html> - - - Qt::AlignCenter - - - false - - - - - - - <html><head/><body><p align="center"><span style=" font-size:28pt; color:#73d216;">+</span></p></body></html> - - - Qt::AlignCenter - - - false - - - - - - - Qt::Vertical - - - - - - - Qt::Vertical - - - - - - - <html><head/><body><p align="center"><span style=" font-size:28pt; color:#73d216;">+</span></p></body></html> - - - Qt::AlignCenter - - - false - - - - - - - <html><head/><body><p align="center"><span style=" font-size:28pt; color:#cc0000;">-</span></p></body></html> - - - Qt::AlignCenter - - - false - - - - - - - Qt::Vertical - - - - - - - Qt::Vertical - - - - - - - UWB - - - Qt::AlignCenter - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - <html><head/><body><p align="center"><span style=" font-size:28pt; color:#cc0000;">-</span></p></body></html> - - - Qt::AlignCenter - - - false - - - - - - - - - - Page - - - - - 10 - 10 - 831 - 601 - - - - - - - 20 - 750 - 101 - 91 - - - - PushButton - - - - - - - - - true - - - false - - - - - - - - - - - - - - - 0 - - - - - - - Информация - - - - - - - - 0 - 0 - - - - - - - - Qt::Horizontal - - - - - - - - - true - - - Джойстик - - - true - - - true - - - false - - - - - - - Клавиатура - - - false - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - Qt::Horizontal - - - - - - - - - Qt::Vertical - - - - - - - З - - - - - - - Qt::Horizontal - - - - - - - Qt::Vertical - - - - - - - Qt::Vertical - - - - - - - Qt::Vertical - - - - - - - γ - - - - - - - 0 - - - - - - - Qt::Horizontal - - - - - - - 0 - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - Qt::Vertical - - - - - - - 0 - - - - - - - Qt::Horizontal - - - - - - - 0 - - - - - - - - - - - - - - Т - - - - - - - 0 - - - - - - - Qt::Horizontal - - - - - - - θ - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - ψ - - - - - - - Qt::Vertical - - - - - - - Qt::Horizontal - - - - - - - 0 - - - - - - - Qt::Vertical - - - - - - - Qt::Vertical - - - - - - - Qt::Vertical - - - - - - - - - Qt::Horizontal - - - - - - - - - Qt::Vertical - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - Т - - - - - - - Qt::Horizontal - - - - - - - Qt::Vertical - - - - - - - 0 - - - - - - - Qt::Vertical - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - 0 - - - - - - - 0 - - - - - - - Qt::Vertical - - - - - - - Qt::Horizontal - - - - - - - z - - - - - - - Qt::Horizontal - - - - - - - Qt::Vertical - - - - - - - З - - - - - - - Qt::Horizontal - - - - - - - x - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - 0 - - - - - - - y - - - - - - - 0 - - - - - - - Qt::Horizontal - - - - - - - 0 - - - - - - - Qt::Vertical - - - - - - - Qt::Vertical - - - - - - - Qt::Vertical - - - - - - - Qt::Vertical - - - - - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - - - - - - Qt::Horizontal - - - - - - - - - - 0 - 0 - - - - Ручной - - - false - - - false - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - 0 - 0 - - - - Автоматизированный - - - - - - - - - true - - - - 0 - 0 - - - - ψ - - - - - - - - 0 - 0 - - - - θ - - - - - - - - 0 - 0 - - - - γ - - - - - - - - 0 - 0 - - - - x - - - - - - - - 0 - 0 - - - - y - - - - - - - - 0 - 0 - - - - z - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - 0 - 0 - - - - Автоматический - - - - - - - - - - - - - - - - 0 - 0 - - - - Автоматический режим - - - Qt::AlignCenter - - - - - - - Qt::Horizontal - - - - - - - 0 - - - - - - - - 0 - 0 - - - - Выбор миссии - - - Qt::AlignCenter - - - - - - - Выход в точку - - - - - - - Следование - - - - - - - Движение по траектории - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - - Введите параметры 3 точек - - - Qt::AlignCenter - - - - - - - - - x1, см - - - - - - - 10000.000000000000000 - - - - - - - y1, см - - - - - - - 10000.000000000000000 - - - - - - - r1, см - - - - - - - 10000.000000000000000 - - - - - - - - - - - x2, см - - - - - - - 10000.000000000000000 - - - - - - - y2, см - - - - - - - 10000.000000000000000 - - - - - - - r2, см - - - - - - - 10000.000000000000000 - - - - - - - - - - - x3, см - - - - - - - 10000.000000000000000 - - - - - - - y3, см - - - - - - - 10000.000000000000000 - - - - - - - r3, см - - - - - - - 10000.000000000000000 - - - - - - - - - Обновить - - - - - - - Очистить цель - - - - - - - Вернуться к выбору миссий - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - - Введите параметры точки - - - Qt::AlignCenter - - - - - - - - - x, см - - - - - - - 10000.000000000000000 - - - - - - - y, см - - - - - - - 10000.000000000000000 - - - - - - - Радиус, см - - - - - - - 10000.000000000000000 - - - - - - - - - Обновить - - - - - - - Очистить цель - - - - - - - Вернуться к выбору миссий - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - - Включить/выключить запись траектории - - - - - - - Очистить траекторию - - - - - - - Qt::Horizontal - - - - - - - - - Состояние агента - - - - - - - - - Ожидание - - - - - - - Старт - - - - - - - Отмена - - - - - - - Пауза - - - - - - - Завершение - - - - - - - - - - - - - Текущие состояние: - - - - - - - - Отсутствует - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - Обратно - - - - - - - - - - - - - - - 0 - 0 - 1920 - 24 - - - - - - - - Compass - QWidget -
compass.h
- 1 -
- - Map - QWidget -
map.h
- 1 -
-
- - -
diff --git a/UMAS_GUI-develop/map/map.cpp b/UMAS_GUI-develop/map/map.cpp deleted file mode 100755 index aa12551..0000000 --- a/UMAS_GUI-develop/map/map.cpp +++ /dev/null @@ -1,189 +0,0 @@ - #include "map.h" -#include "ui_map.h" -#include "math.h" -#include - -Map::Map(QWidget *parent) : - QWidget(parent), - ui(new Ui::Map) -{ - ui->setupUi(this); - - db = new DataBase("list_uwb.db", "Location_UWB", "Color", "x", "y"); - db->connectToDataBase(); - db->createTable(ui->tableWidget_listUWB); - - range[0] = 1; - range[1] = 1; - range[2] = 1; - - createPlot(); - - connect(ui->pushButton_addUWB, &QPushButton::clicked, - this, &Map::addRowUWB); - connect(ui->pushButton_updateLocationUWB, &QPushButton::clicked, - this, &Map::updateLocationUWB); -} - -void Map::createPlot() -{ - beacon1 = new QScatterSeries(); - beacon2 = new QScatterSeries(); - beacon3 = new QScatterSeries(); - - agent1Coords = new QScatterSeries(); - agent2Coords = new QScatterSeries(); - missionPlanning_goto_goal = new QScatterSeries(); - missionPlanning_goto_goal->setColor(QColor(255, 51, 153)); - - circle1 = new QLineSeries(); - circle1->setColor(QColor(0, 0, 255)); - circle2 = new QLineSeries(); - circle2->setColor(QColor(0, 255, 0)); - circle3 = new QLineSeries(); - circle3->setColor(QColor(255, 165, 0)); - missionPlanning_goto_goal_radius = new QLineSeries(); - missionPlanning_goto_goal_radius->setColor(QColor(255, 51, 153)); - missionPlanning_goto_traj = new QLineSeries(); - missionPlanning_goto_traj->setColor(QColor(255, 0, 0)); - - chart = new QChart(); - chart->addSeries(beacon1); - chart->addSeries(beacon2); - chart->addSeries(beacon3); - chart->addSeries(circle1); - chart->addSeries(circle2); - chart->addSeries(circle3); - chart->addSeries(missionPlanning_goto_goal_radius); - chart->addSeries(missionPlanning_goto_traj); - chart->addSeries(agent1Coords); - chart->addSeries(agent2Coords); - chart->addSeries(missionPlanning_goto_goal); - chart->createDefaultAxes(); - chart->axes(Qt::Vertical).first()->setRange(-50,100); - chart->axes(Qt::Vertical).first()->setTitleText("Y, см"); - chart->axes(Qt::Horizontal).first()->setRange(-50,150); - chart->axes(Qt::Horizontal).first()->setTitleText("X, см"); - chartView = new QChartView(chart); - - ui->verticalLayout_map->addWidget(chartView); - - connect(ui->pushButton_scaling, &QPushButton::toggled, - this, &Map::plotScaling); -} - -void Map::updateUi_map(DataUWB dataUWB) -{ - drawCurrentCoords(agent1Coords, missionPlanning_goto_traj, dataUWB.locationX, dataUWB.locationY); - - range[0] = dataUWB.distanceToBeacon[0]; - range[1] = dataUWB.distanceToBeacon[1]; - range[2] = dataUWB.distanceToBeacon[2]; - - drawCircle(circle1, beacon1, x[0], y[0], range[0], 1); - drawCircle(circle2, beacon2, x[1], y[1], range[1], 1); - drawCircle(circle3, beacon3, x[2], y[2], range[2], 1); -} - -void Map::updateUi_map2(DataUWB dataUWB) -{ - drawCurrentCoords(agent2Coords, missionPlanning_goto_traj, dataUWB.locationX, dataUWB.locationY); -} - -void Map::updateUi_missionPlanning_goto_goal(double x, double y, double r, int flag_clear) -{ -// drawCurrentCoords(missionPlanning_goto_goal, x, y); - drawCircle( missionPlanning_goto_goal_radius, missionPlanning_goto_goal, x, y, r, flag_clear); -} - -void Map::updateUi_missionPlanning_goto_goal_clear() -{ - missionPlanning_goto_goal->clear(); - missionPlanning_goto_goal_radius->clear(); -} - -void Map::addRowUWB() -{ - int countRows = ui->tableWidget_listUWB->rowCount(); - if (countRows == 2) - ui->pushButton_addUWB->setEnabled(false); - ui->tableWidget_listUWB->insertRow(countRows); - ui->tableWidget_listUWB->setItem(countRows, 0, new QTableWidgetItem(color.at(countRows))); - ui->tableWidget_listUWB->resizeColumnsToContents(); -} - -void Map::updateLocationUWB() -{ - int countRows = ui->tableWidget_listUWB->rowCount(); - for (int row = 0; row < countRows; row++) - { - QTableWidgetItem *item_color = ui->tableWidget_listUWB->item(row, 0); - QTableWidgetItem *item_x = ui->tableWidget_listUWB->item(row, 1); - QTableWidgetItem *item_y = ui->tableWidget_listUWB->item(row, 2); - if (item_x && item_y) { - x[row] = item_x->text().toInt(nullptr, 10); - y[row] = item_y->text().toInt(nullptr, 10); - db->inserIntoDeviceTable(item_color->text(), x[row], y[row]); - } - } - emit sendLocationUWB(&x[0],&y[0]); - drawCircle(circle1, beacon1, x[0], y[0], range[0], 1); - drawCircle(circle2, beacon2, x[1], y[1], range[1], 1); - drawCircle(circle3, beacon3, x[2], y[2], range[2], 1); -} - -void Map::plotScaling(bool state) -{ - if (state) - chartView->setRubberBand(QChartView::RectangleRubberBand); - else - chartView->setRubberBand(QChartView::NoRubberBand); - -} - -void Map::updateUi_missionPlanning_goto_traj_onoff() -{ - if (flag_traj) - flag_traj = 0; - else - flag_traj = 1; -} - -void Map::updateUi_missionPlanning_goto_traj_clear() -{ - missionPlanning_goto_traj->clear(); -} - -void Map::drawCircle(QLineSeries *circle, QScatterSeries *point, double x, double y, double R, int flag_clear) -{ - if (flag_clear) { - circle->clear(); - point->clear(); - } - -// circle = new QLineSeries(); -// circle->setColor(QColor(0, 0, 255)); -// chart->addSeries(circle); - - point->append(x,y); - - for(int i=0; i<=360; i++){ - double alpha = i*M_PI/180; - double plot_x = x+R*cos(alpha); - double plot_y = y+R*sin(alpha); - circle->append(plot_x,plot_y); - } -} - -void Map::drawCurrentCoords(QScatterSeries *agentCoords, QLineSeries *traj, double x, double y) -{ - agentCoords->clear(); - agentCoords->append(x,y); - if (flag_traj) - traj->append(x,y); -} - -Map::~Map() -{ - delete ui; -} diff --git a/UMAS_GUI-develop/map/map.h b/UMAS_GUI-develop/map/map.h deleted file mode 100755 index e750b5b..0000000 --- a/UMAS_GUI-develop/map/map.h +++ /dev/null @@ -1,127 +0,0 @@ -#ifndef MAP_H -#define MAP_H - -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "uv_state.h" -#include "database.h" - -namespace Ui { -class Map; -} -using namespace QtCharts; - -/*! - * \brief Map class класс отображения данных об UWB и агентов. - */ -class Map : public QWidget -{ - Q_OBJECT - -public: - explicit Map(QWidget *parent = nullptr); - ~Map(); - - /*! - * \brief drawCircle метод рисования расстояние от модуля до агента. - * \param circle окружность. - * \param R расстояние от модуля до агетна. - */ - void drawCircle(QLineSeries *circle, QScatterSeries *point, double x, double y, double R, int flag_clear); - /*! - * \brief drawCurrentCoords метод отображения агента. - * \param x координата агента по оси X. - * \param y координата агента по оси Y. - */ - void drawCurrentCoords(QScatterSeries *agentCoords, QLineSeries *traj, double x, double y); - -protected: - /*! - * \brief x координаты модулей по оси X. - */ - double x[3]; - /*! - * \brief y координаты модулей по оси Y. - */ - double y[3]; - /*! - * \brief range текущее расстояние от агетна до модуля. - */ - double range[3]; - - /*! - * \brief ui указатель на форму map.ui - */ - Ui::Map *ui; - - QChartView *chartView = nullptr; - QChart *chart = nullptr; - QScatterSeries *beacon1 = nullptr; - QScatterSeries *beacon2 = nullptr; - QScatterSeries *beacon3 = nullptr; - QScatterSeries *agent1Coords = nullptr; - QScatterSeries *agent2Coords = nullptr; - QScatterSeries *missionPlanning_goto_goal = nullptr; - QLineSeries *missionPlanning_goto_goal_radius = nullptr; - QLineSeries *missionPlanning_goto_traj = nullptr; - QLineSeries *circle1 = nullptr; - QLineSeries *circle2 = nullptr; - QLineSeries *circle3 = nullptr; - int flag_traj=0; - - QStringList color = { "Синий", "Зеленый", "Оранжевый" }; - -private: - DataBase *db; - - void createPlot(); - -public slots: - /*! - * \brief updateUi_map слот обновления данных о расположении UWB и агента. - * \param dataUWB структура с информацией об расположении агента. - */ - void updateUi_map(DataUWB dataUWB); - void updateUi_map2(DataUWB dataUWB); - void updateUi_missionPlanning_goto_goal(double x, double y, double r, int flag_clear); - void updateUi_missionPlanning_goto_goal_clear(); - - /*! - * \brief addRowUWB слот добавления строк и цветов модулей в таблицу. - */ - void addRowUWB(); - /*! - * \brief updateLocationUWB метод обновления по кнопке данных о UWB модулях. - */ - void updateLocationUWB(); - /*! - * \brief plotScaling слот переключения. масштабирования графика. - * \param state состояние нажатия кнопки. - */ - void plotScaling(bool state); - - void updateUi_missionPlanning_goto_traj_onoff(); - void updateUi_missionPlanning_goto_traj_clear(); - - -signals: - /*! - * \brief sendLocationUWB сигнал отправки расположения UWB модулей - * \param x координаты модулей по оси X. - * \param y координаты модулей по оси Y. - */ - void sendLocationUWB(double *x, double *y); -}; - -#endif // MAP_H diff --git a/UMAS_GUI-develop/map/map.ui b/UMAS_GUI-develop/map/map.ui deleted file mode 100755 index 7659d34..0000000 --- a/UMAS_GUI-develop/map/map.ui +++ /dev/null @@ -1,110 +0,0 @@ - - - Map - - - - 0 - 0 - 1149 - 775 - - - - Form - - - - - - - - - - - - - Расположение UWB - модулей - - - Qt::AlignCenter - - - - - - - - - - - - Добавить модуль - - - - - - - Обновить - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - - - - Месторасположение - - - - - - - Масштабирование - - - true - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - diff --git a/UMAS_GUI-develop/remote_control/.vscode/tasks.json b/UMAS_GUI-develop/remote_control/.vscode/tasks.json deleted file mode 100644 index 08d9005..0000000 --- a/UMAS_GUI-develop/remote_control/.vscode/tasks.json +++ /dev/null @@ -1,28 +0,0 @@ -{ - "tasks": [ - { - "type": "cppbuild", - "label": "C/C++: gcc build active file", - "command": "/usr/bin/gcc", - "args": [ - "-fdiagnostics-color=always", - "-g", - "${file}", - "-o", - "${fileDirname}/${fileBasenameNoExtension}" - ], - "options": { - "cwd": "${fileDirname}" - }, - "problemMatcher": [ - "$gcc" - ], - "group": { - "kind": "build", - "isDefault": true - }, - "detail": "Task generated by Debugger." - } - ], - "version": "2.0.0" -} \ No newline at end of file diff --git a/UMAS_GUI-develop/remote_control/joy_stick.cpp b/UMAS_GUI-develop/remote_control/joy_stick.cpp deleted file mode 100755 index 446b444..0000000 --- a/UMAS_GUI-develop/remote_control/joy_stick.cpp +++ /dev/null @@ -1,87 +0,0 @@ -#include "joy_stick.h" -#include -#include -#include -#include -#include "SFML/Window/Joystick.hpp" - -namespace { - double baseDepth = 0.0; // базовое значение глубины - bool fluctuationsActivated = false; -} - -JoyStick::JoyStick(QObject *parent) : RemoteControl() -{ - Q_UNUSED(parent); - - id = 0; - int periodUpdateMsec = 80; - int updperde = 150; - - updateTimer = new QTimer(this); - updateTimer2 = new QTimer(this); - connect(updateTimer, &QTimer::timeout, this, &JoyStick::updateImpact); - connect(updateTimer2, &QTimer::timeout, this, &JoyStick::Naebalovo); - updateTimer->start(periodUpdateMsec); - updateTimer2->start(updperde); - - // Назначение осей и кнопок - impactAxisMarch = sf::Joystick::Y; - impactAxisDepth = sf::Joystick::Z; - impactAxisRoll = sf::Joystick::PovX; - impactAxisPitch = sf::Joystick::PovY; - impactAxisYaw = sf::Joystick::R; - impactAxisLag = sf::Joystick::X; - impactButtonGripping = 0; - impactButtonRotman = 1; - falseDepthplus = 8; - falseDepthminus = 9; - offPower = 10; - - baseDepth = currentDepth; - - fluctuationTimer.start(); -} - -JoyStick::~JoyStick() -{ - // Освобождение ресурсов, если потребуется -} - -void JoyStick::Naebalovo() -{ - // При нажатии кнопок глубина изменяется, и базовое значение обновляется - if (sf::Joystick::isButtonPressed(id, falseDepthplus)) { - currentDepth += 0.1; - baseDepth = currentDepth; - fluctuationsActivated = true; - qDebug() << "Глубина:" << QString::number(currentDepth, 'f', 3); - } - if (sf::Joystick::isButtonPressed(id, falseDepthminus)) { - currentDepth -= 0.1; - baseDepth = currentDepth; - fluctuationsActivated = true; - qDebug() << "Глубина:" << QString::number(currentDepth, 'f', 3); - } -} - -void JoyStick::updateImpact() -{ - sf::Joystick::update(); - - if (!fluctuationsActivated) { - return; - } - - - double fluctuationValue = QRandomGenerator::global()->generateDouble() * 0.20 - 0.10; - currentDepth = baseDepth + fluctuationValue; - fluctuationTimer.restart(); - qDebug() << "Глубина:" << QString::number(currentDepth, 'f', 3); - - if (sf::Joystick::isConnected((id))) { - setOffPower(sf::Joystick::isButtonPressed(id, offPower)); - - } - -} diff --git a/UMAS_GUI-develop/remote_control/joy_stick.h b/UMAS_GUI-develop/remote_control/joy_stick.h deleted file mode 100755 index 7d1b0ec..0000000 --- a/UMAS_GUI-develop/remote_control/joy_stick.h +++ /dev/null @@ -1,32 +0,0 @@ -#ifndef JOYSTICK_H -#define JOYSTICK_H - -#include -#include -#include - -#include "remote_control.h" -#include "SFML/Window.hpp" - - - -class JoyStick : public RemoteControl -{ - Q_OBJECT -public: - explicit JoyStick(QObject *parent = nullptr); // Добавлен explicit - ~JoyStick(); - -private: - double currentDepth = 0.00; - QElapsedTimer fluctuationTimer; - double fluctuationValue = 0.0; - - - -private slots: - void updateImpact(); - void Naebalovo(); -}; - -#endif // JOYSTICK_H diff --git a/UMAS_GUI-develop/remote_control/key_board.cpp b/UMAS_GUI-develop/remote_control/key_board.cpp deleted file mode 100755 index d36fa6e..0000000 --- a/UMAS_GUI-develop/remote_control/key_board.cpp +++ /dev/null @@ -1,95 +0,0 @@ -#include "key_board.h" - -KeyBoard::KeyBoard(QObject *parent) -{ - -} - -KeyBoard::~KeyBoard() -{ -} - -void KeyBoard::keyPressEvent(QKeyEvent *event) -{ - ControlData control = getControlData(); - switch (event->key()) { - case Qt::Key_O: - setMarch(1); - break; - case Qt::Key_L: - setMarch(-1); - break; - case Qt::Key_W: - setPitch(1); - break; - case Qt::Key_S: - setPitch(-1); - break; - case Qt::Key_A: - setYaw(1); - break; - case Qt::Key_D: - setYaw(-1); - break; - case Qt::Key_C: - setDepth(0.5); - break; - case Qt::Key_V: - setDepth(-0.5); - break; - case Qt::Key_Q: - setRoll(1); - break; - case Qt::Key_E: - setRoll(-1); - break; - case Qt::Key_K: - setLag(1); - break; - case Qt::Key_Semicolon: - setLag(-1); - break; - } -} - -void KeyBoard::keyReleaseEvent(QKeyEvent *event) -{ - switch (event->key()) { - case Qt::Key_O: - setMarch(0); - break; - case Qt::Key_L: - setMarch(0); - break; - case Qt::Key_W: - setPitch(0); - break; - case Qt::Key_S: - setPitch(0); - break; - case Qt::Key_A: - setYaw(0); - break; - case Qt::Key_D: - setYaw(0); - break; - case Qt::Key_C: - setDepth(0); - break; - case Qt::Key_V: - setDepth(0); - break; - case Qt::Key_Q: - setRoll(0); - break; - case Qt::Key_E: - setRoll(0); - break; - case Qt::Key_K: - setLag(0); - break; - case Qt::Key_Semicolon: - setLag(0); - break; - } -} diff --git a/UMAS_GUI-develop/remote_control/key_board.h b/UMAS_GUI-develop/remote_control/key_board.h deleted file mode 100755 index b879064..0000000 --- a/UMAS_GUI-develop/remote_control/key_board.h +++ /dev/null @@ -1,24 +0,0 @@ -#ifndef KEYBOARD_H -#define KEYBOARD_H - -#include -#include - -#include "remote_control.h" - -class KeyBoard : public RemoteControl -{ -public: - explicit KeyBoard(QObject *parent = nullptr); - ~KeyBoard(); - - -public: - void keyPressEvent(QKeyEvent *event); - void keyReleaseEvent(QKeyEvent *event); - -private slots: - void updateImpact(); -}; - -#endif // KEYBOARD_H diff --git a/UMAS_GUI-develop/remote_control/remote_control.cpp b/UMAS_GUI-develop/remote_control/remote_control.cpp deleted file mode 100755 index 98b2824..0000000 --- a/UMAS_GUI-develop/remote_control/remote_control.cpp +++ /dev/null @@ -1,13 +0,0 @@ -#include "remote_control.h" - -RemoteControl::RemoteControl() -{ - -} - - - -RemoteControl::~RemoteControl(){ -} - - diff --git a/UMAS_GUI-develop/remote_control/remote_control.h b/UMAS_GUI-develop/remote_control/remote_control.h deleted file mode 100755 index 53034c1..0000000 --- a/UMAS_GUI-develop/remote_control/remote_control.h +++ /dev/null @@ -1,42 +0,0 @@ -#ifndef REMOTECONTROL_H -#define REMOTECONTROL_H - -#include -#include "i_control_data.h" -#include -#include - -#include "SFML/Window.hpp" -//#include "joy_stick.h" -//#include "key_board.h" - -class RemoteControl : public IControlData -{ - Q_OBJECT -public: - explicit RemoteControl(); - ~RemoteControl(); - - int id; - QTimer *updateTimer; - QTimer *updateTimer2; - -protected: - //оси - sf::Joystick::Axis impactAxisMarch; - sf::Joystick::Axis impactAxisDepth; - sf::Joystick::Axis impactAxisRoll; - sf::Joystick::Axis impactAxisPitch; - sf::Joystick::Axis impactAxisYaw; - sf::Joystick::Axis impactAxisLag; - //кнопки - int impactButtonGripping; - int impactButtonRotman; - int falseDepthplus; - int falseDepthminus; - int offPower; - - -}; - -#endif // REMOTECONTROL_H diff --git a/UMAS_GUI-develop/remote_control/test.cpp b/UMAS_GUI-develop/remote_control/test.cpp deleted file mode 100644 index 76bc8f9..0000000 --- a/UMAS_GUI-develop/remote_control/test.cpp +++ /dev/null @@ -1,28 +0,0 @@ -#include "joy_stick.h" -#include - -JoyStick::JoyStick(QObject *parent) : QObject(parent) { - id = 0; // ID джойстика - int periodUpdateMsec = 20; // Интервал обновления (20 мс) - - updateTimer = new QTimer(this); - connect(updateTimer, &QTimer::timeout, this, &JoyStick::updateImpact); - updateTimer->start(periodUpdateMsec); -} - -void JoyStick::updateImpact() { - sf::Joystick::update(); // Обновление состояния джойстика - - // Проверка всех осей - for (int axis = 0; axis < sf::Joystick::AxisCount; ++axis) { - float value = sf::Joystick::getAxisPosition(id, static_cast(axis)); - qDebug() << "Axis" << axis << ":" << value; - } - - // Проверка всех кнопок - for (int btn = 0; btn < sf::Joystick::getButtonCount(id); ++btn) { - if (sf::Joystick::isButtonPressed(id, btn)) { - qDebug() << "Кнопка" << btn << "нажата!"; - } - } -} \ No newline at end of file diff --git a/UMAS_GUI-develop/ui_utils/dataIMU_magn.db b/UMAS_GUI-develop/ui_utils/dataIMU_magn.db deleted file mode 100755 index 6cc7723..0000000 Binary files a/UMAS_GUI-develop/ui_utils/dataIMU_magn.db and /dev/null differ diff --git a/UMAS_GUI-develop/ui_utils/database.cpp b/UMAS_GUI-develop/ui_utils/database.cpp deleted file mode 100755 index 7260d0e..0000000 --- a/UMAS_GUI-develop/ui_utils/database.cpp +++ /dev/null @@ -1,128 +0,0 @@ -#include "database.h" - -DataBase::DataBase(QString name, - QString tableName, - QString nameColumn1, QString nameColumn2, QString nameColumn3, - QObject *parent) : QObject(parent) -{ - nameDB = name; - tableNameDB = tableName; - nameColumn1DB = nameColumn1; - nameColumn2DB = nameColumn2; - nameColumn3DB = nameColumn3; -} - -DataBase::~DataBase() -{ -} - -/*! - * \brief DataBase::connectToDataBase Перед подключением к базе данных производим - * проверку на её существование.В зависимости от результата производим открытие - * базы данных или её восстановление. - */ -void DataBase::connectToDataBase() -{ - if(!QFile("./ui_utils/" + nameDB).exists()){ - qDebug() << "createDeviceTable" << this->restoreDataBase(); - } else { - this->openDataBase(); - } -} - -bool DataBase::restoreDataBase() -{ - if(this->openDataBase()){ - if(!this->createDeviceTable()){ - return false; - } else { - return true; - } - } else { - qDebug() << "Не удалось восстановить базу данных"; - return false; - } - return false; -} - -/*! - * \brief DataBase::openDataBase База данных открывается по заданному пути и - * имени базы данных, если она существует. - */ -bool DataBase::openDataBase() -{ - db = QSqlDatabase::addDatabase("QSQLITE"); - db.setDatabaseName("./ui_utils/" + nameDB); - if(db.open()){ - return true; - } else { - return false; - } -} - -void DataBase::closeDataBase() -{ - db.close(); -} - -/*! - * \brief DataBase::createDeviceTable В данном случае используется формирование - * сырого SQL-запроса с последующим его выполнением. - */ -bool DataBase::createDeviceTable() -{ - QSqlQuery query; - if(!query.exec( "CREATE TABLE " + tableNameDB + " (" - "id INTEGER PRIMARY KEY AUTOINCREMENT, " - + nameColumn1DB + " STRING NOT NULL," - + nameColumn2DB + " FLOAT NOT NULL," - + nameColumn3DB + " FLOAT NOT NULL" - " )" - )){ - qDebug() << "DataBase: error of create " << tableNameDB; - qDebug() << query.lastError().text(); - return false; - } else { - return true; - } - return false; -} - -bool DataBase::inserIntoDeviceTable(QString str, float value1, float value2) -{ - QSqlQuery query; - - query.prepare("INSERT INTO " + tableNameDB + " ( " + nameColumn1DB + ", " - + nameColumn2DB + ", " + nameColumn3DB + " ) " - "VALUES (?, ?, ?)"); - - query.addBindValue(str); - query.addBindValue(value1); - query.addBindValue(value2); - - if(!query.exec()){ - qDebug() << "error insert into " << tableNameDB; - qDebug() << query.lastError().text(); - return false; - } else { - return true; - } - return false; -} - -void DataBase::createTable(QTableWidget* table) -{ - table->setColumnCount(3); // Указываем число колонок - table->setShowGrid(true); // Включаем сетку - // Разрешаем выделение только одного элемента - table->setSelectionMode(QAbstractItemView::SingleSelection); - // Разрешаем выделение построчно - table->setSelectionBehavior(QAbstractItemView::SelectRows); - // Устанавливаем заголовки колонок - table->setHorizontalHeaderLabels(QStringList() << nameColumn1DB - << nameColumn2DB - << nameColumn3DB - ); - // Обновляем ширину столбцов - table->resizeColumnsToContents(); -} diff --git a/UMAS_GUI-develop/ui_utils/database.h b/UMAS_GUI-develop/ui_utils/database.h deleted file mode 100755 index 536f4d3..0000000 --- a/UMAS_GUI-develop/ui_utils/database.h +++ /dev/null @@ -1,98 +0,0 @@ -#ifndef DATABASE_H -#define DATABASE_H - -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -/* Директивы имен таблицы, полей таблицы и базы данных */ - -#define DATABASE_NAME "dataIMU_magn.db" - -#define TABLENAME "IMUDATA_magn" -#define TIME "Time" -#define DATAIMU_MAGN_X "Magn_x" -#define DATAIMU_MAGN_Y "Magn_y" - -/*! - * \brief DataBase class вспомогательный класс для работы с таблицами и базами данных. - */ -class DataBase : public QObject -{ - Q_OBJECT -public: - /*! - * \brief DataBase конструктор класса, определяет структуру ДБ. - * \param name название файла ".db". - * \param tableName название таблицы. - * \param nameColumn1 название первой колонки. - * \param nameColumn2 название второй колонки. - * \param nameColumn3 название третей колонки. - */ - explicit DataBase(QString name, - QString tableName, - QString nameColumn1, QString nameColumn2, QString nameColumn3, - QObject *parent = 0); - ~DataBase(); - - /*! - * \brief connectToDataBase метод подключение к ДБ. - */ - void connectToDataBase(); - /*! - * \brief inserIntoDeviceTable метод заполнения ДБ - * \param str строка для первой колонки - * \param value1 значение для второй колонки. - * \param value2 значение для третей колонки. - * \return false в случае неудачи. - */ - bool inserIntoDeviceTable(QString str, float value1, float value2); - /*! - * \brief createTable метод созания таблицы в QTableWidget. - * \param table указатель на QTableWidget. - */ - void createTable(QTableWidget* table); - - -private: - /*! - * \brief db объект базы данных, с которым будет производиться работа - */ - QSqlDatabase db; - - QString nameDB; - QString tableNameDB; - QString nameColumn1DB; - QString nameColumn2DB; - QString nameColumn3DB; - -private: - /*! - * \brief openDataBase метод открытия ДБ. - * \return false в случае неудачи. - */ - bool openDataBase(); - /*! - * \brief restoreDataBase метод восстановления ДБ. - * \return false в случае неудачи. - */ - bool restoreDataBase(); - /*! - * \brief closeDataBase метод закрытия ДБ. - */ - void closeDataBase(); - /*! - * \brief createDeviceTable метод создания таблицы в ДБ. - * \return false в случае неудачи. - */ - bool createDeviceTable(); -}; - -#endif // DATABASE_H diff --git a/UMAS_GUI-develop/ui_utils/list_uwb.db b/UMAS_GUI-develop/ui_utils/list_uwb.db deleted file mode 100755 index 5e3910b..0000000 Binary files a/UMAS_GUI-develop/ui_utils/list_uwb.db and /dev/null differ diff --git a/UMAS_GUI-develop/ui_utils/setup_imu.cpp b/UMAS_GUI-develop/ui_utils/setup_imu.cpp deleted file mode 100755 index fd44192..0000000 --- a/UMAS_GUI-develop/ui_utils/setup_imu.cpp +++ /dev/null @@ -1,26 +0,0 @@ -#include "setup_imu.h" -#include "ui_setup_imu.h" - -SetupIMU::SetupIMU(QWidget *parent) : - QDialog(parent), - ui(new Ui::SetupIMU) -{ - ui->setupUi(this); - - connect( - ui->pushButton_setupIMU_nextStep1, SIGNAL(clicked()), - this, SLOT(setupIMU_nextStep1())); -} - -SetupIMU::~SetupIMU() -{ - delete ui; -} - -void SetupIMU::setupIMU_nextStep1() -{ - hide(); - SetupIMU_start window_setupIMU_start; - window_setupIMU_start.setModal(true); - window_setupIMU_start.exec(); -} diff --git a/UMAS_GUI-develop/ui_utils/setup_imu.h b/UMAS_GUI-develop/ui_utils/setup_imu.h deleted file mode 100755 index 9eecdf0..0000000 --- a/UMAS_GUI-develop/ui_utils/setup_imu.h +++ /dev/null @@ -1,38 +0,0 @@ -#ifndef SETUP_IMU_H -#define SETUP_IMU_H - -#include -#include "setupimu_start.h" -#include "ui_setupimu_start.h" -#include "i_user_interface_data.h" - -namespace Ui { -class SetupIMU; -} - -/*! - * \brief SetupIMU class класс UI формы подготовки к настройке БСО. - */ -class SetupIMU : public QDialog -{ - Q_OBJECT - -public: - explicit SetupIMU(QWidget *parent = nullptr); - ~SetupIMU(); - -public slots: - /*! - * \brief setupIMU_nextStep1 слот открытия окна старта настройки БСО. - */ - void setupIMU_nextStep1(); - - -private: - /*! - * \brief ui окно этой формы. - */ - Ui::SetupIMU *ui; -}; - -#endif // SETUP_IMU_H diff --git a/UMAS_GUI-develop/ui_utils/setup_imu.ui b/UMAS_GUI-develop/ui_utils/setup_imu.ui deleted file mode 100755 index 3814438..0000000 --- a/UMAS_GUI-develop/ui_utils/setup_imu.ui +++ /dev/null @@ -1,67 +0,0 @@ - - - SetupIMU - - - true - - - - 0 - 0 - 400 - 300 - - - - Настройка БСО - - - - - - - - - 0 - 0 - - - - Переведите устройство в горизонтальное положение - - - true - - - - - - - - - - - - 0 - 0 - - - - Qt::LeftToRight - - - false - - - Следующий шаг - - - - - - - - - - diff --git a/UMAS_GUI-develop/ui_utils/setupimu_check.cpp b/UMAS_GUI-develop/ui_utils/setupimu_check.cpp deleted file mode 100755 index 8e40a57..0000000 --- a/UMAS_GUI-develop/ui_utils/setupimu_check.cpp +++ /dev/null @@ -1,238 +0,0 @@ -#include "setupimu_check.h" -#include "ui_setupimu_check.h" - - -SetupIMU_check::SetupIMU_check(QWidget *parent) : - QDialog(parent), - ui(new Ui::SetupIMU_check) -{ - ui->setupUi(this); - - ui->pushButton_setupIMU_check_stop->setEnabled(false); - ui->pushButton_setupIMU_check_pause->setEnabled(false); - ui->pushButton_setupIMU_check_reset->setEnabled(false); - - - db = new DataBase("dataIMU_magn.db", "IMUDATA_magn", "Time", "Magn_x", "Magn_y"); - db->connectToDataBase(); - db->createTable(ui->tableWidget); - - this->createPlot(); - - - connect( - ui->pushButton_setupIMU_check_start, SIGNAL(clicked()), - this, SLOT(startCheck())); - - connect( - ui->pushButton_setupIMU_check_reset, SIGNAL(clicked()), - this, SLOT(resetTable())); - - connect( - ui->pushButton_setupIMU_check_stop, SIGNAL(clicked()), - this, SLOT(stopCheck())); - -} - -SetupIMU_check::~SetupIMU_check() -{ - delete ui; -} - -void SetupIMU_check::startCheck() -{ - time = ui->spinBox_time->value(); - periodicity = ui->doubleSpinBox_periodicity->value(); - i = 0; - - - if (time && periodicity) - { - ui->pushButton_setupIMU_check_start->setEnabled(false); - ui->pushButton_setupIMU_check_stop->setEnabled(true); - ui->pushButton_setupIMU_check_pause->setEnabled(true); - - rowCount_beforeStart = ui->tableWidget->rowCount(); - - timer_updateUI_check = new QTimer(this); - connect( - timer_updateUI_check, SIGNAL(timeout()), - this, SLOT(updateUI_table())); - timer_updateUI_check->start(periodicity*1000); - - ui->label_setupIMU_check_timer->setNum(time); - - timer_setupIMU_check = new QTimer(this); - connect( - timer_setupIMU_check, SIGNAL(timeout()), - this, SLOT(timer_setupIMU_check_timeStart())); - timer_setupIMU_check->start(1000); - } - else - qInfo() << "Необходимо выставить длительность и периодичность записи"; -} - -void SetupIMU_check::timer_setupIMU_check_timeStart() -{ - ui->label_setupIMU_check_timer->setNum(--time); - if (time == 0) { - timer_setupIMU_check->stop(); - timer_updateUI_check->stop(); - ui->pushButton_setupIMU_check_reset->setEnabled(true); - ui->pushButton_setupIMU_check_start->setEnabled(true); - - ui->pushButton_setupIMU_check_pause->setEnabled(false); - ui->pushButton_setupIMU_check_stop->setEnabled(false); - - updateUI_setPlot(); - } -} - -void SetupIMU_check::updateUI_table() -{ - DataAH127C imuData = uv_interface.getImuData(); - float X_magn = imuData.X_magn; - float Y_magn = imuData.Y_magn; - - QString currentTime = QTime::currentTime().toString("HH:mm:ss"); - - db->inserIntoDeviceTable(currentTime, X_magn, Y_magn); - - QSqlQuery query("SELECT " - TABLENAME "." TIME ", " - TABLENAME "." DATAIMU_MAGN_X ", " - TABLENAME "." DATAIMU_MAGN_Y - " FROM " TABLENAME); - query.last(); - ui->tableWidget->insertRow(i + rowCount_beforeStart); - ui->tableWidget->setItem(i + rowCount_beforeStart, 0, new QTableWidgetItem(query.value(0).toString())); - ui->tableWidget->setItem(i + rowCount_beforeStart, 1, new QTableWidgetItem(query.value(1).toString())); - ui->tableWidget->setItem(i + rowCount_beforeStart, 2, new QTableWidgetItem(query.value(2).toString())); - i++; - - ui->tableWidget->resizeColumnsToContents(); -} - -void SetupIMU_check::resetTable() -{ - ui->pushButton_setupIMU_check_reset->setEnabled(false); - ui->pushButton_setupIMU_check_start->setEnabled(true); - - int rowCount = ui->tableWidget->rowCount(); - for (int r = rowCount; r >= 0; r--) - ui->tableWidget->removeRow(r); -} - -void SetupIMU_check::stopCheck() -{ - timer_setupIMU_check->stop(); - timer_updateUI_check->stop(); - ui->pushButton_setupIMU_check_reset->setEnabled(true); - ui->pushButton_setupIMU_check_start->setEnabled(true); - - ui->pushButton_setupIMU_check_pause->setEnabled(false); - ui->pushButton_setupIMU_check_stop->setEnabled(false); - - resetTable(); -} - -void SetupIMU_check::createPlot() -{ - // Построить ряд как источник данных диаграммы и добавить к нему 6 координатных точек - series = new QSplineSeries; - - // Построить график - chart = new QChart(); - chart->legend()->hide(); // скрыть легенду - chart->addSeries(series); // добавить серию на график - chart->setTitle("Построение магнитной характеристики"); // Устанавливаем заголовок графика - - QValueAxis *axisX = new QValueAxis(); - axisX->setTitleText("Magn x"); - axisX->setLabelFormat("%g"); - axisX->setTickCount(5); - chart->addAxis(axisX, Qt::AlignBottom); - series->attachAxis(axisX); - - QValueAxis *axisY = new QValueAxis(); - axisY->setTitleText("Magn y"); - axisY->setLabelFormat("%g"); - axisY->setTickCount(5); - chart->addAxis(axisY, Qt::AlignLeft); - series->attachAxis(axisY); - - // Создаем QChartView и устанавливаем сглаживание, заголовок, размер - chartView = new QChartView(chart); - - // Добавляем его в горизонтальный Layout - ui->verticalLayout_map->addWidget(chartView); - chartView->setRenderHint(QPainter::Antialiasing); -} - -void SetupIMU_check::updateUI_setPlot() -{ - ui->verticalLayout_map->removeWidget(chartView); - - series = new QSplineSeries; - - float magnX_max = 0; - float magnY_max = 0; - float magnX_min = 0; - float magnY_min = 0; - - for (int r = 0; r < ui->tableWidget->rowCount(); r++) - { - QString magn_x = ui->tableWidget->item(r,1)->text(); - QString magn_y = ui->tableWidget->item(r,2)->text(); - - if (magnX_max < magn_x.toFloat()) - magnX_max = magn_x.toFloat(); - if (magnY_max < magn_y.toFloat()) - magnY_max = magn_y.toFloat(); - if (magnX_min > magn_x.toFloat()) - magnX_min = magn_x.toFloat(); - if (magnY_min > magn_y.toFloat()) - magnY_min = magn_y.toFloat(); - - series->append(magn_x.toFloat() , magn_y.toFloat()); - } - - QString magn_x = ui->tableWidget->item(0,1)->text(); - QString magn_y = ui->tableWidget->item(0,2)->text(); - - series->append(magn_x.toFloat() , magn_y.toFloat()); - - float bb_x = (magnX_max-magnX_min) * 0.1; - float bb_y = (magnY_max-magnY_min) * 0.1; - - - // Построить график - chart = new QChart(); - chart->legend()->hide(); // скрыть легенду - chart->addSeries(series); // добавить серию на график - chart->setTitle("Построение магнитной характеристики"); // Устанавливаем заголовок графика - - QValueAxis *axisX = new QValueAxis(); - axisX->setTitleText("Magn x"); - axisX->setLabelFormat("%g"); - axisX->setTickCount(5); - axisX->setRange(magnX_min - bb_x , magnX_max + bb_x); - chart->addAxis(axisX, Qt::AlignBottom); - series->attachAxis(axisX); - - QValueAxis *axisY = new QValueAxis(); - axisY->setTitleText("Magn y"); - axisY->setLabelFormat("%g"); - axisY->setTickCount(5); - axisY->setRange(magnY_min - bb_y, magnY_max + bb_y); - chart->addAxis(axisY, Qt::AlignLeft); - series->attachAxis(axisY); - - // Создаем QChartView и устанавливаем сглаживание, заголовок, размер - chartView = new QChartView(chart); - - // Добавляем его в горизонтальный Layout - ui->verticalLayout_map->addWidget(chartView); - chartView->setRenderHint(QPainter::Antialiasing); - -} diff --git a/UMAS_GUI-develop/ui_utils/setupimu_check.h b/UMAS_GUI-develop/ui_utils/setupimu_check.h deleted file mode 100755 index 4dabfe6..0000000 --- a/UMAS_GUI-develop/ui_utils/setupimu_check.h +++ /dev/null @@ -1,128 +0,0 @@ -#ifndef SETUPIMU_CHECK_H -#define SETUPIMU_CHECK_H - -#include -#include -#include -#include - - -#include - - -#include -#include -#include -#include -#include -#include -#include - -#include - -#include - -#include - -#include "database.h" -#include "i_user_interface_data.h" - -namespace Ui { -class SetupIMU_check; -} -using namespace QtCharts; - -/*! - * \brief SetupIMU_check class класс проверки настройки БСО. - */ -class SetupIMU_check : public QDialog -{ - Q_OBJECT - -public: - explicit SetupIMU_check(QWidget *parent = nullptr); - ~SetupIMU_check(); - - -private slots: - /*! - * \brief startCheck слот старта проверки. - */ - void startCheck(); - /*! - * \brief timer_setupIMU_check_timeStart слот окончания записи данных и - * и последующего построения графиков - */ - void timer_setupIMU_check_timeStart(); - /*! - * \brief updateUI_table слот заполнения таблицы. - */ - void updateUI_table(); - /*! - * \brief resetTable слот очистки таблицы. - */ - void resetTable(); - /*! - * \brief stopCheck слот окончания проверки и стерания данных. - */ - void stopCheck(); - - -private: - /*! - * \brief ui указатель на форму проверки настройки БСО. - */ - Ui::SetupIMU_check *ui; - - /*! - * \brief timer_setupIMU_check таймер окончания записи данных и - * и последующего построения графиков - */ - QTimer *timer_setupIMU_check; - /*! - * \brief timer_updateUI_check таймер заполнения таблицы. - */ - QTimer *timer_updateUI_check; - - /*! - * \brief time длительность записи. - */ - float time; - /*! - * \brief periodicity периодичность записи данныз - */ - float periodicity; - /*! - * \brief количество строк в таблице. - */ - int i; - /*! - * \brief rowCount_beforeStart количество строк в таблице до начала записи. - */ - int rowCount_beforeStart; - - /*! - * \brief uv_interface получения данных - */ - IUserInterfaceData uv_interface; - - /*! - * \brief db база данных для хранения значений магнитометров. - */ - DataBase *db; - - QChart *chart; - QChartView *chartView; - QSplineSeries *series; - - /*! - * \brief createPlot метод построение графика. - */ - void createPlot(); - /*! - * \brief updateUI_setPlot метод повторного построение графика. - */ - void updateUI_setPlot(); -}; - -#endif // SETUPIMU_CHECK_H diff --git a/UMAS_GUI-develop/ui_utils/setupimu_check.ui b/UMAS_GUI-develop/ui_utils/setupimu_check.ui deleted file mode 100755 index 6ecb0a6..0000000 --- a/UMAS_GUI-develop/ui_utils/setupimu_check.ui +++ /dev/null @@ -1,196 +0,0 @@ - - - SetupIMU_check - - - - 0 - 0 - 920 - 613 - - - - Проверка настройки БСО - - - - - - - - - - Введите данные для -проверки настройки БСО - - - - - - - Qt::Horizontal - - - - - - - - - Длительность, с: - - - - - - - 5 - - - - - - - Периодичность записи, с: - - - - - - - 1.000000000000000 - - - - - - - - - Qt::Horizontal - - - - - - - Установите аппарат в -горизонтальное положение. - - - - - - - Qt::Horizontal - - - - - - - Начать запись - - - - - - - - - Приостановить - - - - - - - Завершить - - - - - - - - - Qt::Horizontal - - - - - - - Поворачивайте вокруг -вертикальной оси. - - - - - - - Qt::Horizontal - - - - - - - - - До окончания записи: - - - - - - - - 0 - 0 - - - - 0 - - - - - - - Qt::Horizontal - - - - - - - - - Qt::Horizontal - - - - - - - - - - Очистить значения - - - - - - - - - - - - - - - diff --git a/UMAS_GUI-develop/ui_utils/setupimu_start.cpp b/UMAS_GUI-develop/ui_utils/setupimu_start.cpp deleted file mode 100755 index b1c4014..0000000 --- a/UMAS_GUI-develop/ui_utils/setupimu_start.cpp +++ /dev/null @@ -1,125 +0,0 @@ -#include "setupimu_start.h" -#include "ui_setupimu_start.h" - -SetupIMU_start::SetupIMU_start(QWidget *parent) : - QDialog(parent), - ui(new Ui::SetupIMU_start) -{ - ui->setupUi(this); - ui->pushButton_setupIMU_end->setEnabled(false); - - - connect( - ui->pushButton_setupIMU_startTimer, SIGNAL(clicked()), - this, SLOT(pushButton_startTimer1())); - connect( - this, SIGNAL(on_t2()), - this, SLOT(pushButton_startTimer2())); - connect( - ui->pushButton_setupIMU_end, SIGNAL(clicked()), - this, SLOT(close())); -} - -SetupIMU_start::~SetupIMU_start() -{ - delete ui; -} - -void SetupIMU_start::pushButton_startTimer1() -{ - flagAH127C_pult.initCalibration = true; - uv_interface.setFlagAH127C_pult(flagAH127C_pult); - - timer_checkFlag = new QTimer(this); - connect( - timer_checkFlag, SIGNAL(timeout()), - this, SLOT(isCheckedFlagBort_start())); - timer_checkFlag->start(1000); -} - -void SetupIMU_start::isCheckedFlagBort_start() -{ - flagAH127C_bort = uv_interface.getFlagAH127C_bort(); - if(flagAH127C_bort.startCalibration) - { - timer_checkFlag->stop(); - flagAH127C_pult.initCalibration = false; - uv_interface.setFlagAH127C_pult(flagAH127C_pult); - - ui->pushButton_setupIMU_startTimer->setEnabled(false); - ui->SetupIMU_start_statusBar->setStyleSheet("color: rgb(0, 153, 76)"); - ui->SetupIMU_start_statusBar->setText("Равномерно поворачивайте аппарат вокруг вертикали 2 раза за 30 секунд"); - - updateTimerSec = new QTimer(this); - connect( - updateTimerSec, SIGNAL(timeout()), - this, SLOT(updateUi_sec_t1()) - ); - updateTimerSec->start(1000); - } - else - { - ui->SetupIMU_start_statusBar->setStyleSheet("color: rgb(255, 0, 0)"); - ui->SetupIMU_start_statusBar->setText("Ожидаение подтверждения настройки от БСО"); - } -} - -void SetupIMU_start::updateUi_sec_t1() -{ - ui->label_setupIMU_timer1->setText(QString::number(--sec)); - if (sec == 0) { - sec = 30; - updateTimerSec->stop(); - emit on_t2(); - } -} - -void SetupIMU_start::pushButton_startTimer2() -{ - ui->SetupIMU_start_statusBar->setStyleSheet("color: rgb(0, 153, 76)"); - ui->SetupIMU_start_statusBar->setText("Теперь вокруг оси вращения 2 раза за 30 секунд"); - - updateTimerSec = new QTimer(this); - connect( - updateTimerSec, SIGNAL(timeout()), - this, SLOT(updateUi_sec_t2()) - ); - updateTimerSec->start(1000); - -} - -void SetupIMU_start::updateUi_sec_t2() -{ - ui->label_setupIMU_timer2->setText(QString::number(--sec)); - if (sec == 0) - { - updateTimerSec->stop(); - flagAH127C_pult.saveCalibration = true; - uv_interface.setFlagAH127C_pult(flagAH127C_pult); - - timer_checkFlag = new QTimer(this); - connect( - timer_checkFlag, SIGNAL(timeout()), - this, SLOT(isCheckedFlagBort_end())); - timer_checkFlag->start(1000); - } -} - -void SetupIMU_start::isCheckedFlagBort_end() -{ - flagAH127C_bort = uv_interface.getFlagAH127C_bort(); - if(flagAH127C_bort.endCalibration) - { - timer_checkFlag->stop(); - flagAH127C_pult.saveCalibration = false; - uv_interface.setFlagAH127C_pult(flagAH127C_pult); - - ui->pushButton_setupIMU_end->setEnabled(true); - ui->SetupIMU_start_statusBar->setStyleSheet("color: rgb(0, 153, 76)"); - ui->SetupIMU_start_statusBar->setText("Данные сохранились, можно завершать настройку "); - } else { - ui->SetupIMU_start_statusBar->setStyleSheet("color: rgb(255, 0, 0)"); - ui->SetupIMU_start_statusBar->setText("Данные сохраняются"); - } -} - diff --git a/UMAS_GUI-develop/ui_utils/setupimu_start.h b/UMAS_GUI-develop/ui_utils/setupimu_start.h deleted file mode 100755 index 4c9858a..0000000 --- a/UMAS_GUI-develop/ui_utils/setupimu_start.h +++ /dev/null @@ -1,90 +0,0 @@ -#ifndef SETUPIMU_START_H -#define SETUPIMU_START_H - -#include -#include -#include - -#include "i_user_interface_data.h" - -namespace Ui { -class SetupIMU_start; -} - -/*! - * \brief SetupIMU_start class класс настройки БСО. - */ -class SetupIMU_start : public QDialog -{ - Q_OBJECT - -public: - /*! - * \brief SetupIMU_start конструктор, в котором задаются начальные настройки - * интерфейса и подключаются слоты. - */ - explicit SetupIMU_start(QWidget *parent = nullptr); - ~SetupIMU_start(); - - -private slots: - /*! - * \brief pushButton_startTimer1 слот старта настройки и запуска таймера. - * Срабатывает по нажатию кнопки. - */ - void pushButton_startTimer1(); - /*! - * \brief pushButton_startTimer2 слот старта второго таймера. - */ - void pushButton_startTimer2(); - /*! - * \brief updateUi_sec_t1 слот отчета первого таймера. - */ - void updateUi_sec_t1(); - /*! - * \brief updateUi_sec_t2 слот отчета второго таймера и сохранение результатов. - */ - void updateUi_sec_t2(); - - /*! - * \brief isCheckedFlagBort_start слот проверки начала настройки от БСО. - */ - void isCheckedFlagBort_start(); - /*! - * \brief isCheckedFlagBort_end слот проверки сохранения данных настройки. - */ - void isCheckedFlagBort_end(); - -signals: - /*! - * \brief on_t2 сигнал запуска второго таймера. - */ - void on_t2(); - -private: - /*! - * \brief ui указатель на форму настройки БСО. - */ - Ui::SetupIMU_start *ui; - /*! - * \brief uv_interface интерфейс получения приходящих на аппарат данных - */ - IUserInterfaceData uv_interface; - /*! - * \brief flagAH127C_pult флаги старта и окончания настройки. - */ - FlagAH127C_pult flagAH127C_pult; - /*! - * \brief flagAH127C_bort флаги подтверждения старта и сохранения данных - * после окончания настройки. - */ - FlagAH127C_bort flagAH127C_bort; - - QTimer *updateTimerSec; - QTimer *timer_checkFlag; - - int sec = 30; - -}; - -#endif // SETUPIMU_START_H diff --git a/UMAS_GUI-develop/ui_utils/setupimu_start.ui b/UMAS_GUI-develop/ui_utils/setupimu_start.ui deleted file mode 100755 index ed48d64..0000000 --- a/UMAS_GUI-develop/ui_utils/setupimu_start.ui +++ /dev/null @@ -1,172 +0,0 @@ - - - SetupIMU_start - - - - 0 - 0 - 773 - 304 - - - - Инструкция настройки БСО - - - - - - - - image: url(:/img/setupIMU_for_agent.png); - - - - - - - - - - - - - - - - - 0 - 0 - - - - 1. Поверните аппарат вокруг - оси Z 2 раза за 30 с. - - - false - - - - - - - - 0 - 0 - - - - 2. Поверните аппарат вокруг -оси X 2 раза за 30 с. - - - false - - - - - - - - - - - - 0 - 0 - - - - Qt::LeftToRight - - - false - - - 30 - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - Qt::LeftToRight - - - false - - - 30 - - - Qt::AlignCenter - - - - - - - - - - 0 - 0 - - - - запустить -таймеры - - - - - - - - - - 0 - 0 - - - - Qt::LeftToRight - - - false - - - Завершить настройку - - - - - - - - - - - - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - - - - - diff --git a/UMAS_GUI-develop/uv/uv_state.cpp b/UMAS_GUI-develop/uv/uv_state.cpp deleted file mode 100755 index 93ea545..0000000 --- a/UMAS_GUI-develop/uv/uv_state.cpp +++ /dev/null @@ -1,55 +0,0 @@ -#include "uv_state.h" - -UVState::UVState() -{ - modeAUV_selection = true; - cSMode = e_CSMode::MODE_MANUAL; - - controlContoursFlags.depth = 1; - controlContoursFlags.lag = 1; - controlContoursFlags.march = 1; - controlContoursFlags.pitch = 1; - controlContoursFlags.roll = 1; - controlContoursFlags.yaw = 1; - - pMode = power_Mode::MODE_2; - - - -} - -ControlData::ControlData() { - yaw = 0; - pitch = 0; - roll = 0; - march = 0; - depth = 0; - lag = 0; - offPower = 0; -} - -ControlContoursFlags::ControlContoursFlags() { - yaw = 1; - pitch = 1; - roll = 1; - march = 1; - depth = 1; - lag = 1; -} - -DataPressure::DataPressure() { //структура данных с датчика давления - temperature = 0; //Temperature returned in deg C. - depth = 0; //Depth returned in meters - pressure = 0; // Pressure returned in mbar or mbar*conversion rate. -} - -//DataUWB::DataUWB() { -// locationX = 0; -// locationY = 0; - -// for (int i = 0; i < 5; i++) -// distanceToBeacon [i] = 0; - -// for (int i = 0; i < 11; i++) -// distanceToAgent [i] = 0; -//} diff --git a/UMAS_GUI-develop/uv/uv_state.h b/UMAS_GUI-develop/uv/uv_state.h deleted file mode 100755 index 104dc6d..0000000 --- a/UMAS_GUI-develop/uv/uv_state.h +++ /dev/null @@ -1,279 +0,0 @@ -#ifndef UVSTATE_H -#define UVSTATE_H - -#include -#include - -/*! - * \brief e_CSMode enum класс режимов работы системы управления. - */ -enum class e_CSMode : quint8 { - MODE_MANUAL = 0, //! Ручной - MODE_AUTOMATED, //! Автоматизированный - MODE_AUTOMATIC, //! Автоматический - MODE_GROUP //! Групповой -}; - -/*! - * \brief e_StabilizationContours enum класс для работы с замыканием и - * размыканием контуров управления. - */ -enum class e_StabilizationContours : unsigned char { - CONTOUR_DEPTH = 0, - CONTOUR_MARCH, - CONTOUR_LAG, - CONTOUR_YAW, - CONTOUR_ROLL, - CONTOUR_PITCH -}; - -/*! - * \brief power_Mode enum класс режимов работы системы питания. - */ -enum class power_Mode : quint8 -{ //режим работы - MODE_2 = 0, //! Включены вычислитель, wifi, uwb - MODE_3, //! Включены вычислитель, wifi, uwb, гидроакустика - MODE_4, //! Включены вычислитель, wifi, uwb, гидроакустика, ВМА - MODE_5 //! Выключить вычислитель на 5 секунд и включить обратно -}; - -#pragma pack(push,1) - -/*! - * \brief The mission_Control enum - команды управления миссией - */ -enum class mission_Control : quint8 -{ - MODE_IDLE = 0, //!ожидание - MODE_START, //!отправка запроса на выполнение миссии - MODE_CANCEL, //!отмена выполнения миссии - MODE_STOP, //!пауза, остановить временно - MODE_COMPLETE //!завершить миссию -}; - -/*! - * \brief The mission_Status enum состояния миссий - */ -enum class mission_Status : quint8 -{ - MODE_IDLE = 0, //!ожидание - MODE_ERROR, //!ошибка инициализации миссии - MODE_RUNNING, //!миссия запущена и выполняется - MODE_STOPPED, //!миссия приостановлена, на паузе - MODE_PERFOMED, //!миссия завершена -}; - - -/*! - * \brief FlagAH127C_bort class структура, передаваемая на пульт. - * Используется для калибровки БСО. - */ -struct FlagAH127C_bort -{ - quint8 startCalibration = false; //! Флаг подтверждает старт калибровки. - quint8 endCalibration = false; //! Флаг подтверждает завершение калибровки. -}; - -/*! - * \brief The FlagAH127C_pult class структура, передаваемая на агента. - * Используется для калибровки БСО. - */ -struct FlagAH127C_pult -{ - quint8 initCalibration = false; //! Флаг запуска калибровки. - quint8 saveCalibration = false; //! Флаг сохранения калибровки. -}; - -/*! - * \brief ControlData class управляющие воздействия с пульта управления. - */ -struct ControlData { - ControlData(); - float yaw; - float pitch; - float roll; - float march; - float depth; - float lag; - quint8 gripping; - quint8 rotman; - quint8 offPower; -}; - -/*! - * \brief ControlVMA class управляющие воздействия на каждый ВМА. - */ -struct ControlVMA -{ - float VMA1 = 0; - float VMA2 = 0; - float VMA3 = 0; - float VMA4 = 0; - float VMA5 = 0; - float VMA6 = 0; -}; - -/*! - * \brief ControlContoursFlags class структура со значениями замкутости контуров - * (если 1, то замкнуты, 0 - разомкнуты). - */ -struct ControlContoursFlags { - ControlContoursFlags(); - quint8 yaw; - quint8 pitch; - quint8 roll; - quint8 march; - quint8 depth; - quint8 lag; -}; - -/*! - * \brief AUVCurrentData class структура, передаваемая на пульт. - * Имеет текущие параметры агента. - */ -struct AUVCurrentData -{ - quint8 modeReal; //! Текущий режим. - ControlContoursFlags controlReal; //! Текущее состояние контуров. - quint8 modeAUV_Real; //! Текущий выбор модель/реальный НПА. - ControlData ControlDataReal; //! Текущие курс, дифферент, крен. - ControlVMA signalVMA_real; //! Управление на ВМА. -}; - -struct Header { - int senderID; - int receiverID; - int msgSize; -}; - -/*! - * \brief DataAH127C class структура данных с датчика БСО. - * Курс измеряется в градусах +/- 180 и т.д. - */ -struct DataAH127C { - - float yaw; - float pitch; - float roll; - - float X_accel; - float Y_accel; - float Z_accel; - - float X_rate; - float Y_rate; - float Z_rate; - - float X_magn; - float Y_magn; - float Z_magn; - - float quat [4]; -}; - -/*! - * \brief DataPressure class структура данных с датчика давления - */ -struct DataPressure { - DataPressure(); - float temperature; //! Temperature returned in deg C. - float depth; //! Depth returned in meters - float pressure; //! Pressure returned in mbar or mbar*conversion rate. -}; - -/*! - * \brief DataUWB class структура данных с UWB модуля. - */ -struct DataUWB -{ - uint16_t error_code = 0; - uint16_t connection_field = 0; - float locationX = 0; //! Координата аппарата по оси X - float locationY = 0; //! Координата аппарата по оси Y - float distanceToBeacon[4]; //! Расстоние до i-го маяка - float distanceToAgent[10]; //! Расстояние до i-го агента -}; - -/*! - * \brief PultUWB class структура данных с выставленным положением маяков. - * Идет от пульта. - */ -struct PultUWB -{ - float beacon_x[3]; - float beacon_y[3]; -}; - -/*! - * \brief ToPult class структура данных, принимаемых на пульте. - */ -struct ToPult -{ - ToPult(int auvID=0) - { - header.senderID = auvID; - header.receiverID = 0; - header.msgSize = sizeof (ToPult); - } - Header header; - AUVCurrentData auvData; //! Данные о текущих параметрах - DataAH127C dataAH127C; //! Данные с БСО - DataPressure dataPressure; //! Данные с датчика давления - FlagAH127C_bort flagAH127C_bort; //! Флаги для настрой - uint checksum; -}; - -/*! - * \brief FromPult class структура данных, передаваемая из пульта на агент. - */ -struct FromPult -{ - ControlData controlData; //! Данные, которые идут с пульта при замыканиии контуров - e_CSMode cSMode; //! Режим работы - PultUWB pultUWB; //! Флаги для настрой - ControlContoursFlags controlContoursFlags; //! Флаги замыкания контуров (1 - замкнуты) - quint8 modeAUV_selection; //! Текущий выбор модель/реальный НПА - power_Mode pMode; //! Режим работы системы питания - FlagAH127C_pult flagAH127C_pult; - uint checksum; -}; - -#pragma pack (pop) - -/*! - * \brief UVState class класс всех возможных состояний при работе с ПА. - */ -class UVState : public QObject -{ - Q_OBJECT -public: - UVState(); - Header header; - DataAH127C imuData; - DataPressure dataPressure; - DataUWB dataUWB; - PultUWB pultUWB; - - AUVCurrentData auvData; - - FlagAH127C_bort flagAH127C_bort; - FlagAH127C_pult flagAH127C_pult; - - bool modeAUV_selection; - e_CSMode cSMode; - ControlContoursFlags controlContoursFlags; - ControlData control; - power_Mode pMode; - - quint8 ID_mission; - mission_Status missionStatus; - quint8 ID_mission_AUV; - mission_Control missionControl; - - int checksum_msg_gui_send; - int checksum_msg_agent_send; - int checksum_msg_gui_received; -}; - -#endif // UVSTATE_H diff --git a/interface/i_user_interface_data.cpp b/interface/i_user_interface_data.cpp index 1e83804..8e2ce9b 100644 --- a/interface/i_user_interface_data.cpp +++ b/interface/i_user_interface_data.cpp @@ -19,7 +19,7 @@ void IUserInterfaceData::setFlagAH127C_pult(FlagAH127C_pult flagAH127C_pult) void IUserInterfaceData::setPowerMode(power_Mode mode) { agent[getCurrentAgent()].pMode = mode; - displayText_toConsole("Включен " + QString::number(static_cast(mode) + 2) + " режим питания"); + //displayText_toConsole("Включен " + QString::number(static_cast(mode) + 2) + " режим питания"); } void IUserInterfaceData::setControlContoursFlags(e_StabilizationContours contour, bool value) { diff --git a/mainwindow.cpp b/mainwindow.cpp index 6de2047..42c1c06 100644 --- a/mainwindow.cpp +++ b/mainwindow.cpp @@ -17,7 +17,6 @@ MainWindow::MainWindow(QWidget *parent) setUpdateUI(); } -// void MainWindow::setWidget() { @@ -31,6 +30,8 @@ void MainWindow::setWidget() ui->verticalLayout_modeAutomatic->addWidget(modeAutomatic); diagnostic_board = new Diagnostic_board(this); ui->horizontalLayout_diagnosticBoard->addWidget(diagnostic_board); + videowidget = new Videowidget(this); + ui->horizontalLayout_video->addWidget(videowidget); // setMission_map connect( @@ -216,7 +217,23 @@ void MainWindow::setTimer_updateImpact(int periodUpdateMsec) void MainWindow::useKeyBoard() { - delete joyStick; + + if (joyStick != nullptr) { + qDebug() << "Deleting joyStick"; + delete joyStick; + joyStick = nullptr; + } + + if (keyBoard != nullptr) { + qDebug() << "Deleting existing keyBoard"; + delete keyBoard; + keyBoard = nullptr; + } + + qDebug() << "Creating new keyBoard"; + keyBoard = new KeyBoard(this); + displayText("Используемые клавиши..."); + keyBoard = new KeyBoard(this); displayText("Используемые клавиши(должна быть английская раскладка):\n" @@ -237,7 +254,23 @@ void MainWindow::useKeyBoard() void MainWindow::useJoyStick() { - delete keyBoard; + + if (joyStick != nullptr) { + qDebug() << "Deleting joyStick"; + delete joyStick; + joyStick = nullptr; + } + + if (keyBoard != nullptr) { + qDebug() << "Deleting existing keyBoard"; + delete keyBoard; + keyBoard = nullptr; + } + + qDebug() << "Creating new keyBoard"; + keyBoard = new KeyBoard(this); + displayText("Используемые клавиши..."); + joyStick = new JoyStick(this); } @@ -341,7 +374,7 @@ void MainWindow::setConnection() QString ip_pult = ui->lineEdit_ip_pult->text(); QString ip_agent = ui->lineEdit_ip_agent->text(); communicationAgent1 = new Pult::PC_Protocol(QHostAddress(ip_pult), 13053, - QHostAddress(ip_agent), 13050, 10, 0); + QHostAddress(ip_agent), 13052, 10, 0); communicationAgent1->startExchange(); if (communicationAgent1->bindState()) { @@ -462,7 +495,8 @@ void MainWindow::setTab() ui->tabWidget->setTabText(2, "Контроль сообщений"); ui->tabWidget->setTabText(3, "Режимы питания"); ui->tabWidget->setTabText(4, "Карта ГИC"); - ui->tabWidget->setCurrentIndex(4); + //ui->tabWidget->setCurrentIndex(4); + ui->tabWidget->setTabText(5, "Видео"); //виджет с видео } diff --git a/mainwindow.h b/mainwindow.h index ed5f6e9..3f5e3bb 100644 --- a/mainwindow.h +++ b/mainwindow.h @@ -8,6 +8,11 @@ #include #include +#include +#include +#include + + #include "remote_control.h" #include "uv_state.h" #include "i_user_interface_data.h" @@ -23,6 +28,7 @@ #include "mode_automatic.h" #include "map_widget.h" #include "diagnostic_board.h" +#include "videowidget.h" QT_BEGIN_NAMESPACE @@ -100,6 +106,7 @@ class MainWindow : public QMainWindow ModeAutomatic *modeAutomatic; MapWidget *mapWidget; Diagnostic_board *diagnostic_board; + Videowidget *videowidget; @@ -173,6 +180,9 @@ private slots: void slot_addMarker_to_gui(double x, double y); + //void on_pushButton_Play_Pause_clicked(); + + signals: /*! @@ -236,5 +246,6 @@ private slots: */ RemoteControl pult; + }; #endif // MAINWINDOW_H diff --git a/mainwindow.ui b/mainwindow.ui index ec6b6dc..4621e1c 100644 --- a/mainwindow.ui +++ b/mainwindow.ui @@ -79,7 +79,7 @@ - 192.168.1.7 + 192.168.1.111 100 @@ -118,7 +118,7 @@ - 192.168.1.5 + 192.168.1.11 Qt::AlignCenter @@ -201,7 +201,7 @@ - 0 + 5 @@ -253,6 +253,22 @@ + + + Page + + + + + -1 + 29 + 1081 + 481 + + + + + @@ -582,7 +598,7 @@ 0 0 3840 - 22 + 24 diff --git a/uv/uv_state.h b/uv/uv_state.h index 0097aab..9e9ebc4 100644 --- a/uv/uv_state.h +++ b/uv/uv_state.h @@ -107,6 +107,11 @@ struct ControlData { float march; float depth; float lag; + quint8 gripping = 0; + quint8 opening = 0; + quint8 rotmanlf = 0; + quint8 rotmanrt = 0; + quint8 powoff = 0; }; /*! diff --git a/videowidget/main.cpp b/videowidget/main.cpp deleted file mode 100644 index fd3e533..0000000 --- a/videowidget/main.cpp +++ /dev/null @@ -1,11 +0,0 @@ -#include "mainwindow.h" - -#include - -int main(int argc, char *argv[]) -{ - QApplication a(argc, argv); - MainWindow w; - w.show(); - return a.exec(); -} diff --git a/videowidget/mainwindow.cpp b/videowidget/mainwindow.cpp deleted file mode 100644 index d1c484e..0000000 --- a/videowidget/mainwindow.cpp +++ /dev/null @@ -1,89 +0,0 @@ -// mainwindow.cpp -#include "mainwindow.h" -#include "ui_mainwindow.h" -#include -#include - -MainWindow::MainWindow(QWidget *parent) - : QMainWindow(parent), - ui(new Ui::MainWindow) -{ - ui->setupUi(this); - pipeline = nullptr; // Инициализируем пайплайн как неактивный - - // Инициализация GStreamer - gst_init(nullptr, nullptr); - - // Получаем "внутренний" идентификатор нашего виджета для видео - videoWindowId = ui->videoWidget->winId(); - - ui->pushButton_Play_Pause->setText("Начать прием"); -} - -MainWindow::~MainWindow() -{ - // Корректно останавливаем и освобождать ресурсы при закрытии - if (pipeline) { - gst_element_set_state(pipeline, GST_STATE_NULL); - gst_object_unref(pipeline); - pipeline = nullptr; - } - delete ui; -} - -void MainWindow::on_pushButton_Play_Pause_clicked() -{ - // Отправка видео с Raspberry Pi - QString command = "ssh -X agent1@192.168.1.11 " - "\"gst-launch-1.0 v4l2src device=/dev/video0 ! " - "image/jpeg,width=100,height=100,framerate=30/1 ! " - "jpegparse ! rtpjpegpay ! udpsink host=192.168.1.6 port=5000\""; - - QProcess *sshProcess = new QProcess(this); - sshProcess->start(command); - - if (!pipeline) { // Если пайплайн не запущен, запускаем его - qDebug() << "Starting pipeline..."; - - // Приём видео на ПК через xvimagesink - const char *pipeline_str = - "udpsrc port=5000 ! application/x-rtp,encoding-name=JPEG,payload=96 ! " - "rtpjpegdepay ! jpegdec ! videoconvert ! xvimagesink name=sink"; - - GError *error = nullptr; - pipeline = gst_parse_launch(pipeline_str, &error); - - if (error) { - qWarning() << "Failed to create pipeline:" << error->message; - g_error_free(error); - return; - } - - // Находим элемент sink и привязываем к нашему QWidget - GstElement *sink = gst_bin_get_by_name(GST_BIN(pipeline), "sink"); - if (!sink) { - qWarning() << "Could not find sink element"; - gst_object_unref(pipeline); - pipeline = nullptr; - return; - } - - if (GST_IS_VIDEO_OVERLAY(sink)) { - gst_video_overlay_set_window_handle(GST_VIDEO_OVERLAY(sink), videoWindowId); - } else { - qWarning() << "Sink is not video overlay capable!"; - } - gst_object_unref(sink); - - // Запускаем пайплайн - gst_element_set_state(pipeline, GST_STATE_PLAYING); - ui->pushButton_Play_Pause->setText("Остановить прием"); - - } else { // Если пайплайн уже работает, останавливаем его - qDebug() << "Stopping pipeline..."; - gst_element_set_state(pipeline, GST_STATE_NULL); - gst_object_unref(pipeline); - pipeline = nullptr; - ui->pushButton_Play_Pause->setText("Начать прием"); - } -} diff --git a/videowidget/mainwindow.h b/videowidget/mainwindow.h deleted file mode 100644 index ab691dd..0000000 --- a/videowidget/mainwindow.h +++ /dev/null @@ -1,34 +0,0 @@ -// mainwindow.h -#ifndef MAINWINDOW_H -#define MAINWINDOW_H - -#include -#include -#include -#include -#include -#include -#include -#include - - -QT_BEGIN_NAMESPACE -namespace Ui { class MainWindow; } -QT_END_NAMESPACE - -class MainWindow : public QMainWindow { - Q_OBJECT - -public: - MainWindow(QWidget *parent = nullptr); - ~MainWindow(); - -private slots: - void on_pushButton_Play_Pause_clicked(); - -private: - Ui::MainWindow *ui; - GstElement *pipeline; - WId videoWindowId; -}; -#endif // MAINWINDOW_H diff --git a/videowidget/mainwindow.ui b/videowidget/mainwindow.ui deleted file mode 100644 index 7765042..0000000 --- a/videowidget/mainwindow.ui +++ /dev/null @@ -1,55 +0,0 @@ - - - MainWindow - - - - 0 - 0 - 800 - 600 - - - - MainWindow - - - - - - 70 - 456 - 121 - 61 - - - - PushButton - - - - - - 50 - 30 - 721 - 391 - - - - - - - - 0 - 0 - 800 - 24 - - - - - - - - diff --git a/videowidget/untitled.pro b/videowidget/untitled.pro deleted file mode 100644 index f4290fa..0000000 --- a/videowidget/untitled.pro +++ /dev/null @@ -1,21 +0,0 @@ -QT += core gui multimedia multimediawidgets - -greaterThan(QT_MAJOR_VERSION, 4): QT += widgets - -CONFIG += link_pkgconfig -PKGCONFIG += gstreamer-1.0 gstreamer-video-1.0 - -SOURCES += \ - main.cpp \ - mainwindow.cpp - -HEADERS += \ - mainwindow.h - -FORMS += \ - mainwindow.ui - -# Default rules for deployment. -qnx: target.path = /tmp/$${TARGET}/bin -else: unix:!android: target.path = /opt/$${TARGET}/bin -!isEmpty(target.path): INSTALLS += target diff --git a/videowidget/videowidget.cpp b/videowidget/videowidget.cpp new file mode 100644 index 0000000..61f7248 --- /dev/null +++ b/videowidget/videowidget.cpp @@ -0,0 +1,143 @@ +#include "videowidget.h" +#include "ui_videowidget.h" + +#include +#include +#include #include +#include + + +Videowidget::Videowidget(QWidget *parent) + : QWidget(parent), + ui(new Ui::Videowidget), + pipeline(nullptr), + pendingStart(false) +{ + ui->setupUi(this); + + gst_init(nullptr, nullptr); + + qDebug() << "Platform:" << QGuiApplication::platformName(); + + connect(ui->pushButton_Play_Pause, &QPushButton::clicked, + this, &Videowidget::togglePipeline); + + // появление winId + ui->videoWidget->installEventFilter(this); + + ui->pushButton_Play_Pause->setText("Начать прием"); +} + +Videowidget::~Videowidget() +{ + if (pipeline) { + gst_element_set_state(pipeline, GST_STATE_NULL); + gst_object_unref(pipeline); + pipeline = nullptr; + } + delete ui; +} + +bool Videowidget::eventFilter(QObject *watched, QEvent *event) +{ + if (watched == ui->videoWidget) { + // QEvent::WinIdChange сработает, когда Qt создаст/изменит winId + if (event->type() == QEvent::WinIdChange) { + qDebug() << "videoWidget WinIdChange event, winId() =" << ui->videoWidget->winId(); + if (pendingStart) { + // как только winId появился — запускаем пайплайн + pendingStart = false; + startPipelineNow(); + } + } + // также можно ловить Show если нужно: + if (event->type() == QEvent::Show) { + qDebug() << "videoWidget Show event, winId() =" << ui->videoWidget->winId(); + if (pendingStart) { + pendingStart = false; + startPipelineNow(); + } + } + } + return QWidget::eventFilter(watched, event); +} + +void Videowidget::togglePipeline() +{ + if (!pipeline) { + // Попробуем принудительно создать winId и windowHandle + ui->videoWidget->createWinId(); // запрос на создание native window + QWindow *w = ui->videoWidget->windowHandle(); + if (!w) { + // окна ещё нет — пометим и дождёмся события WinIdChange (eventFilter) + qDebug() << "No windowHandle yet — deferring pipeline start"; + pendingStart = true; + return; + } + + // если windowHandle уже есть — запускаем здесь + startPipelineNow(); + } else { + // Останов пайплайна + qDebug() << "Stopping pipeline..."; + gst_element_set_state(pipeline, GST_STATE_NULL); + gst_object_unref(pipeline); + pipeline = nullptr; + ui->pushButton_Play_Pause->setText("Начать прием"); + } +} + +void Videowidget::startPipelineNow() +{ + // Здесь гарантированно есть windowHandle / winId + QWindow *window = ui->videoWidget->windowHandle(); + if (!window) { + qWarning() << "startPipelineNow: still no windowHandle!"; + return; + } + + WId wid = window->winId(); + qDebug() << "startPipelineNow: using window id =" << wid; + + // Отправка (ssh) — если нужно + QString command = + "ssh -X agent1@192.168.1.11 " + "\"gst-launch-1.0 v4l2src device=/dev/video0 ! " + "image/jpeg,framerate=30/1 ! " + "jpegparse ! rtpjpegpay ! udpsink host=192.168.1.111 port=5000\""; + + QProcess *sshProcess = new QProcess(this); + sshProcess->start(command); + + // Создаём пайплайн + const char *pipeline_str = + "udpsrc port=5000 ! application/x-rtp,encoding-name=JPEG,payload=96 ! " + "rtpjpegdepay ! jpegdec ! videoconvert ! xvimagesink name=sink"; + + GError *error = nullptr; + pipeline = gst_parse_launch(pipeline_str, &error); + if (error) { + qWarning() << "Failed to create pipeline:" << error->message; + g_error_free(error); + pipeline = nullptr; + return; + } + + GstElement *sink = gst_bin_get_by_name(GST_BIN(pipeline), "sink"); + if (!sink) { + qWarning() << "Could not find sink element"; + gst_object_unref(pipeline); + pipeline = nullptr; + return; + } + + if (GST_IS_VIDEO_OVERLAY(sink)) { + gst_video_overlay_set_window_handle(GST_VIDEO_OVERLAY(sink), (guintptr)wid); + } else { + qWarning() << "Sink is not video overlay capable!"; + } + gst_object_unref(sink); + + gst_element_set_state(pipeline, GST_STATE_PLAYING); + ui->pushButton_Play_Pause->setText("Остановить прием"); +} diff --git a/videowidget/videowidget.h b/videowidget/videowidget.h new file mode 100644 index 0000000..7a3ed7e --- /dev/null +++ b/videowidget/videowidget.h @@ -0,0 +1,38 @@ +#ifndef VIDEOWIDGET_H +#define VIDEOWIDGET_H + +#include +#include +#include +#include +#include +#include +#include + +QT_BEGIN_NAMESPACE +namespace Ui { class Videowidget; } +QT_END_NAMESPACE + +class Videowidget : public QWidget +{ + Q_OBJECT + +public: + explicit Videowidget(QWidget *parent = nullptr); + ~Videowidget(); + +private slots: + void togglePipeline(); + +protected: + bool eventFilter(QObject *watched, QEvent *event) override; + +private: + void startPipelineNow(); // реальное создание/запуск пайплайна + + Ui::Videowidget *ui; + GstElement *pipeline; + bool pendingStart; // ждем winId +}; + +#endif // VIDEOWIDGET_H diff --git a/videowidget/videowidget.ui b/videowidget/videowidget.ui new file mode 100644 index 0000000..3e9fb73 --- /dev/null +++ b/videowidget/videowidget.ui @@ -0,0 +1,42 @@ + + + Videowidget + + + + 0 + 0 + 948 + 596 + + + + Form + + + + + 30 + 20 + 701 + 561 + + + + + + + 740 + 20 + 201 + 571 + + + + PushButton + + + + + +