diff --git a/QOpenHD.pro b/QOpenHD.pro index 28fb86dd0..102e0a0be 100755 --- a/QOpenHD.pro +++ b/QOpenHD.pro @@ -234,6 +234,17 @@ JetsonBuild { WindowsBuild { # This aparently makes qt use absolute paths, otherwise we get compile issues ? QMAKE_PROJECT_DEPTH = 0 + #include(app/videostreaming/gstreamer/gst_video.pri) + #include(app/videostreaming/avcodec/avcodec_video.pri) + # Path to FFmpeg headers + # INCLUDEPATH += C:/ffmpeg + #INCLUDEPATH += C:/ffmpeg/libavutil/ + + # Path to FFmpeg libraries + #LIBS += -LC:/ffmpeg/lib + + # Link against the required FFmpeg libraries + #LIBS += -lavcodec -lavformat -lavutil -lswscale -lswresample } AndroidBuild { diff --git a/app/telemetry/connection/tcp_connection.cpp b/app/telemetry/connection/tcp_connection.cpp index 3773eba14..4c6dfabb3 100644 --- a/app/telemetry/connection/tcp_connection.cpp +++ b/app/telemetry/connection/tcp_connection.cpp @@ -1,85 +1,142 @@ #include "tcp_connection.h" #include "tutil/qopenhdmavlinkhelper.hpp" -#ifdef __windows__ -#define _WIN32_WINNT 0x0600 //TODO dirty +#ifdef _WIN32 +#define _WIN32_WINNT 0x0600 // Windows Vista and above #include -#include // For InetPton +#include #include +#pragma comment(lib, "Ws2_32.lib") #else #include #include #include -#endif #include #include - +#endif #include - #include "mavlinkchannel.h" -static int tcp_socket_try_connect(const std::string remote_ip, const int remote_port,const int timeout_seconds){ - //qDebug()<<"tcp_socket_try_connect:"<(&remote_addr), sizeof(struct sockaddr_in)); - if(connect_result==0){ - qDebug()<<"Got connection immeiately"; + if (inet_pton(AF_INET, remote_ip.c_str(), &remote_addr.sin_addr) <= 0) { + qDebug() << "Invalid address:" << remote_ip.c_str(); +#ifdef _WIN32 + closesocket(sockfd); + WSACleanup(); +#else + close(sockfd); +#endif + return -1; + } + + const int connect_result = connect(sockfd, reinterpret_cast(&remote_addr), sizeof(remote_addr)); + if (connect_result == 0) { + qDebug() << "Connected immediately."; return sockfd; } - if ((connect_result== -1) && (errno != EINPROGRESS)) { - qDebug()<<"Didnt get EINPROGRESS"<<(int)connect_result; +#ifdef _WIN32 + if (connect_result == SOCKET_ERROR && WSAGetLastError() != WSAEWOULDBLOCK) { + qDebug() << "Connection error:" << WSAGetLastError(); + closesocket(sockfd); + WSACleanup(); + return -1; + } +#else + if (connect_result == -1 && errno != EINPROGRESS) { + qDebug() << "Connection error:" << strerror(errno); close(sockfd); return -1; } - // Wait for up to X seconds to connect +#endif + fd_set fdset; - struct timeval tv; FD_ZERO(&fdset); FD_SET(sockfd, &fdset); + + struct timeval tv; tv.tv_sec = timeout_seconds; tv.tv_usec = 0; - const int rc= select(sockfd + 1, NULL, &fdset, NULL, &tv); - if(rc!=1){ - qDebug()<<"Timed out or other crap"; + + const int select_result = select(sockfd + 1, NULL, &fdset, NULL, &tv); + if (select_result != 1) { + qDebug() << "Connection timed out or failed."; +#ifdef _WIN32 + closesocket(sockfd); + WSACleanup(); +#else close(sockfd); +#endif return -1; } - // Check if there are any errors + + // Check for socket errors int so_error; - // data to read socklen_t len = sizeof(so_error); - #ifdef __linux__ +#ifdef _WIN32 + getsockopt(sockfd, SOL_SOCKET, SO_ERROR, reinterpret_cast(&so_error), &len); + if (so_error != 0) { + qDebug() << "Socket error after select:" << WSAGetLastError(); + closesocket(sockfd); + WSACleanup(); + return -1; + } +#else getsockopt(sockfd, SOL_SOCKET, SO_ERROR, &so_error, &len); if (so_error != 0) { - qDebug()<<"Any socket error:"<(&TCPConnection::loop_connect_receive,this); +void TCPConnection::start_looping() { + assert(m_receive_thread == nullptr); + m_keep_receiving = true; + m_receive_thread = std::make_unique(&TCPConnection::loop_connect_receive, this); } -void TCPConnection::stop_looping_if() -{ - if(is_looping())stop_looping(); +void TCPConnection::stop_looping_if() { + if (is_looping()) stop_looping(); } -void TCPConnection::stop_looping() -{ - assert(m_receive_thread!=nullptr); - qDebug()<<"TCPConnection2::stop_receiving begin"; - m_keep_receiving=false; -#ifdef __windows__ - shutdown(m_socket_fd, SD_BOTH); - - closesocket(m_socket_fd); - - WSACleanup(); -#else \ - // This should interrupt a recv/recvfrom call. - shutdown(m_socket_fd, SHUT_RDWR); - // But on Mac, closing is also needed to stop blocking recv/recvfrom. - close(m_socket_fd); +void TCPConnection::stop_looping() { + assert(m_receive_thread != nullptr); + qDebug() << "Stopping connection"; + m_keep_receiving = false; +#ifdef _WIN32 + shutdown(m_socket_fd, SD_BOTH); + closesocket(m_socket_fd); + WSACleanup(); +#else + shutdown(m_socket_fd, SHUT_RDWR); + close(m_socket_fd); #endif - m_receive_thread->join(); - m_receive_thread=nullptr; - qDebug()<<"TCPConnection2::stop_receiving end"; + m_receive_thread->join(); + m_receive_thread = nullptr; + qDebug() << "Connection stopped."; } - - - - -void TCPConnection::send_message(const mavlink_message_t &msg) -{ +void TCPConnection::send_message(const mavlink_message_t& msg) { uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; const int buffer_len = mavlink_msg_to_send_buffer(buffer, &msg); - if(!m_keep_receiving){ + if (!m_keep_receiving) { return; // Otherwise sendto blocks } - if(m_socket_fd<0){ - //qDebug()<<"Cannot send message"; + if (m_socket_fd < 0) { + qDebug() << "Cannot send message: Socket not connected."; return; } - if(!linux_send_message(m_socket_fd,m_remote_ip,m_remote_port,buffer,buffer_len)){ - //qDebug()<<"Cannot send message"; + if (!linux_send_message(m_socket_fd, m_remote_ip, m_remote_port, buffer, buffer_len)) { + qDebug() << "Failed to send MAVLink message."; } } -bool TCPConnection::threadsafe_is_alive() -{ - const int32_t now_ms=QOpenHDMavlinkHelper::getTimeMilliseconds();; - const auto elapsed=now_ms-m_last_data_ms; - return elapsed <= 3*1000; +bool TCPConnection::threadsafe_is_alive() { + const int32_t now_ms = QOpenHDMavlinkHelper::getTimeMilliseconds(); + const auto elapsed = now_ms - m_last_data_ms; + return elapsed <= 3 * 1000; } -void TCPConnection::process_data(const uint8_t *data, int data_len) -{ - m_last_data_ms=QOpenHDMavlinkHelper::getTimeMilliseconds(); +void TCPConnection::process_data(const uint8_t* data, int data_len) { + m_last_data_ms = QOpenHDMavlinkHelper::getTimeMilliseconds(); mavlink_message_t msg; for (int i = 0; i < data_len; i++) { - uint8_t res = mavlink_parse_char(m_mav_channel,data[i], &msg, &m_recv_status); + uint8_t res = mavlink_parse_char(m_mav_channel, data[i], &msg, &m_recv_status); if (res) { process_mavlink_message(msg); } } } -void TCPConnection::process_mavlink_message(mavlink_message_t message) -{ +void TCPConnection::process_mavlink_message(mavlink_message_t message) { m_cb(message); } - -void TCPConnection::receive_until_stopped() -{ - // Enough for MTU 1500 bytes. - auto buffer=std::make_unique>(); - buffer->resize(1500); - //struct timeval tv; - //tv.tv_sec = 3; - //tv.tv_usec = 0; - //setsockopt(m_socket_fd, SOL_SOCKET, SO_RCVTIMEO, (const char*)&tv, sizeof tv); +void TCPConnection::receive_until_stopped() { + auto buffer = std::make_unique>(1500); while (m_keep_receiving) { - const auto elapsed_last_message=QOpenHDMavlinkHelper::getTimeMilliseconds()-m_last_data_ms; - if(elapsed_last_message>3*1000){ - qDebug()<<"No message for more than 3 seconds, disconnecting"; + const auto elapsed_last_message = QOpenHDMavlinkHelper::getTimeMilliseconds() - m_last_data_ms; + if (elapsed_last_message > 3 * 1000) { + qDebug() << "No message for more than 3 seconds, disconnecting."; return; } const auto recv_len = recvfrom( m_socket_fd, - (char*)buffer->data(), + reinterpret_cast(buffer->data()), buffer->size(), 0, nullptr, nullptr); if (recv_len == 0) { - // This can happen when shutdown is called on the socket, - // therefore we check _should_exit again. - //qDebug()<<"Got recv_len==0"; - //return; continue; } if (recv_len < 0) { - // This happens on desctruction when close(_socket_fd) is called, - // therefore be quiet. - // LogErr() << "recvfrom error: " << GET_ERROR(errno); - // Something went wrong, we should try to re-connect in next iteration. - //qDebug()<<"Got recv_len<0 :"<data(),recv_len); + process_data(buffer->data(), recv_len); } } -void TCPConnection::loop_connect_receive() -{ -#ifdef __linux__ - qDebug()<<"TCPConnection2::loop_connect_receive begin"; - while(m_keep_receiving){ - m_socket_fd=tcp_socket_try_connect(m_remote_ip,m_remote_port,3); - if(m_socket_fd>0){ - m_last_data_ms=QOpenHDMavlinkHelper::getTimeMilliseconds(); - receive_until_stopped(); - qDebug()<<"Broke out of receive loop"; - close(m_socket_fd); - m_socket_fd=-1; - }else{ - int count=0; - while(m_keep_receiving && count<3){ - std::this_thread::sleep_for(std::chrono::seconds(1)); - count++; - } - } - } - qDebug()<<"TCPConnection2::loop_connect_receive end"; +void TCPConnection::loop_connect_receive() { + qDebug() << "Starting connection loop."; + while (m_keep_receiving) { + m_socket_fd = tcp_socket_try_connect(m_remote_ip, m_remote_port, 3); + if (m_socket_fd > 0) { + m_last_data_ms = QOpenHDMavlinkHelper::getTimeMilliseconds(); + receive_until_stopped(); + qDebug() << "Exited receive loop."; +#ifdef _WIN32 + closesocket(m_socket_fd); +#else + close(m_socket_fd); #endif + m_socket_fd = -1; + } else { + int count = 0; + while (m_keep_receiving && count < 3) { + std::this_thread::sleep_for(std::chrono::seconds(1)); + count++; + } + } + } + qDebug() << "Connection loop ended."; } diff --git a/app/videostreaming/avcodec/avcodec_video.pri b/app/videostreaming/avcodec/avcodec_video.pri index ef46819a7..4872c9809 100644 --- a/app/videostreaming/avcodec/avcodec_video.pri +++ b/app/videostreaming/avcodec/avcodec_video.pri @@ -1,6 +1,7 @@ INCLUDEPATH += $$PWD +INCLUDEPATH += C:/ffmpeg/include -LIBS += -lavcodec -lavutil -lavformat +LIBS += -LC:/ffmpeg/lib -lavcodec -lavutil -lavformat # TODO dirty LIBS += -lGLESv2 -lEGL diff --git a/app/videostreaming/gstreamer/gst_video.pri b/app/videostreaming/gstreamer/gst_video.pri index cf54f3331..635c7bcf8 100644 --- a/app/videostreaming/gstreamer/gst_video.pri +++ b/app/videostreaming/gstreamer/gst_video.pri @@ -1,8 +1,11 @@ +# Enable GStreamer QMLGLSink for video rendering DEFINES += QOPENHD_ENABLE_GSTREAMER_QMLGLSINK -#DEFINES += QOPENHD_GSTREAMER_PRIMARY_VIDEO +# Uncomment for primary video, keep secondary for now +# DEFINES += QOPENHD_GSTREAMER_PRIMARY_VIDEO DEFINES += QOPENHD_GSTREAMER_SECONDARY_VIDEO +# Sources and headers specific to GStreamer SOURCES += \ $$PWD/gstqmlglsinkstream.cpp \ $$PWD/gstrtpaudioplayer.cpp \ @@ -14,16 +17,14 @@ HEADERS += \ $$PWD/gstrtpaudioplayer.h \ $$PWD/gstrtpreceiver.h -android{ - message("gst android") - # More or less taken from QGroundControl. - # this is already the "least dirty" solution I could come up with :/ - #DOWNLOADED_GST_FOLDER= /home/hyperion/gstreamer-1.0-android-universal-1.20.5 - #DOWNLOADED_GST_FOLDER= /home/consti10/Downloads/gstreamer-1.0-android-universal-1.20.5 - #DOWNLOADED_GST_FOLDER= $$PWD/../../../lib/gstreamer_prebuilts/gstreamer-1.0-android-universal-1.20.5 - DOWNLOADED_GST_FOLDER= $$PWD/../../../lib/gstreamer_prebuilts/gstreamer-1.0-android-universal +# Platform-specific configurations +android { + message("Configuring GStreamer for Android") - # Set the right folder for the compile arch + # Define the base directory for the GStreamer prebuilt binaries + DOWNLOADED_GST_FOLDER = $$PWD/../../../lib/gstreamer_prebuilts/gstreamer-1.0-android-universal + + # Determine the GStreamer architecture folder based on the target architecture GSTREAMER_ARCH_FOLDER = armv7 contains(ANDROID_TARGET_ARCH, armeabi-v7a) { GSTREAMER_ARCH_FOLDER = armv7 @@ -32,69 +33,75 @@ android{ } else:contains(ANDROID_TARGET_ARCH, x86_64) { GSTREAMER_ARCH_FOLDER = x86_64 } else { - message(Unknown ANDROID_TARGET_ARCH $$ANDROID_TARGET_ARCH) + message("Unknown ANDROID_TARGET_ARCH: $$ANDROID_TARGET_ARCH") GSTREAMER_ARCH_FOLDER = armv7 } - #GSTREAMER_ARCH_FOLDER = arm64 - + # Define the root path for GStreamer GSTREAMER_ROOT_ANDROID = $$DOWNLOADED_GST_FOLDER/$$GSTREAMER_ARCH_FOLDER - message(gstreamer root android:) - message($$GSTREAMER_ROOT_ANDROID) + message("GStreamer root for Android: $$GSTREAMER_ROOT_ANDROID") GST_ROOT = $$GSTREAMER_ROOT_ANDROID + + # Check if the GStreamer root directory exists exists($$GST_ROOT) { - message(Doing QGC gstreamer stuff) - message($$GST_ROOT) - QMAKE_CXXFLAGS += -pthread - CONFIG += VideoEnabled + message("Setting up GStreamer for Android build") + QMAKE_CXXFLAGS += -pthread + CONFIG += VideoEnabled + # Link GStreamer libraries LIBS += -L$$GST_ROOT/lib/gstreamer-1.0 \ - -lgstvideo-1.0 \ - -lgstcoreelements \ - -lgstplayback \ - -lgstudp \ - -lgstrtp \ - -lgstrtsp \ - -lgstx264 \ - -lgstlibav \ - -lgstsdpelem \ - -lgstvideoparsersbad \ - -lgstrtpmanager \ - -lgstisomp4 \ - -lgstmatroska \ - -lgstmpegtsdemux \ - -lgstandroidmedia \ - -lgstopengl \ - -lgsttcp \ - -lgstapp \ - -lgstalaw \ - -lgstautodetect - - - # Rest of GStreamer dependencies + -lgstvideo-1.0 -lgstcoreelements -lgstplayback -lgstudp \ + -lgstrtp -lgstrtsp -lgstx264 -lgstlibav -lgstsdpelem \ + -lgstvideoparsersbad -lgstrtpmanager -lgstisomp4 \ + -lgstmatroska -lgstmpegtsdemux -lgstandroidmedia \ + -lgstopengl -lgsttcp -lgstapp -lgstalaw -lgstautodetect + LIBS += -L$$GST_ROOT/lib \ - -lgraphene-1.0 -ljpeg -lpng16 \ - -lgstfft-1.0 -lm \ - -lgstnet-1.0 -lgio-2.0 \ - -lgstphotography-1.0 -lgstgl-1.0 -lEGL \ - -lgstaudio-1.0 -lgstcodecparsers-1.0 -lgstbase-1.0 \ - -lgstreamer-1.0 -lgstrtp-1.0 -lgstpbutils-1.0 -lgstrtsp-1.0 -lgsttag-1.0 \ - -lgstvideo-1.0 -lavformat -lavcodec -lavutil -lx264 -lavfilter -lswresample \ - -lgstriff-1.0 -lgstcontroller-1.0 -lgstapp-1.0 \ + -lgraphene-1.0 -ljpeg -lpng16 -lgstfft-1.0 -lm \ + -lgstnet-1.0 -lgio-2.0 -lgstphotography-1.0 -lgstgl-1.0 -lEGL \ + -lgstaudio-1.0 -lgstcodecparsers-1.0 -lgstbase-1.0 -lgstreamer-1.0 \ + -lgstrtp-1.0 -lgstpbutils-1.0 -lgstrtsp-1.0 -lgsttag-1.0 \ + -lgstvideo-1.0 -lavformat -lavcodec -lavutil -lx264 -lavfilter \ + -lswresample -lgstriff-1.0 -lgstcontroller-1.0 -lgstapp-1.0 \ -lgstsdp-1.0 -lbz2 -lgobject-2.0 -lgstmpegts-1.0 \ - -Wl,--export-dynamic -lgmodule-2.0 -pthread -lglib-2.0 -lorc-0.4 -liconv -lffi -lintl \ + -Wl,--export-dynamic -lgmodule-2.0 -pthread -lglib-2.0 -lorc-0.4 -liconv -lffi -lintl + # Include paths for GStreamer INCLUDEPATH += \ $$GST_ROOT/include/gstreamer-1.0 \ $$GST_ROOT/lib/gstreamer-1.0/include \ $$GST_ROOT/include/glib-2.0 \ $$GST_ROOT/lib/glib-2.0/include - }else { - message(Gstreamer prebuilt directory does not exist) + } else { + message("GStreamer prebuilt directory does not exist") + } +} else { + # GStreamer configuration for non-Android platforms + GST_ROOT = c:/gstreamer/1.0/x86_64 + + exists($$GST_ROOT) { + CONFIG += VideoEnabled + + # Link GStreamer libraries + LIBS += -L$$GST_ROOT/lib -lopengl32 + + LIBS += -lgstfft-1.0 \ + -lgstnet-1.0 -lgio-2.0 \ + -lgstaudio-1.0 -lgstcodecparsers-1.0 -lgstbase-1.0 \ + -lgstreamer-1.0 -lgstrtp-1.0 -lgstpbutils-1.0 -lgstrtsp-1.0 -lgsttag-1.0 \ + -lgstvideo-1.0 \ + -lgstriff-1.0 -lgstcontroller-1.0 -lgstapp-1.0 \ + -lgstsdp-1.0 -lbz2 -lgobject-2.0 \ + -lgstgl-1.0 -lgraphene-1.0 -lpng16 -ljpeg -lgstphotography-1.0 \ + -lgmodule-2.0 -lglib-2.0 -lorc-0.4 -lffi -lintl + + # Include paths for GStreamer + INCLUDEPATH += \ + $$GST_ROOT/include/gstreamer-1.0 \ + $$GST_ROOT/include/glib-2.0 \ + $$GST_ROOT/lib/gstreamer-1.0/include \ + $$GST_ROOT/lib/glib-2.0/include + } -}else { - message(gst linux) - CONFIG += link_pkgconfig - PKGCONFIG += gstreamer-1.0 gstreamer-video-1.0 gstreamer-gl-1.0 gstreamer-app-1.0 #gstreamer1.0-plugins-good } diff --git a/qml/ui/elements/AppSettings.qml b/qml/ui/elements/AppSettings.qml index 7f6e38a19..93772e771 100644 --- a/qml/ui/elements/AppSettings.qml +++ b/qml/ui/elements/AppSettings.qml @@ -203,7 +203,7 @@ Settings { property double press_temp_warn: 75 property double press_temp_caution: 60 - property bool show_press_temp2: true + property bool show_press_temp2: false property bool press_temp_declutter2: false //AC180 or another 8812 wifi module temperature ranges (datasheet 125 max) property double press_temp_warn2: 75 @@ -221,7 +221,7 @@ Settings { property double airspeed_temp_warn: 0 property double airspeed_temp_caution: 10 - property bool show_esc_temp: true + property bool show_esc_temp: false property bool esc_temp_declutter: false property double esc_temp_warn: 75 property double esc_temp_caution: 60 diff --git a/qml/ui/sidebar/MappedMavlinkChoices.qml b/qml/ui/sidebar/MappedMavlinkChoices.qml index bd6a6df28..a5d642eaf 100644 --- a/qml/ui/sidebar/MappedMavlinkChoices.qml +++ b/qml/ui/sidebar/MappedMavlinkChoices.qml @@ -170,6 +170,7 @@ Item { ListElement {value: 1; verbose:"5.8"} ListElement {value: 2; verbose:"2.4"} ListElement {value: 3; verbose:"ALL"} + //ListElement {value: 3; verbose:"CUSTOM"} } ListModel{ id: elements_model_rate diff --git a/qml/ui/sidebar/MavlinkChoiceElement.qml b/qml/ui/sidebar/MavlinkChoiceElement.qml index 161167490..7de8ac144 100644 --- a/qml/ui/sidebar/MavlinkChoiceElement.qml +++ b/qml/ui/sidebar/MavlinkChoiceElement.qml @@ -44,23 +44,21 @@ BaseJoyEditElement{ ListElement {value: 200; verbose:"200%"} } ListModel{ - id: elements_model_saturation - ListElement {value: 50; verbose:"50%"} - ListElement {value: 75; verbose:"75%"} - ListElement {value: 90; verbose:"90%"} - ListElement {value: 100; verbose:"100%\n(Default)"} - ListElement {value: 110; verbose:"110%"} - ListElement {value: 125; verbose:"125%"} - ListElement {value: 150; verbose:"150%"} + id: elements_model_exposure + ListElement {value: -3; verbose:"-3"} + ListElement {value: -2; verbose:"-2"} + ListElement {value: -1; verbose:"-1"} + ListElement {value: 0; verbose:"0"} + ListElement {value: 1; verbose:"+1%"} + ListElement {value: 2; verbose:"+2"} + ListElement {value: 3; verbose:"+3"} } ListModel{ - id: elements_model_contrast - ListElement {value: 50; verbose:"50%"} - ListElement {value: 75; verbose:"75%"} - ListElement {value: 90; verbose:"90%"} - ListElement {value: 100; verbose:"100%\n(Default)"} - ListElement {value: 125; verbose:"125%"} - ListElement {value: 150; verbose:"150%"} + id: elements_model_metering + ListElement {value: "centre"; verbose:"center"} + ListElement {value: "spot"; verbose:"spot"} + ListElement {value: "matrix"; verbose:"matrix"} + } ListModel{ id: elements_model_sharpness @@ -152,10 +150,10 @@ BaseJoyEditElement{ function get_model(){ if(m_param_id=="BRIGHTNESS"){ return elements_model_brightness; - }else if(m_param_id=="SATURATION"){ - return elements_model_saturation; - }else if(m_param_id=="CONTRAST"){ - return elements_model_contrast; + }else if(m_param_id=="EXPOSURE"){ + return elements_model_exposure; + }else if(m_param_id=="METERING"){ + return elements_model_metering; }else if(m_param_id=="SHARPNESS"){ return elements_model_sharpness; }else if(m_param_id=="ROTATION"){ diff --git a/qml/ui/sidebar/MavlinkChoiceElement2.qml b/qml/ui/sidebar/MavlinkChoiceElement2.qml index bdfab8f9d..e7bb6d387 100644 --- a/qml/ui/sidebar/MavlinkChoiceElement2.qml +++ b/qml/ui/sidebar/MavlinkChoiceElement2.qml @@ -76,10 +76,10 @@ BaseJoyEditElement2{ } function open_choices_menu(clickable){ - if(!m_param_exists){ - _qopenhd.show_toast("N/A"); - return; - } + // if(!m_param_exists){ + // _qopenhd.show_toast("N/A"); + // return; + // } if(m_settings_model.ui_is_busy){ _qopenhd.show_toast("Busy, please try again later"); return; @@ -140,6 +140,10 @@ BaseJoyEditElement2{ }else{ m_param_exists=m_settings_model.param_int_exists(m_param_id) } + if(m_param_id==mPARAM_ID_FREQUENCY_SCAN){ + m_param_exists=true; + _wbLinkSettingsHelper.change_param_air_and_ground_frequency(value_new) + } if(!m_param_exists){ console.log("Param "+m_param_id+" does not exist"); populate_display_text="NOT\nAVAILABLE"; diff --git a/qml/ui/sidebar/Panel1Link.qml b/qml/ui/sidebar/Panel1Link.qml index f2063f955..082031ee7 100644 --- a/qml/ui/sidebar/Panel1Link.qml +++ b/qml/ui/sidebar/Panel1Link.qml @@ -5,7 +5,7 @@ SideBarBasePanel{ function takeover_control(){ - edit_frequency_element.takeover_control(); + scan_frequency_element.takeover_control(); } Column { @@ -43,24 +43,24 @@ SideBarBasePanel{ } }*/ MavlinkChoiceElement2{ - id:edit_frequency_element - m_title: "Frequency" - m_param_id: mPARAM_ID_FREQUENCY - m_settings_model: _ohdSystemAirSettingsModel + id:scan_frequency_element + m_title: "Scan for Air" + m_param_id: mPARAM_ID_FREQUENCY_SCAN + m_settings_model: _ohdSystemGroundSettings onGoto_previous: { - sidebar.regain_control_on_sidebar_stack() + sidebar.regain_control_on_sidebar_stack(); } onGoto_next: { - scan_frequency_element.takeover_control() + edit_frequency_element.takeover_control() } } MavlinkChoiceElement2{ - id:scan_frequency_element - m_title: "Scan for Air" - m_param_id: mPARAM_ID_FREQUENCY_SCAN - m_settings_model: _ohdSystemGroundSettings + id:edit_frequency_element + m_title: "Frequency" + m_param_id: mPARAM_ID_FREQUENCY + m_settings_model: _ohdSystemAirSettingsModel onGoto_previous: { - edit_frequency_element.takeover_control(); + scan_frequency_element.takeover_control() } onGoto_next: { edit_channel_width_element.takeover_control() diff --git a/qml/ui/sidebar/Panel3Camera.qml b/qml/ui/sidebar/Panel3Camera.qml index 7ba36f53d..8f8a0499b 100644 --- a/qml/ui/sidebar/Panel3Camera.qml +++ b/qml/ui/sidebar/Panel3Camera.qml @@ -31,28 +31,28 @@ SideBarBasePanel{ sidebar.regain_control_on_sidebar_stack() } onGoto_next: { - saturation.takeover_control(); + exposure.takeover_control(); } } MavlinkChoiceElement2{ - id: saturation - m_title: "Saturation" - m_param_id: "SATURATION" + id: exposure + m_title: "Exposure" + m_param_id: "EXPOSURE" m_settings_model: _airCameraSettingsModel onGoto_previous: { brightness.takeover_control(); } onGoto_next: { - contrast.takeover_control(); + metering.takeover_control(); } } MavlinkChoiceElement2{ - id: contrast - m_title: "Contrast" - m_param_id: "CONTRAST" + id: metering + m_title: "Metering" + m_param_id: "METERING" m_settings_model: _airCameraSettingsModel onGoto_previous: { - saturation.takeover_control(); + exposure.takeover_control(); } onGoto_next: { sharpness.takeover_control(); @@ -64,7 +64,7 @@ SideBarBasePanel{ m_param_id: "SHARPNESS" m_settings_model: _airCameraSettingsModel onGoto_previous: { - contrast.takeover_control(); + metering.takeover_control(); } onGoto_next: { sidebar.regain_control_on_sidebar_stack() diff --git a/qml/ui/sidebar/Panel4Recording.qml b/qml/ui/sidebar/Panel4Recording.qml index ea69a5305..90d9b3107 100644 --- a/qml/ui/sidebar/Panel4Recording.qml +++ b/qml/ui/sidebar/Panel4Recording.qml @@ -53,7 +53,7 @@ SideBarBasePanel { text: { var tmp = " Status"; if (!_ohdSystemAir.is_alive) { - return tmp + " disabled "; + return tmp + " disabled "; } return tmp + _cameraStreamModelPrimary.camera_recording_mode_to_string(_cameraStreamModelPrimary.air_recording_active) }