diff --git a/app/main.cpp b/app/main.cpp index 38baed1f7..f3741c4f4 100755 --- a/app/main.cpp +++ b/app/main.cpp @@ -26,6 +26,8 @@ const QVector permissions({"android.permission.INTERNET", #include "telemetry/models/rcchannelsmodel.h" #include "telemetry/settings/mavlinksettingsmodel.h" #include "telemetry/settings/wblinksettingshelper.h" +#include "telemetry/settings/frequencyhelper.h" +#include "telemetry/settings/pollutionhelper.h" #include "osd/speedladder.h" #include "osd/altitudeladder.h" #include "osd/headingladder.h" @@ -168,6 +170,22 @@ static void write_platform_context_properties(QQmlApplicationEngine& engine){ #endif } +static void android_check_permissions(){ +#if defined(__android__) + qDebug()<<"Android request permissions"; + for(const QString &permission : permissions) { + auto result = QtAndroid::checkPermission(permission); + if (result == QtAndroid::PermissionResult::Denied) { + auto resultHash = QtAndroid::requestPermissionsSync(QStringList({permission})); + if (resultHash[permission] == QtAndroid::PermissionResult::Denied) { + LogMessagesModel::instanceGround().add_message_warn("QOpenHD","Android - missing permissions"); + return; + } + } + } +#endif +} + int main(int argc, char *argv[]) { @@ -233,20 +251,8 @@ int main(int argc, char *argv[]) { applePlatform->registerNotifications(); #endif - QOpenHD::instance().keep_screen_on(true); -#if defined(__android__) - qDebug()<<"Android request permissions"; - for(const QString &permission : permissions) { - auto result = QtAndroid::checkPermission(permission); - if (result == QtAndroid::PermissionResult::Denied) { - auto resultHash = QtAndroid::requestPermissionsSync(QStringList({permission})); - if (resultHash[permission] == QtAndroid::PermissionResult::Denied) { - return 0; - } - } - } -#endif - + QOpenHD::instance().keep_screen_on(true); + android_check_permissions(); load_fonts(); qmlRegisterType("OpenHD", 1, 0, "SpeedLadder"); @@ -282,6 +288,8 @@ int main(int argc, char *argv[]) { engine.rootContext()->setContextProperty("_ohdSystemAirSettingsModel", &MavlinkSettingsModel::instanceAir()); engine.rootContext()->setContextProperty("_ohdSystemGroundSettings", &MavlinkSettingsModel::instanceGround()); engine.rootContext()->setContextProperty("_wbLinkSettingsHelper", &WBLinkSettingsHelper::instance()); + engine.rootContext()->setContextProperty("_frequencyHelper", &FrequencyHelper::instance()); + engine.rootContext()->setContextProperty("_pollutionHelper", &PollutionHelper::instance()); engine.rootContext()->setContextProperty("_fcMavlinkSystem", &FCMavlinkSystem::instance()); engine.rootContext()->setContextProperty("_fcMavlinkAction", &FCAction::instance()); engine.rootContext()->setContextProperty("_fcMavlinkMissionItemsModel", &FCMavlinkMissionItemsModel::instance()); diff --git a/app/osd/altitudeladder.cpp b/app/osd/altitudeladder.cpp index c6cf59981..70ada7789 100644 --- a/app/osd/altitudeladder.cpp +++ b/app/osd/altitudeladder.cpp @@ -7,6 +7,8 @@ #include "debug_overdraw.hpp" +static constexpr int DEFAULT_FONT_PIXEL_SIZE=11; + AltitudeLadder::AltitudeLadder(QQuickItem *parent): QQuickPaintedItem(parent) { qDebug() << "AltitudeLadder::AltitudeLadder()"; setRenderTarget(RenderTarget::FramebufferObject); @@ -119,6 +121,13 @@ void AltitudeLadder::setAltitudeRange(int altitudeRange) { void AltitudeLadder::setFontFamily(QString fontFamily) { m_fontFamily = fontFamily; emit fontFamilyChanged(m_fontFamily); - m_font = QFont(m_fontFamily, 13, QFont::Bold, false); + m_font = QFont(m_fontFamily, DEFAULT_FONT_PIXEL_SIZE*m_custom_font_scale, QFont::Bold, false); + update(); +} + +void AltitudeLadder::set_custom_font_scale(double custom_font_scale) +{ + m_custom_font_scale=custom_font_scale; + m_font.setPointSize(DEFAULT_FONT_PIXEL_SIZE*m_custom_font_scale); update(); } diff --git a/app/osd/altitudeladder.h b/app/osd/altitudeladder.h index 74ba3e764..0b5c6ea6e 100644 --- a/app/osd/altitudeladder.h +++ b/app/osd/altitudeladder.h @@ -2,6 +2,8 @@ #include #include +#include "../../../lib/lqtutils_master/lqtutils_prop.h" + class AltitudeLadder : public QQuickPaintedItem { Q_OBJECT Q_PROPERTY(QColor color READ color WRITE setColor NOTIFY colorChanged) @@ -10,7 +12,8 @@ class AltitudeLadder : public QQuickPaintedItem { // actual altitude, unit - less Q_PROPERTY(int altitude MEMBER m_altitude WRITE set_altitude NOTIFY altitude_changed) Q_PROPERTY(QString fontFamily MEMBER m_fontFamily WRITE setFontFamily NOTIFY fontFamilyChanged) - +public: + Q_PROPERTY(double custom_font_scale WRITE set_custom_font_scale) public: explicit AltitudeLadder(QQuickItem* parent = nullptr); @@ -25,6 +28,7 @@ public slots: void setAltitudeRange(int altitudeRange); void set_altitude(double alt); void setFontFamily(QString fontFamily); + void set_custom_font_scale(double custom_font_scale); signals: void colorChanged(QColor color); void glowChanged(QColor glow); @@ -43,4 +47,6 @@ public slots: QString m_fontFamily; QFont m_font; + double m_custom_font_scale=1.0; + }; diff --git a/app/osd/aoagauge.h b/app/osd/aoagauge.h index b9730a7ee..6d1dfb276 100644 --- a/app/osd/aoagauge.h +++ b/app/osd/aoagauge.h @@ -2,7 +2,6 @@ #include #include - class AoaGauge : public QQuickPaintedItem { Q_OBJECT Q_PROPERTY(QColor color READ color WRITE setColor NOTIFY colorChanged) diff --git a/app/osd/debug_overdraw.hpp b/app/osd/debug_overdraw.hpp index 0a3e573b3..d568a71cb 100644 --- a/app/osd/debug_overdraw.hpp +++ b/app/osd/debug_overdraw.hpp @@ -4,4 +4,5 @@ // Such that we can enable / disable the "overdraw debugging" with just a single variable change static constexpr bool ENABLE_DEBUG_OVERDRAW=false; + #endif // DEBUG_OVERDRAW_HPP diff --git a/app/osd/flightpathvector.h b/app/osd/flightpathvector.h index 9f5c97442..e262dabe1 100644 --- a/app/osd/flightpathvector.h +++ b/app/osd/flightpathvector.h @@ -2,7 +2,6 @@ #include #include - class FlightPathVector : public QQuickPaintedItem { Q_OBJECT Q_PROPERTY(QColor color READ color WRITE setColor NOTIFY colorChanged) diff --git a/app/osd/headingladder.cpp b/app/osd/headingladder.cpp index 268fb8476..3e89b97e9 100644 --- a/app/osd/headingladder.cpp +++ b/app/osd/headingladder.cpp @@ -6,6 +6,8 @@ #include "debug_overdraw.hpp" +static constexpr int DEFAULT_FONT_PIXEL_SIZE=11; + HeadingLadder::HeadingLadder(QQuickItem *parent): QQuickPaintedItem(parent) { qDebug() << "HeadingLadder::HeadingLadder()"; setRenderTarget(RenderTarget::FramebufferObject); @@ -235,6 +237,13 @@ void HeadingLadder::setHomeHeading(int homeHeading) { void HeadingLadder::setFontFamily(QString fontFamily) { m_fontFamily = fontFamily; emit fontFamilyChanged(m_fontFamily); - m_font = QFont(m_fontFamily, 11, QFont::Bold, false); + m_font = QFont(m_fontFamily, DEFAULT_FONT_PIXEL_SIZE*m_custom_font_scale, QFont::Bold, false); + update(); +} + +void HeadingLadder::set_custom_font_scale(double custom_font_scale) +{ + m_custom_font_scale=custom_font_scale; + m_font.setPointSize(DEFAULT_FONT_PIXEL_SIZE*m_custom_font_scale); update(); } diff --git a/app/osd/headingladder.h b/app/osd/headingladder.h index b9be2d6f2..341b3ff0a 100644 --- a/app/osd/headingladder.h +++ b/app/osd/headingladder.h @@ -2,6 +2,8 @@ #include #include +#include "../../../lib/lqtutils_master/lqtutils_prop.h" + class HeadingLadder : public QQuickPaintedItem { Q_OBJECT Q_PROPERTY(QColor color READ color WRITE setColor NOTIFY colorChanged) @@ -16,8 +18,8 @@ class HeadingLadder : public QQuickPaintedItem { Q_PROPERTY(QString fontFamily MEMBER m_fontFamily WRITE setFontFamily NOTIFY fontFamilyChanged) - -//show_horizon_heading_ladder +public: + Q_PROPERTY(double custom_font_scale WRITE set_custom_font_scale) public: explicit HeadingLadder(QQuickItem* parent = nullptr); @@ -39,7 +41,7 @@ public slots: void setHomeHeading(int homeHeading); void setFontFamily(QString fontFamily); - + void set_custom_font_scale(double custom_font_scale); signals: void colorChanged(QColor color); void glowChanged(QColor glow); @@ -69,4 +71,5 @@ public slots: QFont m_font; QFont m_fontAwesome = QFont("Font Awesome 5 Free", 14, QFont::Bold, false); + double m_custom_font_scale=1.0; }; diff --git a/app/osd/horizonladder.cpp b/app/osd/horizonladder.cpp index f0d351667..d82e12269 100644 --- a/app/osd/horizonladder.cpp +++ b/app/osd/horizonladder.cpp @@ -5,9 +5,10 @@ #include #include -#include "common/TimeHelper.hpp" #include "debug_overdraw.hpp" +static constexpr int DEFAULT_FONT_PIXEL_SIZE=11; + HorizonLadder::HorizonLadder(QQuickItem *parent): QQuickPaintedItem(parent) { qDebug() << "HorizonLadder::HorizonLadder()"; setRenderTarget(RenderTarget::FramebufferObject); @@ -491,6 +492,13 @@ void HorizonLadder::setShowHorizonHome(bool showHorizonHome) { void HorizonLadder::setFontFamily(QString fontFamily) { m_fontFamily = fontFamily; emit fontFamilyChanged(m_fontFamily); - m_font = QFont(m_fontFamily, 11, QFont::Bold, false); + m_font = QFont(m_fontFamily, DEFAULT_FONT_PIXEL_SIZE*m_custom_font_scale, QFont::Bold, false); + update(); +} + +void HorizonLadder::set_custom_font_scale(double custom_font_scale) +{ + m_custom_font_scale=custom_font_scale; + m_font.setPointSize(DEFAULT_FONT_PIXEL_SIZE*m_custom_font_scale); update(); } diff --git a/app/osd/horizonladder.h b/app/osd/horizonladder.h index d113b7e56..c2c48ff21 100644 --- a/app/osd/horizonladder.h +++ b/app/osd/horizonladder.h @@ -32,7 +32,8 @@ class HorizonLadder : public QQuickPaintedItem { L_RW_PROP(bool,show_center_indicator, set_show_center_indicator, true) // Adjust the stroke strength of the lines, in percent //L_RW_PROP(double,line_stroke_strength_perc, set_line_stroke_strength_perc, 100) - +public: + Q_PROPERTY(double custom_font_scale WRITE set_custom_font_scale) public: explicit HorizonLadder(QQuickItem* parent = nullptr); @@ -61,7 +62,7 @@ public slots: void setShowHorizonHome(bool showHorizonHome); void setFontFamily(QString fontFamily); - + void set_custom_font_scale(double custom_font_scale); signals: void colorChanged(QColor color); void glowChanged(QColor glow); @@ -108,5 +109,6 @@ public slots: QFont m_font; QFont m_fontAwesome = QFont("Font Awesome 5 Free", 15, QFont::Bold, false); + double m_custom_font_scale=1.0; }; #endif //QOPENHD_HORIZON_LADDER diff --git a/app/osd/speedladder.cpp b/app/osd/speedladder.cpp index 0154cb76f..6d0fe86ef 100644 --- a/app/osd/speedladder.cpp +++ b/app/osd/speedladder.cpp @@ -7,6 +7,8 @@ #include "debug_overdraw.hpp" +static constexpr int DEFAULT_FONT_PIXEL_SIZE=11; + SpeedLadder::SpeedLadder(QQuickItem *parent): QQuickPaintedItem(parent) { qDebug() << "SpeedLadder::SpeedLadder()"; setRenderTarget(RenderTarget::FramebufferObject); @@ -129,6 +131,13 @@ void SpeedLadder::setSpeed(int speed) { void SpeedLadder::setFontFamily(QString fontFamily) { m_fontFamily = fontFamily; emit fontFamilyChanged(m_fontFamily); - m_font = QFont(m_fontFamily, 10, QFont::Bold, false); + m_font = QFont(m_fontFamily, DEFAULT_FONT_PIXEL_SIZE*m_custom_font_scale, QFont::Bold, false); + update(); +} + +void SpeedLadder::set_custom_font_scale(double custom_font_scale) +{ + m_custom_font_scale=custom_font_scale; + m_font.setPointSize(DEFAULT_FONT_PIXEL_SIZE*m_custom_font_scale); update(); } diff --git a/app/osd/speedladder.h b/app/osd/speedladder.h index 3b0d772a0..225185480 100644 --- a/app/osd/speedladder.h +++ b/app/osd/speedladder.h @@ -2,6 +2,7 @@ #include #include +#include "../../../lib/lqtutils_master/lqtutils_prop.h" class SpeedLadder : public QQuickPaintedItem { Q_OBJECT @@ -13,7 +14,8 @@ class SpeedLadder : public QQuickPaintedItem { Q_PROPERTY(int speed MEMBER m_speed WRITE setSpeed NOTIFY speedChanged) Q_PROPERTY(QString fontFamily MEMBER m_fontFamily WRITE setFontFamily NOTIFY fontFamilyChanged) - +public: + Q_PROPERTY(double custom_font_scale WRITE set_custom_font_scale) public: explicit SpeedLadder(QQuickItem* parent = nullptr); @@ -31,7 +33,7 @@ public slots: void setSpeed(int speed); void setFontFamily(QString fontFamily); - + void set_custom_font_scale(double custom_font_scale); signals: void colorChanged(QColor color); void glowChanged(QColor glow); @@ -51,5 +53,5 @@ public slots: QString m_fontFamily; QFont m_font; - + double m_custom_font_scale=1.0; }; diff --git a/app/telemetry/MavlinkTelemetry.cpp b/app/telemetry/MavlinkTelemetry.cpp index f3c5267d7..c656f5f6c 100644 --- a/app/telemetry/MavlinkTelemetry.cpp +++ b/app/telemetry/MavlinkTelemetry.cpp @@ -285,7 +285,7 @@ bool MavlinkTelemetry::change_manual_tcp_ip(QString ip) void MavlinkTelemetry::send_heartbeat_loop() { - while(true){ + while(m_heartbeat_thread_run){ //qDebug()<<"send_heartbeat_loop"; std::this_thread::sleep_for(std::chrono::milliseconds(1000)); perform_connection_management(); diff --git a/app/telemetry/models/aohdsystem.cpp b/app/telemetry/models/aohdsystem.cpp index 4d2bab18a..309554d6e 100644 --- a/app/telemetry/models/aohdsystem.cpp +++ b/app/telemetry/models/aohdsystem.cpp @@ -139,18 +139,16 @@ bool AOHDSystem::process_message(const mavlink_message_t &msg) CameraStreamModel::instance(0).update_mavlink_openhd_camera_status_air(parsedMsg); }else if(msg.compid==OHD_COMP_ID_AIR_CAMERA_SECONDARY){ CameraStreamModel::instance(1).update_mavlink_openhd_camera_status_air(parsedMsg); + set_dirty_air_has_secondary_cam(true); // Feature - tell user to enable 2 cameras in qopenhd set_n_openhd_cameras(2); const int value_in_qopenhd=QOpenHDVideoHelper::get_qopenhd_n_cameras(); if(value_in_qopenhd!=2){ const auto elapsed=std::chrono::steady_clock::now()-m_last_n_cameras_message; - if(elapsed>std::chrono::seconds(10)){ - auto message="QOpenHD is not configured for dual cam usage, go to QOpenHD settings / General to configure your GCS to show secondary camera screen"; - qDebug()<std::chrono::seconds(5)){ + LogMessagesModel::instanceGround().add_message_debug("QOpenHD","Please enable 2 camera control"); m_last_n_cameras_message=std::chrono::steady_clock::now(); } - HUDLogMessagesModel::instance().add_message_info("QOpenHD only shows 1 camera"); } } diff --git a/app/telemetry/models/aohdsystem.h b/app/telemetry/models/aohdsystem.h index f147f49a6..e132c687f 100644 --- a/app/telemetry/models/aohdsystem.h +++ b/app/telemetry/models/aohdsystem.h @@ -118,6 +118,8 @@ class AOHDSystem : public QObject L_RO_PROP(int,wb_gnd_operating_mode,set_wb_gnd_operating_mode,-1) // L_RO_PROP(int,air_reported_fc_sys_id,set_air_reported_fc_sys_id,-1) + // + L_RO_PROP(bool,dirty_air_has_secondary_cam,set_dirty_air_has_secondary_cam,false) private: const bool m_is_air; // either true (for air) or false (for ground) uint8_t get_own_sys_id()const{ diff --git a/app/telemetry/models/camerastreammodel.cpp b/app/telemetry/models/camerastreammodel.cpp index e85af8de0..6c1101612 100644 --- a/app/telemetry/models/camerastreammodel.cpp +++ b/app/telemetry/models/camerastreammodel.cpp @@ -34,6 +34,50 @@ CameraStreamModel &CameraStreamModel::instance(int cam_index) assert(false); } +QString CameraStreamModel::camera_type_to_string(int camera_type) +{ + if(camera_type<=0)return "Unknown"; + if(camera_type==1)return "DUMMY"; + if(camera_type==2)return "RPI_CSI_MMAL"; + if(camera_type==3)return "RPI_CSI_VEYE_V4l2"; + if(camera_type==4)return "RPI_CSI_LIBCAMERA"; + if(camera_type==5)return "JETSON_CSI"; + if(camera_type==6)return "ROCKCHIP_CSI"; + if(camera_type==7)return "ALLWINNER_CSI"; + if(camera_type==8)return "UVC (USB)"; + if(camera_type==9)return "UVC_H264"; + if(camera_type==10)return "IP"; + if(camera_type==11)return "ROCK_HDMI"; + if(camera_type==12)return "CUSTOM UNMANAGED"; + return "ERROR"; +} + +QString CameraStreamModel::camera_status_to_string(int camera_status) +{ + if(camera_status<0)return "N/A"; + if(camera_status==0)return "X"; + if(camera_status==1)return "streaming"; + if(camera_status==2)return "restarting"; + return "ERROR"; +} + +QString CameraStreamModel::camera_codec_to_string(int camera_codec) +{ + if(camera_codec<0)return "ERROR"; + if(camera_codec==0)return "h264"; + if(camera_codec==1)return "h265"; + if(camera_codec==2)return "mjpeg"; + return "ERROR"; +} + +QString CameraStreamModel::camera_recording_mode_to_string(int recording_mode) +{ + if(recording_mode<0)return "n/a"; + if(recording_mode==0)return "not active"; + if(recording_mode==1)return "active"; + return "error"; +} + void CameraStreamModel::update_mavlink_openhd_stats_wb_video_air(const mavlink_openhd_stats_wb_video_air_t &msg) { const auto curr_recommended_bitrate_kbits=msg.curr_recommended_bitrate; @@ -88,6 +132,7 @@ void CameraStreamModel::update_mavlink_openhd_camera_status_air(const mavlink_op set_curr_curr_keyframe_interval(msg.encoding_keyframe_interval); set_air_recording_active(msg.air_recording_active); set_camera_type(msg.cam_type); + set_encoding_codec(msg.encoding_format); { std::stringstream ss; ss<<(int)msg.stream_w<<"x"<<(int)msg.stream_h<<"@"<=std::chrono::seconds(3)){ - m_last_hud_message_camera_status=std::chrono::steady_clock::now(); - std::stringstream log; - log<<(secondary ? "CAM2" : "CAM1"); - log<<" is restarting, please wait"; - HUDLogMessagesModel::instance().add_message_info(log.str().c_str()); - } - } } void CameraStreamModel::update_mavlink_openhd_stats_wb_video_air_fec_performance(const mavlink_openhd_stats_wb_video_air_fec_performance_t &msg) diff --git a/app/telemetry/models/camerastreammodel.h b/app/telemetry/models/camerastreammodel.h index 7531f207e..7263e5ca1 100644 --- a/app/telemetry/models/camerastreammodel.h +++ b/app/telemetry/models/camerastreammodel.h @@ -54,7 +54,8 @@ class CameraStreamModel : public QObject L_RO_PROP(QString,air_tx_packets_per_second_and_bits_per_second,set_air_tx_packets_per_second_and_bits_per_second,"N/A") // UI might change slightly depending on the camera type L_RO_PROP(int,camera_type,set_camera_type,-1) - L_RO_PROP(int,camera_status,set_camera_status,-1) + L_RO_PROP(int,camera_status,set_camera_status,-1) + L_RO_PROP(int,encoding_codec,set_encoding_codec,-1) // // These are generated by the OpenHD ground unit // @@ -64,6 +65,11 @@ class CameraStreamModel : public QObject L_RO_PROP(qint64,count_blocks_recovered,set_count_blocks_recovered,-1) L_RO_PROP(qint64,count_fragments_recovered,set_count_fragments_recovered,-1) L_RO_PROP(QString,curr_fec_decode_time_avg_min_max,set_curr_fec_decode_time_avg_min_max,"avg na, min na, max na") +public: + Q_INVOKABLE QString camera_type_to_string(int camera_type); + Q_INVOKABLE QString camera_status_to_string(int camera_status); + Q_INVOKABLE QString camera_codec_to_string(int camera_codec); + Q_INVOKABLE QString camera_recording_mode_to_string(int recording_mode); // public: // generated by wb / link diff --git a/app/telemetry/settings/frequencyhelper.cpp b/app/telemetry/settings/frequencyhelper.cpp new file mode 100644 index 000000000..22928cb97 --- /dev/null +++ b/app/telemetry/settings/frequencyhelper.cpp @@ -0,0 +1,150 @@ +#include "frequencyhelper.h" +#include "wifi_channel.h" + +FrequencyHelper::FrequencyHelper(QObject *parent) : QObject{parent} +{ + +} + +FrequencyHelper &FrequencyHelper::instance() +{ + static FrequencyHelper instance{}; + return instance; +} + +QList FrequencyHelper::get_frequencies(bool openhd_bands_only) +{ + QList ret; + if(openhd_bands_only){ + auto tmp=openhd::get_openhd_channels_1_to_5(); + for(auto& channel:tmp){ + ret.push_back(channel.frequency); + } + }else{ + const auto frequency_items=openhd::get_all_channels_2G_5G(); + for(auto& item:frequency_items){ + if(item.is_legal_at_least_one_country){ + ret.push_back(item.frequency); + } + } + } + return ret; +} + +QList FrequencyHelper::get_frequencies_all_40Mhz() +{ + QList ret; + const auto frequency_items=openhd::get_all_channels_2G_5G(); + for(auto& item:frequency_items){ + if(item.space==openhd::WifiSpace::G2_4){ + if(item.is_legal_at_least_one_country){ + ret.push_back(item.frequency); + } + }else{ + if(item.is_legal_at_least_one_country && item.in_40Mhz_ht40_plus){ + ret.push_back(item.frequency); + } + } + } + return ret; +} + +bool FrequencyHelper::get_frequency_radar(int frequency_mhz) +{ + if(frequency_mhz>=5260 && frequency_mhz<=5680){ + return true; + } + return false; +} + +int FrequencyHelper::get_frequency_openhd_race_band(int frequency_mhz) +{ + // 5700,5745,5785,5825,5865 + if(frequency_mhz==5700){ + return 1; + } + if(frequency_mhz==5745){ + return 2; + } + if(frequency_mhz==5785){ + return 3; + } + if(frequency_mhz==5825){ + return 4; + } + if(frequency_mhz==5865){ + return 5; + } + return -1; +} + +int FrequencyHelper::get_frequency_channel_nr(int frequency_mhz) +{ + const auto frequency_item=openhd::channel_from_frequency(frequency_mhz); + if(frequency_item.has_value()){ + return frequency_item.value().channel; + } + return -1; +} + +bool FrequencyHelper::set_hw_supported_frequencies_threadsafe(const std::vector supported_channels) +{ + std::lock_guard lock(m_supported_channels_mutex); + if(m_supported_channels!=supported_channels){ + m_supported_channels=supported_channels; + return true; + } + return false; +} + +bool FrequencyHelper::has_valid_supported_frequencies_data() +{ + std::lock_guard lock(m_supported_channels_mutex); + return !m_supported_channels.empty(); +} + +bool FrequencyHelper::hw_supports_frequency_threadsafe(int frequency_mhz) +{ + std::lock_guard lock(m_supported_channels_mutex); + for(const auto supported_freq: m_supported_channels){ + if(supported_freq==frequency_mhz)return true; + } + return false; +} + + +static std::string spaced_string(int number){ + std::stringstream ss; + if(number<100)ss<<" "; + if(number<10)ss<<" "; + ss<channel)<<"] "; + ss< FrequencyHelper::filter_frequencies(QList frequencies, int filter_level) +{ + QList ret; + for(const auto& element:frequencies){ + if(filter_level==2){ + if(element> 3000){ + ret.push_back(element); + } + }else if(filter_level==1){ + if(element< 3000){ + ret.push_back(element); + } + }else{ + ret.push_back(element); + } + } + return ret; +} diff --git a/app/telemetry/settings/frequencyhelper.h b/app/telemetry/settings/frequencyhelper.h new file mode 100644 index 000000000..20d8fc5a2 --- /dev/null +++ b/app/telemetry/settings/frequencyhelper.h @@ -0,0 +1,39 @@ +#ifndef FREQUENCYHELPER_H +#define FREQUENCYHELPER_H + +#include "qlist.h" +#include +#include +#include + + + +class FrequencyHelper : public QObject +{ + Q_OBJECT +public: + explicit FrequencyHelper(QObject *parent = nullptr); + static FrequencyHelper &instance(); + + Q_INVOKABLE QList get_frequencies(bool openhd_bands_only); + Q_INVOKABLE QList get_frequencies_all_40Mhz(); + + Q_INVOKABLE bool get_frequency_radar(int frequency_mhz); + Q_INVOKABLE int get_frequency_openhd_race_band(int frequency_mhz); + Q_INVOKABLE int get_frequency_channel_nr(int frequency_mhz); + // -------------- + Q_INVOKABLE bool hw_supports_frequency_threadsafe(int frequency_mhz); + // + Q_INVOKABLE QString get_frequency_description(int frequency_mhz); + + Q_INVOKABLE QList filter_frequencies(QList frequencies,int filter_level); +public: + bool set_hw_supported_frequencies_threadsafe(const std::vector supported_channels); + bool has_valid_supported_frequencies_data(); +private: + // Written by telemetry, read by UI + std::mutex m_supported_channels_mutex; + std::vector m_supported_channels; +}; + +#endif // FREQUENCYHELPER_H diff --git a/app/telemetry/settings/pollutionhelper.cpp b/app/telemetry/settings/pollutionhelper.cpp index 6dd4d02c4..d2b46fedb 100644 --- a/app/telemetry/settings/pollutionhelper.cpp +++ b/app/telemetry/settings/pollutionhelper.cpp @@ -1,8 +1,9 @@ #include "pollutionhelper.h" #include +#include -PollutionHelper::PollutionHelper() +PollutionHelper::PollutionHelper(QObject *parent) : QObject{parent} { } @@ -51,3 +52,42 @@ std::optional PollutionHelper::threadsafe_get //qDebug()<<"Cannot find pollution for "< frequencies) +{ + QStringList ret; + for(auto& freq:frequencies){ + std::stringstream ss; + ss< frequencies, bool normalize) +{ + QVariantList ret; + for(auto& freq: frequencies){ + auto pollution=threadsafe_get_pollution_for_frequency(freq); + if(pollution.has_value()){ + if(normalize){ + ret.push_back(static_cast(pollution.value().n_foreign_packets_normalized)); + }else{ + ret.push_back(static_cast(pollution.value().n_foreign_packets)); + } + + }else{ + ret.push_back(static_cast(0)); + } + } + return ret; +} + +int PollutionHelper::pollution_get_last_scan_pollution_for_frequency(int frequency) +{ + auto tmp=threadsafe_get_pollution_for_frequency(frequency); + if(tmp.has_value()){ + return tmp.value().n_foreign_packets; + } + return -1; +} diff --git a/app/telemetry/settings/pollutionhelper.h b/app/telemetry/settings/pollutionhelper.h index 555de471f..7b5bbd2c0 100644 --- a/app/telemetry/settings/pollutionhelper.h +++ b/app/telemetry/settings/pollutionhelper.h @@ -4,16 +4,19 @@ #include #include #include +#include #include - +#include +#include // Written by telemetry, read by UI // This atomic behaviour is enough for us - we signal the ui to rebuild itself every time the data changes // The OpenHD ground unit broadcast the whole pollution set during channel scan, filling it as the scan proceeds. -class PollutionHelper +class PollutionHelper: public QObject { + Q_OBJECT public: - PollutionHelper(); + explicit PollutionHelper(QObject *parent = nullptr); static PollutionHelper& instance(); public: struct PollutionElement{ @@ -24,6 +27,10 @@ class PollutionHelper }; void threadsafe_update(const std::vector& values); std::optional threadsafe_get_pollution_for_frequency(int frequency); +public: + Q_INVOKABLE QStringList pollution_frequencies_int_to_qstringlist(QList frequencies); + Q_INVOKABLE QVariantList pollution_frequencies_int_get_pollution(QList frequencies,bool normalize=false); + Q_INVOKABLE int pollution_get_last_scan_pollution_for_frequency(int frequency); private: // Written by telemetry, read by UI std::map m_pollution_elements; diff --git a/app/telemetry/settings/wblinksettingshelper.cpp b/app/telemetry/settings/wblinksettingshelper.cpp index f41487a0e..ec14ac3e0 100644 --- a/app/telemetry/settings/wblinksettingshelper.cpp +++ b/app/telemetry/settings/wblinksettingshelper.cpp @@ -10,6 +10,7 @@ #include "../../util/qopenhd.h" #include "pollutionhelper.h" +#include "frequencyhelper.h" static void tmp_log_result(bool enable,const std::string message){ if(enable){ @@ -85,11 +86,6 @@ void WBLinkSettingsHelper::validate_and_set_air_channel_width_mhz(int channel_wi set_curr_air_channel_width_mhz(channel_width_mhz); } -void WBLinkSettingsHelper::set_simplify_channels(bool enable) -{ - m_simplify_channels=enable; -} - void WBLinkSettingsHelper::process_message_openhd_wifibroadcast_supported_channels(const mavlink_openhd_wifbroadcast_supported_channels_t &msg) { std::vector channels; @@ -101,7 +97,7 @@ void WBLinkSettingsHelper::process_message_openhd_wifibroadcast_supported_channe qDebug()<<"No valid channels from ground station - should never happen"; return; } - if(update_supported_channels(channels)){ + if(FrequencyHelper::instance().set_hw_supported_frequencies_threadsafe(channels)){ qDebug()<<"Supported channels changed"; signal_ui_rebuild_model_when_possible(); } @@ -139,11 +135,15 @@ void WBLinkSettingsHelper::process_message_openhd_wifibroadcast_analyze_channels ss<<" Foreign packets:"<=100){ ss<<"100%, Done"; + // DONE + set_current_analyze_frequency(-1); }else{ ss<<(int)msg.progress_perc<<"%"; + set_current_analyze_frequency(curr_channel_mhz); } qDebug()< get_freq_descr(){ - std::vector ret{ - FrequencyItem{-1,2312,false,false,false,-1}, - FrequencyItem{-1,2332,false,false,false,-1}, - FrequencyItem{-1,2352,false,false,false,-1}, - FrequencyItem{-1,2372,false,false,false,-1}, - FrequencyItem{-1,2392,false,false,false,-1}, - // ACTUAL 2G - FrequencyItem{1 ,2412,false,true,false,-1}, - FrequencyItem{5 ,2432,false,true,false,-1}, - FrequencyItem{9 ,2452,false,true,false,-1}, - FrequencyItem{13,2472,false,true,false,-1}, - FrequencyItem{14,2484,false,false,false,-1}, - // ACTUAL 2G end - FrequencyItem{-1,2492,false,false,false,-1}, - FrequencyItem{-1,2512,false,false,false,-1}, - FrequencyItem{-1,2532,false,false,false,-1}, - FrequencyItem{-1,2572,false,false,false,-1}, - FrequencyItem{-1,2592,false,false,false,-1}, - FrequencyItem{-1,2612,false,false,false,-1}, - FrequencyItem{-1,2632,false,false,false,-1}, - FrequencyItem{-1,2652,false,false,false,-1}, - FrequencyItem{-1,2672,false,false,false,-1}, - FrequencyItem{-1,2692,false,false,false,-1}, - FrequencyItem{-1, 2712,false,false,false,-1}, - // 5G begin - FrequencyItem{ 32,5160,false,false,false,-1}, - FrequencyItem{ 36,5180,false,true ,false,-1}, - FrequencyItem{ 40,5200,false,false,false,-1}, - FrequencyItem{ 44,5220,false,true,false,-1}, - FrequencyItem{ 48,5240,false,false,false,-1}, - FrequencyItem{ 52,5260,true,true ,false,-1}, - FrequencyItem{ 56,5280,true,false,false,-1}, - FrequencyItem{ 60,5300,true,true,false,-1}, - FrequencyItem{ 64,5320,true,false,false,-1}, - // big break / part that is not allowed - FrequencyItem{100,5500,true,true,false,-1}, - FrequencyItem{104,5520,true,false,false,-1}, - FrequencyItem{108,5540,true,true,false,-1}, - FrequencyItem{112,5560,true,false,false,-1}, - FrequencyItem{116,5580,true,true,false,-1}, - FrequencyItem{120,5600,true,false,false,-1}, - FrequencyItem{124,5620,true,true,false,-1}, - FrequencyItem{128,5640,true,false,false,-1}, - FrequencyItem{132,5660,true,true,false,-1}, - FrequencyItem{136,5680,true,false,false,-1}, - FrequencyItem{140,5700,false,true,false,1}, - FrequencyItem{144,5720,false,false,false,-1}, - // Here is the weird break - FrequencyItem{149,5745,false,true,true,2}, - FrequencyItem{153,5765,false,false,false,-1}, - FrequencyItem{157,5785,false,true,true,3}, - FrequencyItem{161,5805,false,false,false,-1}, - FrequencyItem{165,5825,false,true,true,4}, - // Depends - FrequencyItem{169,5845,false,false,false,-1}, - FrequencyItem{173,5865,false,true,true,5}, - FrequencyItem{177,5885,false,false,false,-1}, - FrequencyItem{181,5905,false,false,true,-1} - }; - return ret; -} - -static FrequencyItem find_frequency_item(const int frequency){ - const auto frequency_items=get_freq_descr(); - for(const auto& item:frequency_items){ - if(item.frequency==frequency)return item; - } - return FrequencyItem{-1,-1,false,false,false}; -} - -static std::string spaced_string(int number){ - std::stringstream ss; - if(number<100)ss<<" "; - if(number<10)ss<<" "; - ss<(keyframe_interval),"KEYFRAME"); @@ -422,22 +289,6 @@ bool WBLinkSettingsHelper::set_param_stbc_ldpc_enable_air_ground() return true; } -bool WBLinkSettingsHelper::update_supported_channels(const std::vector supported_channels) -{ - std::lock_guard lock(m_supported_channels_mutex); - if(m_supported_channels!=supported_channels){ - m_supported_channels=supported_channels; - return true; - } - return false; -} - -bool WBLinkSettingsHelper::has_valid_reported_channel_data() -{ - std::lock_guard lock(m_supported_channels_mutex); - return !m_supported_channels.empty(); -} - void WBLinkSettingsHelper::change_param_air_async(const int comp_id,const std::string param_id,std::variant param_value,const std::string tag) { mavlink_param_ext_set_t command; @@ -468,7 +319,7 @@ void WBLinkSettingsHelper::change_param_air_async(const int comp_id,const std::s if(std::holds_alternative(param_value)){ ss<(param_value); }else{ - ss<(param_value); + ss<(param_value); } ss<<",please check uplink"; HUDLogMessagesModel::instance().add_message_warning(ss.str().c_str()); @@ -490,67 +341,10 @@ void WBLinkSettingsHelper::change_param_air_channel_width_async(int value, bool change_param_air_async(OHD_COMP_ID_LINK_PARAM,PARAM_ID_WB_CHANNEL_WIDTH,static_cast(value),"BWIDTH"); } -QList WBLinkSettingsHelper::get_supported_frequencies() -{ - std::lock_guard lock(m_supported_channels_mutex); - QList ret; - for(auto& channel:m_supported_channels){ - ret.push_back(channel); - } - return ret; -} - -QList WBLinkSettingsHelper::get_supported_frequencies_filtered(int filter_level) -{ - auto supported_frequencies=get_supported_frequencies(); - if(filter_level<=0)return supported_frequencies; - QList ret; - for(auto& frequency: supported_frequencies){ - if(filter_level==1){ - // 40Mhz spacing - auto info=find_frequency_item(frequency); - if(info.simple){ - ret.push_back(frequency); - } - } - } - return ret; -} - -QStringList WBLinkSettingsHelper::pollution_frequencies_int_to_qstringlist(QList frequencies) -{ - QStringList ret; - for(auto& freq:frequencies){ - std::stringstream ss; - ss< frequencies,bool normalize) -{ - QVariantList ret; - for(auto& freq: frequencies){ - auto pollution=PollutionHelper::instance().threadsafe_get_pollution_for_frequency(freq); - if(pollution.has_value()){ - if(normalize){ - ret.push_back(static_cast(pollution.value().n_foreign_packets_normalized)); - }else{ - ret.push_back(static_cast(pollution.value().n_foreign_packets)); - } - - }else{ - ret.push_back(static_cast(0)); - } - } - return ret; -} - void WBLinkSettingsHelper::signal_ui_rebuild_model_when_possible() { - const bool valid_ground_channel_data=has_valid_reported_channel_data(); + const bool valid_ground_channel_data=FrequencyHelper::instance().has_valid_supported_frequencies_data(); if(m_curr_channel_mhz>0 && m_curr_channel_width_mhz>0 && valid_ground_channel_data){ qDebug()<<"Signal UI Ready & should rebuild "< get_supported_frequencies(); - // To not overload the user, we filter the frequencies a bit - Q_INVOKABLE QList get_supported_frequencies_filtered(int filter_level); - Q_INVOKABLE QStringList pollution_frequencies_int_to_qstringlist(QList frequencies); - Q_INVOKABLE QVariantList pollution_frequencies_int_get_pollution(QList frequencies,bool normalize=false); - - Q_INVOKABLE QString get_frequency_description(int frequency_mhz); - Q_INVOKABLE bool get_frequency_radar(int frequency_mhz); - Q_INVOKABLE bool get_frequency_simplify(int frequency_mhz); - Q_INVOKABLE bool get_frequency_reccommended(int frequency_mhz); - Q_INVOKABLE int get_frequency_openhd_race_band(int frequency_mhz); // These params can be changed "on the fly" and are additionally their value(s) are broadcasted // so we can update them completely async, log the result to the user // and use the broadcasted value(s) to update the UI @@ -114,17 +102,6 @@ class WBLinkSettingsHelper : public QObject // Extra Q_INVOKABLE bool set_param_tx_power(bool ground,bool is_tx_power_index,bool is_for_armed_state,int value); Q_INVOKABLE bool set_param_stbc_ldpc_enable_air_ground(); -private: - struct SupportedChannel{ - uint16_t frequency; - int n_foreign_packets; - }; - // Written by telemetry, read by UI - std::mutex m_supported_channels_mutex; - std::vector m_supported_channels; - bool update_supported_channels(const std::vector supported_channels); - bool has_valid_reported_channel_data(); - std::atomic m_simplify_channels=false; private: void signal_ui_rebuild_model_when_possible(); }; diff --git a/app/telemetry/settings/wifi_channel.h b/app/telemetry/settings/wifi_channel.h new file mode 100644 index 000000000..3319ec25d --- /dev/null +++ b/app/telemetry/settings/wifi_channel.h @@ -0,0 +1,252 @@ +// +// Created by consti10 on 11.12.22. +// + +#ifndef OPENHD_OPENHD_OHD_INTERFACE_INC_WIFI_CHANNEL_H_ +#define OPENHD_OPENHD_OHD_INTERFACE_INC_WIFI_CHANNEL_H_ + +#include +#include +#include +#include + + +namespace OHDUtil{ +template +static void vec_append(std::vector& dest, const std::vector& src) { + dest.insert(dest.end(), src.begin(), src.end()); +} +} + +// USefully links: +// https://www.bundesnetzagentur.de/SharedDocs/Downloads/DE/Sachgebiete/Telekommunikation/Unternehmen_Institutionen/Frequenzen/20190705_Frequenzplan_EntwurfStandMai.pdf?__blob=publicationFile&v=1 +// https://en.wikipedia.org/wiki/List_of_WLAN_channels +// https://www.arubanetworks.com/vrd/OutdoorMIMOVRD/wwhelp/wwhimpl/common/html/wwhelp.htm#context=OutdoorMIMOVRD&file=AppA.html + +// NOTE: DO NOT USE CHANNEL NUMBERS ANYWHERE IN CODE - USE FREQUENCIES IN MHZ, SINCE THEY ARE UNIQUE +namespace openhd { + +enum class WifiSpace { G2_4, G5_8 }; + +// Wifi channel and the corresponding frequency, in mHz. +// "standard" : listed under wikipedia or not. +struct WifiChannel { + // frequency in mhz, recommended to use + uint32_t frequency; + // channel corresponding to this frequency, error-prone compared to the frequency since often defined incorrectly and/or for the non-standard AR9271 frequencies there is no standard channel number + int channel; + // weather this is a channel in the 2.4G space or 5.8G space + WifiSpace space; + // weather this channel is listed under wikipedia or not. + // Channels not listed under wikipedia might still work on some cards, given the driver has been modified. generally, they are not legally usable in most countries though. + bool is_standard; + // Weather this channel is legal in at least one country + bool is_legal_at_least_one_country; + // Weather it is legal in at least one country to use 40Mhz on this wifi channel + bool is_legal_any_country_40Mhz; + // Weather we (should / have to, otherwise driver crashes) use HT40+ or HT40- when doing 40Mhz on this channel + bool in_40Mhz_ht40_plus; + // weather this channel is used by openhd or not. + [[nodiscard]] std::string to_string() const { + std::stringstream ss; + ss << (int)frequency << "Mhz [" << channel << "] " + << (space == WifiSpace::G2_4 ? "2.4G" : "5.8G") + << (is_standard ? "" : "nonstandard"); + return ss.str(); + } +}; + +static std::vector get_channels_2G() { + return std::vector{ + // These are not valid 2.4G wifi channel(s) but some cards aparently can do them, too From https://github.com/OpenHD/linux/blob/092115ae6a980feaa09722690891d99da3afb55c/drivers/net/wireless/ath/ath9k/common-init.c#L39 + // NOTE: In OpenHD we never use the channel number (since it is prone to errors, even in the linux kernel) but rather use the frequency in mhz, which is well-defined. Also read https://yo3iiu.ro/blog/?p=1301 + // NOTE: OpenHD does not use channel width <20Mhz, so we ignore a couple of channels here + WifiChannel{2312, -1, WifiSpace::G2_4, false, false, false}, + //WifiChannel{2317, -1, WifiSpace::G2_4, false}, + //WifiChannel{2322, -1, WifiSpace::G2_4, false}, + //WifiChannel{2327, -1, WifiSpace::G2_4, false}, + WifiChannel{2332, -1, WifiSpace::G2_4, false, false, false}, + //WifiChannel{2337, -1, WifiSpace::G2_4, false}, + //WifiChannel{2342, -1, WifiSpace::G2_4, false}, + //WifiChannel{2347, -1, WifiSpace::G2_4, false}, + WifiChannel{2352, -1, WifiSpace::G2_4, false, false, false}, + //WifiChannel{2357, -1, WifiSpace::G2_4, false}, + //WifiChannel{2362, -1, WifiSpace::G2_4, false}, + //WifiChannel{2367, -1, WifiSpace::G2_4, false}, + WifiChannel{2372, -1, WifiSpace::G2_4, false, false, false}, + //WifiChannel{2377, -1, WifiSpace::G2_4, false}, + //WifiChannel{2382, -1, WifiSpace::G2_4, false}, + //WifiChannel{2387, -1, WifiSpace::G2_4, false}, + WifiChannel{2392, -1, WifiSpace::G2_4, false, false, false}, + //WifiChannel{2397, -1, WifiSpace::G2_4, false}, + //WifiChannel{2402, -1, WifiSpace::G2_4, false}, + //WifiChannel{2407, -1, WifiSpace::G2_4, false}, + // Now to the standard Wi-Fi channel(s) + // https://en.wikipedia.org/wiki/List_of_WLAN_channels#2.4_GHz_(802.11b/g/n/ax) + WifiChannel{2412, 1, WifiSpace::G2_4, true, true, true, true}, + //WifiChannel{2417, 2, WifiSpace::G2_4, true}, + //WifiChannel{2422, 3, WifiSpace::G2_4, true}, + //WifiChannel{2427, 4, WifiSpace::G2_4, true}, + WifiChannel{2432, 5, WifiSpace::G2_4, true, true, true, false}, + //WifiChannel{2437, 6, WifiSpace::G2_4, true}, + //WifiChannel{2442, 7, WifiSpace::G2_4, true}, + //WifiChannel{2447, 8, WifiSpace::G2_4, true}, + WifiChannel{2452, 9, WifiSpace::G2_4, true, true, true, true}, + //WifiChannel{2457, 10, WifiSpace::G2_4, true}, + //WifiChannel{2462, 11, WifiSpace::G2_4, true}, + //WifiChannel{2467, 12, WifiSpace::G2_4, true}, + WifiChannel{2472, 13, WifiSpace::G2_4, true, true, true, false}, + // until here it is consistent (5Mhz increments) + // this one is neither allowed in EU nor USA + // (only in Japan under 11b) + WifiChannel{2484, 14, WifiSpace::G2_4, true, true, false}, + // and these are all not valid wlan channels, but the AR9271 can do them anyways + //WifiChannel{2487, -1, WifiSpace::G2_4, false}, + //WifiChannel{2489, -1, WifiSpace::G2_4, false}, + WifiChannel{2492, -1, WifiSpace::G2_4, false, false, false}, + //WifiChannel{2494, -1, WifiSpace::G2_4, false}, + //WifiChannel{2497, -1, WifiSpace::G2_4, false}, + //WifiChannel{2499, -1, WifiSpace::G2_4, false}, + WifiChannel{2512, -1, WifiSpace::G2_4, false, false, false}, + //WifiChannel{2532, -1, WifiSpace::G2_4, false}, + //WifiChannel{2572, -1, WifiSpace::G2_4, false}, + //WifiChannel{2592, -1, WifiSpace::G2_4, false}, + WifiChannel{2612, -1, WifiSpace::G2_4, false, false, false}, + //WifiChannel{2632, -1, WifiSpace::G2_4, false}, + //WifiChannel{2652, -1, WifiSpace::G2_4, false}, + //WifiChannel{2672, -1, WifiSpace::G2_4, false}, + WifiChannel{2692, -1, WifiSpace::G2_4, false, false, false}, + WifiChannel{2712, -1, WifiSpace::G2_4, false, false, false}, + //WifiChannel{2732, -1, WifiSpace::G2_4, false}, + }; +} + + +static std::vector get_channels_5G(){ + return std::vector{ + // https://en.wikipedia.org/wiki/List_of_WLAN_channels#5_GHz_(802.11a/h/j/n/ac/ax) + WifiChannel{5180, 36, WifiSpace::G5_8, true, true, true, true}, + WifiChannel{5200, 40, WifiSpace::G5_8, true, true, true, false}, + WifiChannel{5220, 44, WifiSpace::G5_8, true, true, true, true}, + WifiChannel{5240, 48, WifiSpace::G5_8, true, true, true, false}, + WifiChannel{5260, 52, WifiSpace::G5_8, true, true, true, true}, + WifiChannel{5280, 56, WifiSpace::G5_8, true, true, true, false}, + WifiChannel{5300, 60, WifiSpace::G5_8, true, true, true, true}, + WifiChannel{5320, 64, WifiSpace::G5_8, true, true, true, false}, + // These channel(s) are not valid Wi-Fi channels in all countries + WifiChannel{5340, 68, WifiSpace::G5_8, true, false, false}, // (Only on 20Mhz allowed in some) + WifiChannel{5360, 72, WifiSpace::G5_8, true, false, false}, + WifiChannel{5380, 76, WifiSpace::G5_8, true, false, false}, + WifiChannel{5400, 80, WifiSpace::G5_8, true, false, false}, + WifiChannel{5420, 84, WifiSpace::G5_8, true, false, false}, + WifiChannel{5440, 88, WifiSpace::G5_8, true, false, false}, + WifiChannel{5460, 92, WifiSpace::G5_8, true, false, false}, + WifiChannel{5480, 96, WifiSpace::G5_8, true, false, false}, + // part often disabled end + WifiChannel{5500, 100, WifiSpace::G5_8, true, true, true, true}, + WifiChannel{5520, 104, WifiSpace::G5_8, true, true, true, false}, + WifiChannel{5540, 108, WifiSpace::G5_8, true, true, true, true}, + WifiChannel{5560, 112, WifiSpace::G5_8, true, true, true, false}, + WifiChannel{5580, 116, WifiSpace::G5_8, true, true, true, true}, + WifiChannel{5600, 120, WifiSpace::G5_8, true, true, true, false}, + WifiChannel{5620, 124, WifiSpace::G5_8, true, true, true, true}, + WifiChannel{5640, 128, WifiSpace::G5_8, true, true, true, false}, + WifiChannel{5660, 132, WifiSpace::G5_8, true, true, true, true}, + WifiChannel{5680, 136, WifiSpace::G5_8, true, true, true, false}, + WifiChannel{5700, 140, WifiSpace::G5_8, true, true, true, true}, + WifiChannel{5720, 144, WifiSpace::G5_8, true, true, true, false}, + // There is a gap not usable in between 5720 and 5745 Mhz + // For some reason, there is a 25Mhz jump here. Weird stuff ... + WifiChannel{5745, 149, WifiSpace::G5_8, true, true, true, true}, + WifiChannel{5765, 153, WifiSpace::G5_8, true, true, true, false}, + WifiChannel{5785, 157, WifiSpace::G5_8, true, true, true, true}, + WifiChannel{5805, 161, WifiSpace::G5_8, true, true, true, false}, + WifiChannel{5825, 165, WifiSpace::G5_8, true, true, true, true}, + // starting from here, often disabled territory begins again + WifiChannel{5845, 169, WifiSpace::G5_8, true, true, true, false}, + WifiChannel{5865, 173, WifiSpace::G5_8, true, true, true, true}, + // This one (177) is listed in wikipedia, but not valid in any country - but it works on rtl8812bu + WifiChannel{5885, 177, WifiSpace::G5_8, true, true, true, false}, + // this one does not work on bu, au no idea - for now, hide it + WifiChannel{5905, 181, WifiSpace::G5_8, true, false, false, true}, + }; +}; +// Returns all Wi-Fi channels 5G that are legal in any country +static std::vector get_channels_5G_legal_at_least_one_country(){ + const auto channels=get_channels_5G(); + std::vector ret; + for(auto& channel:channels){ + if(channel.is_legal_at_least_one_country){ + ret.push_back(channel); + } + } + return ret; +} +// Returns all Wi-Fi channels 2.4G that are legal in at least one country +static std::vector get_channels_2G_legal_at_least_one_country(){ + const auto channels=get_channels_2G(); + std::vector ret; + for(auto& channel:channels){ + if(channel.is_legal_at_least_one_country){ + ret.push_back(channel); + } + } + return ret; +} + + +static std::vector get_all_channels_2G_5G() { + std::vector channels{}; + OHDUtil::vec_append(channels, get_channels_2G()); + OHDUtil::vec_append(channels, get_channels_5G()); + return channels; +} + +static std::vector get_all_channel_frequencies(const std::vector& channels) { + std::vector frequencies{}; + frequencies.reserve(channels.size()); + for (const auto& channel : channels) { + frequencies.push_back(channel.frequency); + } + return frequencies; +} + +// Returns the corresponding Wi-Fi Channel if there is one +// since the mavlink setting is an int, this might not always be possible (and the frequency is then 100% not possible) and therefore should be discarded / fixed +static std::optional channel_from_frequency(uint32_t frequency) { + const auto channels = get_all_channels_2G_5G(); + for (const auto& channel : channels) { + if (channel.frequency == frequency) { + return channel; + } + } + return std::nullopt; +} + +static WifiSpace get_space_from_frequency(uint32_t frequency){ + auto channel= channel_from_frequency(frequency); + if(!channel.has_value()){ + return WifiSpace::G5_8; + } + return channel.value().space; +} + +static std::vector frequencies_to_channels(const std::vector& frequencies){ + std::vector ret; + auto channels=get_all_channels_2G_5G(); + for(const auto freq:frequencies){ + auto tmp= channel_from_frequency(freq); + if(tmp.has_value()){ + ret.push_back(tmp.value()); + } + } + return ret; +} + +static std::vector get_openhd_channels_1_to_5(){ + std::vector frequencies={5700,5745,5785,5825,5865}; + return frequencies_to_channels(frequencies); +} + +} +#endif // OPENHD_OPENHD_OHD_INTERFACE_INC_WIFI_CHANNEL_H_ diff --git a/app/telemetry/telemetry.pri b/app/telemetry/telemetry.pri index fe0e7fa3a..468f00337 100644 --- a/app/telemetry/telemetry.pri +++ b/app/telemetry/telemetry.pri @@ -12,6 +12,7 @@ SOURCES += \ $$PWD/connection/udp_connection.cpp \ $$PWD/models/fcmapmodel.cpp \ $$PWD/settings/documentedparam.cpp \ + $$PWD/settings/frequencyhelper.cpp \ $$PWD/settings/pollutionhelper.cpp \ $$PWD/settings/wblinksettingshelper.cpp \ $$PWD/action/impl/xparam.cpp \ @@ -36,7 +37,9 @@ HEADERS += \ $$PWD/connection/tcp_connection.h \ $$PWD/settings/documentedparam.h \ $$PWD/action/impl/xparam.h \ + $$PWD/settings/frequencyhelper.h \ $$PWD/settings/pollutionhelper.h \ + $$PWD/settings/wifi_channel.h \ $$PWD/util/geodesi_helper.h \ $$PWD/util/mavlink_enum_to_string.h \ $$PWD//util/openhd_defines.hpp \ diff --git a/qml/main.qml b/qml/main.qml index dfbefe530..4c31079be 100755 --- a/qml/main.qml +++ b/qml/main.qml @@ -93,26 +93,6 @@ ApplicationWindow { } } - // Loads the proper (platform-dependent) video widget for the secondary video, if enabled. - // r.n we only have a gstreamer - qmlglsink implementation for it - Loader { - anchors.fill: parent - z: 2.0 - anchors.bottom: parent.bottom - source: { - if(settings.dev_qopenhd_n_cameras>1){ - // R.N the only implementation for secondary video - if (QOPENHD_ENABLE_GSTREAMER_QMLGLSINK){ - return "../video/SecondaryVideoGStreamer.qml"; - }else{ - console.warn("No secondary video implementation") - } - }else{ - console.debug("Scondary video disabled"); - } - return ""; - } - } ColorPicker { id: colorPicker diff --git a/qml/qml.qrc b/qml/qml.qrc index 8afac7f5f..09d76a5bc 100644 --- a/qml/qml.qrc +++ b/qml/qml.qrc @@ -182,7 +182,6 @@ video/SecondaryVideoGStreamer.qml video/MainVideoQSG.qml ui/widgets/VideoBitrateWidgetSecondary.qml - ui/widgets/RecordVideoWidget.qml ui/widgets/RCRssiWidget.qml video/ExpMainVideoAndroid.qml ui/elements/WorkaroundMessageBox.qml @@ -238,7 +237,7 @@ ui/elements/ArmDisarmSlider.qml ui/elements/SimpleProgressBar.qml ui/elements/ButtonGreen.qml - ui/configpopup/openhd_settings/DialoqueFreqChangeArmed.qml + ui/configpopup/openhd_settings/DialoqueFreqChangeAirGnd.qml ui/configpopup/openhd_settings/FreqComboBoxRow.qml ui/configpopup/status/QOpenHDVersionCard.qml ui/elements/CardToast.qml @@ -258,5 +257,9 @@ ui/configpopup/openhd_settings/PopupEnableSTBCLDPC.qml ui/widgets/PerformanceHorizonWidget2.qml ui/configpopup/status/StatusCardsColumn.qml + ui/elements/SimpleLeftRightText.qml + video/SecondaryVideoGstreamerPane.qml + ui/elements/SettingsHeaderElement.qml + ui/configpopup/qopenhd_settings/AppWidgetStyleSettingsView.qml diff --git a/qml/ui/HUDOverlayGrid.qml b/qml/ui/HUDOverlayGrid.qml index afe49440a..feeda9815 100644 --- a/qml/ui/HUDOverlayGrid.qml +++ b/qml/ui/HUDOverlayGrid.qml @@ -13,6 +13,8 @@ import "./widgets/map" import "../resources" as Resources import "./elements" +import "../video" + Item { id: hudOverlayGrid focus: true @@ -21,6 +23,8 @@ Item { property bool m_show_vertical_center_indicator: false property bool m_show_horizontal_center_indicator: false + //scale: settings.dev_some_scale + //signal settingsButtonClicked property int m_highlight_index : 0 property int m_MAX_ITEM_INDEX: 15 @@ -147,20 +151,19 @@ Item { var ret=downlink if(index==0)return settingsButtonHighlight; if(index==1)return downlink; - if(index==2)return record_video_widget; - if(index==3)return wBLinkRateControlWidget; - if(index==4)return qRenderStatsWidget; - if(index==5)return bitrate1; - if(index==6)return bitrate2; - if(index==7)return air_status; - if(index==8)return ground_status; - if(index==9)return uplink; - if(index==10)return air_battery; - if(index==11)return flight_mode; - if(index==12)return throttleWidget; - if(index==13)return missionWidget; - if(index==14)return gps; - if(index==15)return home_distance; + if(index==2)return wBLinkRateControlWidget; + if(index==3)return qRenderStatsWidget; + if(index==4)return bitrate1; + if(index==5)return bitrate2; + if(index==6)return air_status; + if(index==7)return ground_status; + if(index==8)return uplink; + if(index==9)return air_battery; + if(index==10)return flight_mode; + if(index==11)return throttleWidget; + if(index==12)return missionWidget; + if(index==13)return gps; + if(index==14)return home_distance; //if(index==13)return uplink; console.log("Invalid index"); return ret; @@ -197,29 +200,29 @@ Item { } Keys.onPressed: (event)=> { - console.log("HUDOverlayGrid::Key was pressed:"+event); - if (event.key == Qt.Key_Return) { - //console.log("enter was pressed"); - event.accepted = true; - dummy_joystick_enter() - }else if(event.key == Qt.Key_Left){ - //console.log("left was pressed") - event.accepted=true; - dummy_joystick_left(); - }else if(event.key == Qt.Key_Right){ - //console.log("right was pressed") - event.accepted=true; - dummy_joystick_right(); - }else if(event.key == Qt.Key_Up){ - //console.log("up was pressed") - event.accepted=true; - dummy_joystick_up() - }else if(event.key == Qt.Key_Down){ - //console.log("down was pressed") - event.accepted=true; - dummy_joystick_down() - } - } + console.log("HUDOverlayGrid::Key was pressed:"+event); + if (event.key == Qt.Key_Return) { + //console.log("enter was pressed"); + event.accepted = true; + dummy_joystick_enter() + }else if(event.key == Qt.Key_Left){ + //console.log("left was pressed") + event.accepted=true; + dummy_joystick_left(); + }else if(event.key == Qt.Key_Right){ + //console.log("right was pressed") + event.accepted=true; + dummy_joystick_right(); + }else if(event.key == Qt.Key_Up){ + //console.log("up was pressed") + event.accepted=true; + dummy_joystick_up() + }else if(event.key == Qt.Key_Down){ + //console.log("down was pressed") + event.accepted=true; + dummy_joystick_down() + } + } Image { id: settingsButton @@ -250,224 +253,227 @@ Item { color: "transparent" } } + + // Dirty, in between a HUD element and not a HUD element + // placed here because of the focus issue + SecondaryVideoGStreamer{ + id: secondary_video + } + Item{ id: actual_hud_elements width: parent.width height: parent.height - // By default on top row - // -------------------------------------------------------------------------- - LinkDownRSSIWidget { - id: downlink - m_next_item: record_video_widget - } - RecordVideoWidget { - id: record_video_widget - } - WBLinkRateControlWidget{ - id: wBLinkRateControlWidget - } - // exp - QRenderStatsWidget { - id: qRenderStatsWidget - } - VideoBitrateWidgetPrimary { - id: bitrate1 - } - VideoBitrateWidgetSecondary { - id: bitrate2 - } - SOCStatusWidgetAir { - id: air_status - } - SOCStatusWidgetGround { - id: ground_status - } - LinkUpRSSIWidget { - id: uplink - } - Sidebar{ - id: sidebar - } - // ---------------------------------------------------------------------------- - // TODO SORT ME + // By default on top row + // -------------------------------------------------------------------------- + LinkDownRSSIWidget { + id: downlink + } + WBLinkRateControlWidget{ + id: wBLinkRateControlWidget + } + // exp + QRenderStatsWidget { + id: qRenderStatsWidget + } + VideoBitrateWidgetPrimary { + id: bitrate1 + } + VideoBitrateWidgetSecondary { + id: bitrate2 + } + SOCStatusWidgetAir { + id: air_status + } + SOCStatusWidgetGround { + id: ground_status + } + LinkUpRSSIWidget { + id: uplink + } + Sidebar{ + id: sidebar + } + // ---------------------------------------------------------------------------- + // TODO SORT ME - // + 0% cpu - MessageHUD { - id: messageHUD - } + // + 0% cpu + MessageHUD { + id: messageHUD + } - GroundPowerWidget { - id: groundPowerWidget - } + GroundPowerWidget { + id: groundPowerWidget + } - // + 0% cpu - AirBatteryWidget { - id: air_battery - } + // + 0% cpu + AirBatteryWidget { + id: air_battery + } - // + 0% cpu - FlightModeWidget { - id: flight_mode - } + // + 0% cpu + FlightModeWidget { + id: flight_mode + } - // + 0% cpu - GPSWidget { - id: gps - } + // + 0% cpu + GPSWidget { + id: gps + } - // + 0% cpu - HomeDistanceWidget { - id: home_distance - } + // + 0% cpu + HomeDistanceWidget { + id: home_distance + } - // + 0% cpu - FlightTimeWidget { - id: flight_timer - } + // + 0% cpu + FlightTimeWidget { + id: flight_timer + } - // + 0% cpu - FlightDistanceWidget { - id: flight_distance - } + // + 0% cpu + FlightDistanceWidget { + id: flight_distance + } - // + 0% cpu - FlightMahWidget { - id: flight_mah - } + // + 0% cpu + FlightMahWidget { + id: flight_mah + } - // + 0% cpu - FlightMahKmWidget { - id: flight_mah_km - } + // + 0% cpu + FlightMahKmWidget { + id: flight_mah_km + } - // + 0% cpu - ImuTempWidget { - id: imu_temp - } + // + 0% cpu + ImuTempWidget { + id: imu_temp + } - // + 0% cpu - PressTempWidget { - id: press_temp - } - RCRssiWidget { - id: rc_rssi_widget - } + // + 0% cpu + PressTempWidget { + id: press_temp + } + RCRssiWidget { + id: rc_rssi_widget + } - AirspeedTempWidget { - id: airspeed_temp - } + AirspeedTempWidget { + id: airspeed_temp + } - // + 0% cpu - EscTempWidget { - id: esc_temp - } + // + 0% cpu + EscTempWidget { + id: esc_temp + } - // + 12% cpu - HorizonWidget { - id: horizonWidget - } + // + 12% cpu + HorizonWidget { + id: horizonWidget + } - PerformanceHorizonWidget2{ - id: performanceHorizonWidget - } + PerformanceHorizonWidget2{ + id: performanceHorizonWidget + } - // + 7% cpu - FpvWidget { - id: fpvWidget - } + // + 7% cpu + FpvWidget { + id: fpvWidget + } - // + 4% cpu - AltitudeWidget { - id: altitudeWidget - } + // + 4% cpu + AltitudeWidget { + id: altitudeWidget + } - // + 0% cpu - AltitudeSecondWidget { - id: altitudesecondWidget - } + // + 0% cpu + AltitudeSecondWidget { + id: altitudesecondWidget + } - // + 17% cpu - SpeedWidget { - id: speedWidget - } + // + 17% cpu + SpeedWidget { + id: speedWidget + } - SpeedSecondWidget { - id: speedSecondWidget - } + SpeedSecondWidget { + id: speedSecondWidget + } - // +3% cpu - HeadingWidget { - id: headingWidget - } + // +3% cpu + HeadingWidget { + id: headingWidget + } - // + 0% cpu - ArrowWidget { - id: arrowWidget - } + // + 0% cpu + ArrowWidget { + id: arrowWidget + } - // + 0% cpu - ThrottleWidget { - id: throttleWidget - scale: 0.7 - } + // + 0% cpu + ThrottleWidget { + id: throttleWidget + scale: 0.7 + } - // + 0% cpu - ControlWidget { - id: controlWidget - // scale: 0.7 - } + // + 0% cpu + ControlWidget { + id: controlWidget + // scale: 0.7 + } - // + 0% cpu - GPIOWidget { - id: gpioWidget - } + // + 0% cpu + GPIOWidget { + id: gpioWidget + } - // + 3% cpu - VibrationWidget { - id: vibrationWidget - } + // + 3% cpu + VibrationWidget { + id: vibrationWidget + } - VerticalSpeedSimpleWidget{ - id: vssimpleWidget - } - VerticalSpeedGaugeWidget{ - id: vsgaugewidget - } + VerticalSpeedSimpleWidget{ + id: vssimpleWidget + } + VerticalSpeedGaugeWidget{ + id: vsgaugewidget + } - // + 0% cpu - WindWidget { - id: windWidget - } + // + 0% cpu + WindWidget { + id: windWidget + } - // + 3% cpu - RollWidget { - id: rollWidget - } + // + 3% cpu + RollWidget { + id: rollWidget + } - MissionWidget { - id: missionWidget - } + MissionWidget { + id: missionWidget + } - AoaWidget { - id: aoaWidget - } + AoaWidget { + id: aoaWidget + } - MapWidget { - id: mapWidget - } + MapWidget { + id: mapWidget + } - ExampleWidget { - id: exampleWidget - } + ExampleWidget { + id: exampleWidget + } - DistanceSensorWidget{ - id: distancesensorwidget - } + DistanceSensorWidget{ + id: distancesensorwidget + } - UAVTimeWiget{ - id: uavtimewidget - } + UAVTimeWiget{ + id: uavtimewidget + } } // Extra element - allows customizing the OSD color(s) and more diff --git a/qml/ui/configpopup/ConfigPopup.qml b/qml/ui/configpopup/ConfigPopup.qml index 2af0d6f00..cdc9f3175 100644 --- a/qml/ui/configpopup/ConfigPopup.qml +++ b/qml/ui/configpopup/ConfigPopup.qml @@ -38,10 +38,6 @@ Rectangle { hudOverlayGrid.regain_focus(); } - function showAppSettings(i) { - console.log("TEST show app settings:"+i); - } - function side_bar_regain_focus(){ sidebar.focus = true; } @@ -162,82 +158,87 @@ Rectangle { _qopenhd.show_toast("No joystick navigation for this panel"); } } - - Column { + ScrollView{ width: parent.width + height: parent.height + contentHeight: navigation_buttons_column.height + Column { + id: navigation_buttons_column + width: parent.width + anchors.top: parent.top + // Status + ConfigPopupSidebarButton{ + id: power + m_icon_text: "\uf21e" //"\uf011" + m_description_text: "Status" + m_selection_index: 0 + } - anchors.top: parent.top - - // Status - ConfigPopupSidebarButton{ - id: power - m_icon_text: "\uf21e" //"\uf011" - m_description_text: "Status" - m_selection_index: 0 - } - - // OpenHD Settings - MavlinkAllSettingsPanel - ConfigPopupSidebarButton{ - id: openhd_button - m_icon_text: "\uf085" - m_description_text: "OpenHD" - m_selection_index: 1 - } + // OpenHD Settings - MavlinkAllSettingsPanel + ConfigPopupSidebarButton{ + id: openhd_button + m_icon_text: "\uf085" + m_description_text: "OpenHD" + m_selection_index: 1 + } - // (QOpenHD Settings - AppSettingsPanel) - // OSD - ConfigPopupSidebarButton{ - id: qopenhd_button - m_icon_text: "\uf013" - m_description_text: "OSD" - m_selection_index: 2 - } + // (QOpenHD Settings - AppSettingsPanel) + // OSD + ConfigPopupSidebarButton{ + id: qopenhd_button + m_icon_text: "\uf013" + m_description_text: "OSD" + m_selection_index: 2 + } - // Log - ConfigPopupSidebarButton{ - id: log_button - m_icon_text: "\uf0c9" - m_description_text: "Log" - m_selection_index: 3 - } + // Log + ConfigPopupSidebarButton{ + id: log_button + m_icon_text: "\uf0c9" + m_description_text: "Log" + m_selection_index: 3 + } - // RC - ConfigPopupSidebarButton{ - id: rc - m_icon_text: "\uf11b" - m_description_text: "RC" - m_selection_index: 4 - } + // RC + ConfigPopupSidebarButton{ + id: rc + m_icon_text: "\uf11b" + m_description_text: "RC" + m_selection_index: 4 + } - // We only need the connect panel on android (external device) - // On localhost, QOpenHD "automatically" connects due to udp localhost method - ConfigPopupSidebarButton{ - visible: m_show_connect_option - id: connect_button - m_icon_text: "\uf6ff" - m_description_text: "Connect" - m_selection_index: 5 - } + // We only need the connect panel on android (external device) + // On localhost, QOpenHD "automatically" connects due to udp localhost method + ConfigPopupSidebarButton{ + visible: m_show_connect_option + id: connect_button + m_icon_text: "\uf6ff" + m_description_text: "Connect" + m_selection_index: 5 + } - // Credits and copyright - ConfigPopupSidebarButton{ - id: credits - m_icon_text: "\uf005" - m_description_text: "Credits" - m_selection_index: 6 - } + // Credits and copyright + ConfigPopupSidebarButton{ + id: credits + m_icon_text: "\uf005" + m_description_text: "Credits" + m_selection_index: 6 + } - // Developer stats - ConfigPopupSidebarButton{ - id: developerstats - m_icon_text: "\uf0ad" - m_description_text: "DEV" - m_selection_index: 7 + // Developer stats + ConfigPopupSidebarButton{ + id: developerstats + m_icon_text: "\uf0ad" + m_description_text: "DEV" + m_selection_index: 7 + } } } } + + StackLayout { id: mainStackLayout anchors.bottom: parent.bottom diff --git a/qml/ui/configpopup/connect/PaneConnectionMode.qml b/qml/ui/configpopup/connect/PaneConnectionMode.qml index f05786825..6bf06c9ab 100644 --- a/qml/ui/configpopup/connect/PaneConnectionMode.qml +++ b/qml/ui/configpopup/connect/PaneConnectionMode.qml @@ -98,7 +98,13 @@ Rectangle{ Button{ text: "Android Tethering" Layout.preferredWidth: 180 - onClicked: _qopenhd.android_open_tethering_settings() + onClicked: { + if(_qopenhd.is_android()){ + _qopenhd.android_open_tethering_settings() + }else{ + _qopenhd.show_toast("Only available on android"); + } + } } ButtonIconInfoText { m_info_text: "1) Connect your phone via high quality USB cable to your ground station.\n\n"+ @@ -112,6 +118,9 @@ Rectangle{ text: "Wifi tethering" Layout.preferredWidth: 180 //TODO enable hotspot + onClicked: { + _messageBoxInstance.set_text_and_show("Please connect:\nWiFi Name: openhd_air/openhd_ground.\n PW: openhdopenhd") + } } ButtonIconInfoText { m_info_text: "1) Check status if your air / ground unit supports WiFi hotspot\n\n"+ @@ -125,6 +134,9 @@ Rectangle{ text: "Passive Eth tethering" Layout.preferredWidth: 180 //TODO disable active tethering and enable passive when clicking the button + onClicked: { + _qopenhd.show_toast("Please read info"); + } } ButtonIconInfoText { m_info_text: "1) Disable ETH_HOTSPOT_E and Enable ETH_PASSIVE_F\n\n"+ @@ -138,6 +150,9 @@ Rectangle{ text: "Active Eth tethering" Layout.preferredWidth: 180 //TODO disable passive tethering and enable active when clicking the button + onClicked: { + _qopenhd.show_toast("Please read info"); + } } ButtonIconInfoText { m_info_text: "1) Disable ETH_PASSIVE_F and Enable ETH_HOTSPOT_E\n\n"+ diff --git a/qml/ui/configpopup/log/LogMessagesStatusView.qml b/qml/ui/configpopup/log/LogMessagesStatusView.qml index 8a408f04f..a90be3110 100644 --- a/qml/ui/configpopup/log/LogMessagesStatusView.qml +++ b/qml/ui/configpopup/log/LogMessagesStatusView.qml @@ -17,7 +17,6 @@ Item { property int rowHeight: 64 property int elementHeight: 48 - property int elementComboBoxWidth: 300 // Tab bar for selecting items in stack layout TabBar { id: selectItemInStackLayoutBar diff --git a/qml/ui/configpopup/openhd_settings/DialoqueFreqChangeAirGnd.qml b/qml/ui/configpopup/openhd_settings/DialoqueFreqChangeAirGnd.qml new file mode 100644 index 000000000..9dc43f634 --- /dev/null +++ b/qml/ui/configpopup/openhd_settings/DialoqueFreqChangeAirGnd.qml @@ -0,0 +1,124 @@ +import QtQuick 2.12 +import QtQuick.Controls 2.12 +import QtQuick.Layouts 1.12 +import QtQuick.Dialogs 1.0 +import QtQuick.Controls.Material 2.12 + +import "../../elements" + +// Dialoque that is shown to the user when the FC is armed and he wants to change frequency +// Once the user clicks the warning away, proceed as if FC is not armed +Card { + id: dialoqueFreqChangeAirGnd + width: 360 + height: 340 + z: 5.0 + anchors.centerIn: parent + cardName: get_card_title_string() + cardNameColor: "black" + visible: false + + property int m_wanted_frequency: -1 + + property bool m_fc_is_armed: true + + function close(){ + visible=false; + enabled=false; + } + + function initialize_and_show_frequency(frequency){ + m_wanted_frequency=frequency + visible=true; + enabled=true; + // Show warning if + if(_fcMavlinkSystem.is_alive && _fcMavlinkSystem.armed){ + m_fc_is_armed=true; + }else{ + m_fc_is_armed=false; + } + } + + function get_card_title_string(){ + return "Frequency "+m_wanted_frequency+"Mhz" + } + + function get_card_body_string(){ + const channel_nr=_frequencyHelper.get_frequency_channel_nr(m_wanted_frequency); + const channel_nr_openhd=_frequencyHelper.get_frequency_openhd_race_band(m_wanted_frequency); + return "Set AIR and GROUND to CHANNEL ["+channel_nr+"]\n"+ + "("+m_wanted_frequency+" Mhz) ?"; + + } + + cardBody: Item{ + height: 200 + width: 320 + + Text{ + id: description + width: parent.width + height: parent.height /2; + leftPadding: 12 + rightPadding: 12 + wrapMode: Text.WordWrap + text: get_card_body_string(); + } + Text{ + anchors.top: description.bottom + anchors.left: parent.left + anchors.right: parent.right + anchors.bottom: parent.bottom + leftPadding: 12 + rightPadding: 12 + wrapMode: Text.WordWrap + text: "WARNING !\n CHANGING FREQUENCY WHILE ARMED IS NOT RECOMMENDED !"; + color: "red" + visible: m_fc_is_armed + } + } + hasFooter: true + cardFooter: Item { + anchors.fill: parent + RowLayout{ + anchors.fill: parent + + Button{ + Layout.preferredWidth: 150 + text: "CANCEL" + onPressed: { + dialoqueFreqChangeAirGnd.visible=false; + } + } + + Button{ + Layout.preferredWidth: 150 + text: "YES"; + Material.accent: m_fc_is_armed ? Material.Red : Material.Grey + highlighted: m_fc_is_armed ? true : false; + + onPressed: { + var result= _wbLinkSettingsHelper.change_param_air_and_ground_frequency(m_wanted_frequency); + if(result==0){ + _qopenhd.show_toast("SUCCESS"); + dialoqueFreqChangeAirGnd.visible=false; + return; + }else if(result==-1){ + // Air unit rejected + _qopenhd.show_toast("ERROR - AIR REJECTED"); + return; + }else if(result==-2){ + // Couldn't reach air unit + var error_message_not_reachable="Couldn't reach air unit -"; + _qopenhd.show_toast("ERROR -COULDN'T REACH AIR"); + return; + } + // Really really bad + _messageBoxInstance.set_text_and_show("Something went wrong - please use 'FIND AIR UNIT' to fix"); + dialoqueFreqChangeAirGnd.visible=false; + } + } + } + } +} + diff --git a/qml/ui/configpopup/openhd_settings/DialoqueFreqChangeArmed.qml b/qml/ui/configpopup/openhd_settings/DialoqueFreqChangeArmed.qml deleted file mode 100644 index f76ba635f..000000000 --- a/qml/ui/configpopup/openhd_settings/DialoqueFreqChangeArmed.qml +++ /dev/null @@ -1,86 +0,0 @@ -import QtQuick 2.12 -import QtQuick.Controls 2.12 -import QtQuick.Layouts 1.12 -import QtQuick.Dialogs 1.0 -import QtQuick.Controls.Material 2.12 - -import "../../elements" - -// Dialoque that is shown to the user when the FC is armed and he wants to change frequency -// Once the user clicks the warning away, proceed as if FC is not armed -Card { - id: dialoqueFreqChangeArmed - width: 360 - height: 340 - z: 5.0 - anchors.centerIn: parent - cardName: get_card_title_string() - cardNameColor: "black" - visible: false - - property int m_wanted_frequency: -1 - - function close(){ - visible=false; - enabled=false; - } - - function initialize_and_show_frequency(frequency){ - m_wanted_frequency=frequency - m_wanted_channel_width=-1 - m_type=0; - visible=true; - enabled=true; - } - - function get_card_title_string(){ - return "Frequency "+m_wanted_frequency+"Mhz" - } - - function get_card_body_string(){ - return "WARNING ! Changing frequency while armed is not recommended - while unlikely, changing them needs synchronization and therefore can fail, -after which you have to perform a channel scan to reconnect to your air unit."; - } - - cardBody: Item{ - height: 200 - width: 320 - - Text{ - width: parent.width - height: parent.height - leftPadding: 12 - rightPadding: 12 - wrapMode: Text.WordWrap - text: get_card_body_string(); - } - } - hasFooter: true - cardFooter: Item { - anchors.fill: parent - RowLayout{ - anchors.fill: parent - ButtonRed{ - Layout.preferredWidth: 180 - Layout.alignment: Qt.AlignLeft - Layout.leftMargin: 12 - text: qsTr("CONTINUE ANYWAY") - onPressed: { - dialoqueFreqChangeArmed.visible=false - // Call function from MavlinkExtraWBParamPanel - change_frequency_sync_otherwise_handle_error(m_wanted_frequency,true/*ignore armed state*/) - } - } - ButtonGreen{ - Layout.preferredWidth: 140 - Layout.alignment: Qt.AlignRight - Layout.rightMargin: 12 - text: qsTr("Okay") - onPressed: { - dialoqueFreqChangeArmed.visible=false - } - } - } - } -} - diff --git a/qml/ui/configpopup/openhd_settings/DialoqueFreqChangeGndOnly.qml b/qml/ui/configpopup/openhd_settings/DialoqueFreqChangeGndOnly.qml index 70e4dddbe..ed2162fde 100644 --- a/qml/ui/configpopup/openhd_settings/DialoqueFreqChangeGndOnly.qml +++ b/qml/ui/configpopup/openhd_settings/DialoqueFreqChangeGndOnly.qml @@ -40,7 +40,7 @@ Card { property string m_info_string_frequency: "Please use the channel scan to find your air unit, then change frequency."+ "Otherwise, you can manually change your ground station frequency,"+ -"leaving your air unit untouched - thiis can be quicker than a channel scan if you know your air unit frequency." +"leaving your air unit untouched - this can be quicker than a channel scan if you know your air unit frequency." property string m_info_ground_only: "WARNING: This changes your ground unit frequency without changing your air unit frequency !" diff --git a/qml/ui/configpopup/openhd_settings/FreqComboBoxRow.qml b/qml/ui/configpopup/openhd_settings/FreqComboBoxRow.qml index 135420d81..56c5eeee2 100644 --- a/qml/ui/configpopup/openhd_settings/FreqComboBoxRow.qml +++ b/qml/ui/configpopup/openhd_settings/FreqComboBoxRow.qml @@ -28,6 +28,8 @@ Rectangle{ property int m_openhd_race_band: -1 + property int m_pollution_pps: -1 + color: "transparent" anchors.fill: parent @@ -83,14 +85,13 @@ Rectangle{ }*/ Text{ Layout.alignment: Qt.AlignLeft - Layout.preferredWidth: 90 + Layout.preferredWidth: 60 text: "Default" font.family: "Font Awesome 5 Free" color: "green" visible: m_openhd_race_band==2 font.pixelSize: comboBoxFreq.font.pixelSize } - Text{ // recommended / openhd race band channel Layout.alignment: Qt.AlignRight Layout.preferredWidth: 60 @@ -102,5 +103,29 @@ Rectangle{ color: "green" font.pixelSize: comboBoxFreq.font.pixelSize } + // Channel occupancy estimate + Item{ + Layout.preferredWidth: parent.height + Layout.preferredHeight: parent.height + height: parent.height + width: height + Layout.alignment: Qt.AlignRight + Rectangle{// Channel occupancy estimate + height: parent.height * 2/3; + width: height + radius: width + anchors.centerIn: parent + color: { + if(m_pollution_pps<0){ + return "gray" + } + if(m_pollution_pps<1)return "green"; + if(m_pollution_pps<20) return "orange"; + return "red"; + } + border.width: 2 + border.color: "black" + } + } } } diff --git a/qml/ui/configpopup/openhd_settings/MavlinkOpenHDWBParamPanel.qml b/qml/ui/configpopup/openhd_settings/MavlinkOpenHDWBParamPanel.qml index 2277f4c91..17bd50434 100644 --- a/qml/ui/configpopup/openhd_settings/MavlinkOpenHDWBParamPanel.qml +++ b/qml/ui/configpopup/openhd_settings/MavlinkOpenHDWBParamPanel.qml @@ -39,58 +39,54 @@ Rectangle{ for(var i = 0; i < model.count; ++i) if (model.get(i).value===value) return i return -1 } - // try and update the combobox to the retrieved value(value != index) - function update_combobox(_combobox,_value){ - var _index=find_index(_combobox.model,_value) - if(_index >= 0){ - _combobox.currentIndex=_index; - } - } function fc_is_armed(){ return _fcMavlinkSystem.armed } ListModel{ - id: supported_frequencies_model - ListElement {title: "Unknown"; value:-1; radar: false; recommended: false; openhd_raceband_nr: -1} + id: frequencies_model_all + ListElement {title: "Unknown"; value_frequency_mhz:-1} + } + ListModel{ + id: frequencies_model_openhd_channels_only + ListElement {title: "Unknown"; value_frequency_mhz:-1} } - function show_popup_message(message){ - _messageBoxInstance.set_text_and_show(message) + function create_list_models_frequency(){ + frequencies_model_all.clear(); + const frequencies_all=_frequencyHelper.get_frequencies(false); + for(var i=0;i= 0; + function update_frequency_combobox(){ + if(m_simplify_enable){ + comboBoxFreq.model=frequencies_model_openhd_channels_only; + }else{ + comboBoxFreq.model=frequencies_model_all; + } + if(_wbLinkSettingsHelper.curr_channel_mhz>0){ + var index=find_index(comboBoxFreq.model,_wbLinkSettingsHelper.curr_channel_mhz); + if(index>=0){ + comboBoxFreq.currentIndex=index; }else{ - append_this_value=true; - } - if(append_this_value){ - supported_frequencies_model.append({title: text, value: frequency, radar:radar, recommended: recommended, openhd_raceband_nr: openhd_raceband}) + comboBoxFreq.currentIndex=0; + console.log("Seems not to be a valid channel "+_wbLinkSettingsHelper.curr_channel_mhz) } - } - var index=find_index(supported_frequencies_model,_wbLinkSettingsHelper.curr_channel_mhz); - comboBoxFreq.model=supported_frequencies_model - if(index>=0){ - comboBoxFreq.currentIndex=index; }else{ - comboBoxFreq.currentIndex=0; - console.log("Seems not to be a valid channel "+_wbLinkSettingsHelper.curr_channel_mhz) + comboBoxFreq.currentIndex=-1; } } @@ -102,20 +98,19 @@ Rectangle{ } function function_rebuild_ui(){ + update_frequency_combobox(); console.log("function_rebuild_ui:"+_wbLinkSettingsHelper.ui_rebuild_models); if(_wbLinkSettingsHelper.ui_rebuild_models<=0)return - create_list_model_supported(); - //update_pollution_graph(); - pollution_chart_view.update(); + popup_analyze_channels.update(); } // function close_all_dialoques(){ - pollution_chart_view.close() - channel_scan_progress_view.close(); - change_tx_power_popup.close(); + popup_analyze_channels.close() + popup_scan_channels.close(); + popup_change_tx_power.close(); dialoqueFreqChangeGndOnly.close(); - dialoqueFreqChangeArmed.close(); + dialoqueFreqChangeAirGnd.close(); popup_enable_stbc_ldpc.close(); } @@ -130,51 +125,8 @@ Rectangle{ Component.onCompleted: { close_all_dialoques(); - } - // - - // ------------------- PART HELPER FOR CURRENT LOSS / POLLUTION / THROTTLE BEGIN ------------------- - // ------------------- PART HELPER FOR CURRENT LOSS / POLLUTION / THROTTLE END ------------------- - - - // Changes either the frequency or channel width - // This one need to be synced, so we have ( a bit complicated, but quite natural for the user) dialoque for the cases where we need to handle errors / show a warning - function change_frequency_sync_otherwise_handle_error(frequency_mhz,ignore_armed_state){ - console.log("change_frequency_sync_otherwise_handle_error: "+"FREQ:"+frequency_mhz+"Mhz"); - // Ground needs to be alive and well - if(!_ohdSystemGround.is_alive){ - _messageBoxInstance.set_text_and_show("Ground unit not alive",5); - return; - } - // Air needs to be alive and well - otherwise we show the "do you want to change gnd only" dialoque - if(!_ohdSystemAir.is_alive){ - var error_message_not_alive="AIR Unit not alive -" - dialoqueFreqChangeGndOnly.initialize_and_show_frequency(frequency_mhz,error_message_not_alive); - return; - } - // FC needs to be disarmed - otherwise show warning - const fc_currently_armed = (_fcMavlinkSystem.is_alive && _fcMavlinkSystem.armed)// || true; - if(fc_currently_armed && ignore_armed_state===false){ - dialoqueFreqChangeArmed.initialize_and_show_frequency(frequency_mhz) - return; - } - var result= _wbLinkSettingsHelper.change_param_air_and_ground_frequency(frequency_mhz); - if(result==0){ - var message="Succesfully set air and ground to FREQUENCY: "+frequency_mhz+"Mhz"; - _messageBoxInstance.set_text_and_show(message,5); - return; - }else if(result==-1){ - // Air unit rejected - _messageBoxInstance.set_text_and_show("Air unit does not support this value",5); - return; - }else if(result==-2){ - // Couldn't reach air unit - var error_message_not_reachable="Couldn't reach air unit -" - dialoqueFreqChangeGndOnly.initialize_and_show_frequency(frequency_mhz,error_message_not_reachable); - return; - } - // Really really bad - _messageBoxInstance.set_text_and_show("Something went wrong - please use 'FIND AIR UNIT' to fix"); + create_list_models_frequency(); + update_frequency_combobox(); } function get_text_wifi_tx_power(air){ @@ -195,6 +147,7 @@ Rectangle{ contentWidth: main_column_layout.width //ScrollBar.vertical.policy: ScrollBar.AlwaysOn ScrollBar.vertical.interactive: true + visible: (!popup_analyze_channels.visible && !popup_enable_stbc_ldpc.visible && !popup_change_tx_power.visible && !popup_scan_channels.visible) ColumnLayout{ Layout.fillWidth: true @@ -209,7 +162,7 @@ Rectangle{ implicitHeight: frequency_area_layout.implicitHeight+5 radius: 10 - GridLayout { + ColumnLayout { id: frequency_area_layout Layout.fillWidth: true Layout.fillHeight: true @@ -222,75 +175,29 @@ Rectangle{ font.bold: true } - ComboBox { - id: comboBoxFreq - model: supported_frequencies_model - textRole: "title" - implicitWidth: elementComboBoxWidth - currentIndex: 0 - delegate: ItemDelegate { - width: comboBoxFreq.width - contentItem: FreqComboBoxRow{ - m_main_text: title - m_selection_tpye: (value===_wbLinkSettingsHelper.curr_channel_mhz) ? 1 : 0 - m_is_2G: value < 3000 && value > 100 - m_show_radar: radar - m_openhd_race_band: openhd_raceband_nr - } - highlighted: comboBoxFreq.highlightedIndex === index - } - Layout.row: 1 - Layout.column: 0 - } - Button{ - text: "APPLY" - id: buttonSwitchFreq - //enabled: false - onClicked: { - var selectedValue=supported_frequencies_model.get(comboBoxFreq.currentIndex).value - if(selectedValue<=100){ - _messageBoxInstance.set_text_and_show("Please select a valid frequency",5); - return; - } - change_frequency_sync_otherwise_handle_error(selectedValue,-1,false); - } - //Material.background: fc_is_armed() ? Material.Red : Material.Normal; - enabled: _wbLinkSettingsHelper.ui_rebuild_models>=0 && (_ohdSystemGround.is_alive && _ohdSystemGround.wb_gnd_operating_mode==0); - Layout.row: 1 - Layout.column: 1 - } - Switch{ - Layout.row: 1 - Layout.column: 2 - text: "SIMPLIFY" - checked: true - onCheckedChanged: { - if(m_simplify_enable!=checked){ - m_simplify_enable=checked; - function_rebuild_ui(); - } - } - } - ButtonIconInfo{ - Layout.row: 1 - Layout.column: 3 - onClicked: { - var text="SIMPLIFY: Show recommended channels only. These channels usually have the least amount of pollution by WiFi APs and most FPV antennas are tuned to those Frequncies.\n"+ - "OpenHD works best on them in most scenarios,and you can use 20Mhz and 40Mhz dynamically without issues (40Mhz spacing by default).\n"+ - "Otherwise, show all channels supported by harware (ADVANCED USERS ONLY).\n"; - _messageBoxInstance.set_text_and_show(text) - } - } RowLayout{ - Layout.row: 2 - Layout.column: 0 - Layout.fillWidth: true - Layout.fillHeight: true - id: gnd_op_mode_status - //SimpleProgressBar{ - //} - Text{ - text: { + ComboBox { + id: comboBoxFreq + //model: supported_frequencies_model + //model: frequencies_model_openhd_channels_only + textRole: "title" + implicitWidth: elementComboBoxWidth + currentIndex: 0 + delegate: ItemDelegate { + width: comboBoxFreq.width + contentItem: FreqComboBoxRow{ + m_main_text: title + m_selection_tpye: (value_frequency_mhz===_wbLinkSettingsHelper.curr_channel_mhz) ? 1 : 0 + m_is_2G: value_frequency_mhz < 3000 && value_frequency_mhz > 100 + m_show_radar: _frequencyHelper.get_frequency_radar(value_frequency_mhz) + m_openhd_race_band: _frequencyHelper.get_frequency_openhd_race_band(value_frequency_mhz) + m_pollution_pps: _pollutionHelper.pollution_get_last_scan_pollution_for_frequency(value_frequency_mhz) + } + highlighted: comboBoxFreq.highlightedIndex === index + } + Layout.row: 1 + Layout.column: 0 + displayText: { if(!_ohdSystemGround.is_alive)return "GND NOT ALIVE"; if(_ohdSystemGround.wb_gnd_operating_mode==1){ return "SCANNING"; @@ -303,86 +210,159 @@ Rectangle{ } return _wbLinkSettingsHelper.curr_channel_mhz+"@"+_wbLinkSettingsHelper.curr_channel_width_mhz+" Mhz"; } + onActivated: { + console.log("onActivated:"+currentIndex); + if(currentIndex<0)return; + const frequency_mhz=comboBoxFreq.model.get(currentIndex).value_frequency_mhz + console.log("Selected frequency: "+frequency_mhz); + if(!_frequencyHelper.hw_supports_frequency_threadsafe(frequency_mhz)){ + _qopenhd.show_toast("your HW does not support "+frequency_mhz+" Mhz"); + return; + } + if(_wbLinkSettingsHelper.curr_channel_mhz==frequency_mhz){ + console.log("Already at frequency "+frequency_mhz); + return; + } + if(!_ohdSystemAir.is_alive){ + var error_message_not_alive="AIR Unit not alive -" + dialoqueFreqChangeGndOnly.initialize_and_show_frequency(frequency_mhz,error_message_not_alive); + return; + } + // Change the freuquency + dialoqueFreqChangeAirGnd.initialize_and_show_frequency(frequency_mhz); + } + enabled: _ohdSystemGround.is_alive && _ohdSystemGround.wb_gnd_operating_mode==0; + } + Switch{ Layout.row: 1 - Layout.column: 0 - verticalAlignment: Text.AlignVCenter + Layout.column: 1 + Layout.columnSpan: 1 + text: "SIMPLIFY" + checked: true + onCheckedChanged: { + if(m_simplify_enable!=checked){ + m_simplify_enable=checked; + function_rebuild_ui(); + } + } + } + ButtonIconInfo{ + Layout.row: 1 + Layout.column: 2 + onClicked: { + var text="Please select a channel / frequency free of noise and interference. The current loss / pollution / throttle stats below can help,"+ + "as well as the analyze channels feature or a frequency analyzer on your phone. SIMPLIFY: Show OpenHD standard channels [1-5] only - they "+ + " often are free of wifi pollution and should be used. Only disable SIMPLIFY if you know exactly why." + _messageBoxInstance.set_text_and_show(text) + } } } - Button{ + + + + RowLayout{ Layout.row: 2 - Layout.column: 1 - id: b_find_air_unit - text: "SCAN" - enabled: _ohdSystemGround.is_alive - onClicked: { - close_all_dialoques(); - channel_scan_progress_view.open() + Layout.column: 0 + Layout.columnSpan: 3 + Item{ // FILLER + Layout.preferredWidth: 30 + Layout.minimumWidth: 0 } - SequentialAnimation { - running: false - loops: 4 - id: anim_find_air_unit - // Expand the button - PropertyAnimation { - target: b_find_air_unit - property: "scale" - to: 1.5 - duration: 200 - easing.type: Easing.InOutQuad + Button{ + Layout.preferredWidth: 150 + id: b_find_air_unit + text: "SCAN" + enabled: _ohdSystemGround.is_alive + onClicked: { + close_all_dialoques(); + popup_scan_channels.open() } - // Shrink back to normal - PropertyAnimation { - target: b_find_air_unit - property: "scale" - to: 1.0 - duration: 200 - easing.type: Easing.InOutQuad + SequentialAnimation { + running: false + loops: 4 + id: anim_find_air_unit + // Expand the button + PropertyAnimation { + target: b_find_air_unit + property: "scale" + to: 1.5 + duration: 200 + easing.type: Easing.InOutQuad + } + // Shrink back to normal + PropertyAnimation { + target: b_find_air_unit + property: "scale" + to: 1.0 + duration: 200 + easing.type: Easing.InOutQuad + } } } - } - Button{ - Layout.row: 2 - Layout.column: 2 - text: "ANALYZE" - enabled: _ohdSystemGround.is_alive - onClicked: { - close_all_dialoques(); - pollution_chart_view.open() + Item{ // FILLER + Layout.preferredWidth: 30 + Layout.minimumWidth: 0 } - } - ButtonIconInfo{ - Layout.row: 2 - Layout.column: 3 - onClicked: { - var text="SCAN: Scan for a running openhd air unit (required if you switch between different air / ground stations or re-flash the image.)\n"+ - "ANALYZE: Analyze all channels for WiFi pollution. If any of the default openhd channels is not polluted, they should be used."+ - "NOTE: Analogue FPV or other digital FPV systems won't show up during analyze - read the wiki for more info."; - _messageBoxInstance.set_text_and_show(text) + Button{ + Layout.preferredWidth: 150 + text: "ANALYZE" + enabled: _ohdSystemGround.is_alive + onClicked: { + close_all_dialoques(); + popup_analyze_channels.open() + } + } + Item{ // FILLER + Layout.preferredWidth: 30 + Layout.minimumWidth: 0 + } + ButtonIconInfo{ + onClicked: { + var text="SCAN: Similar to analoque channel scan, find a running air unit by checking all possible channels (frequencies).\n\n"+ + "ANALYZE: Analyze channels for WiFi pollution. Read the wiki for more info."; + _messageBoxInstance.set_text_and_show(text) + } } } - // Row 3 RowLayout{ - Layout.row: 3 - Layout.column: 0 - Layout.columnSpan: 3 Text{ + Layout.preferredHeight: 50 + Layout.preferredWidth: 120 text:{ - "LOSS %:"+_ohdSystemGround.curr_rx_packet_loss_perc + "LOSS:\n"+_ohdSystemGround.curr_rx_packet_loss_perc+"%" } color: _ohdSystemGround.curr_rx_packet_loss_perc > 5 ? "red" : "black" verticalAlignment: Qt.AlignVCenter + horizontalAlignment: Qt.AlignHCenter + font.bold: true } Text{ + Layout.preferredHeight: 50 + Layout.preferredWidth: 120 text: { - return "POLLUTION pps:"+_ohdSystemGround.wb_link_curr_foreign_pps + return "POLLUTION:\n"+_ohdSystemGround.wb_link_curr_foreign_pps+"pps" } color: _ohdSystemGround.wb_link_curr_foreign_pps > 20 ? "red" : "black" + verticalAlignment: Qt.AlignVCenter + horizontalAlignment: Qt.AlignHCenter + font.bold: true } Text{ + Layout.preferredHeight: 50 + Layout.preferredWidth: 120 text: { - return "THROTTLE:"+_ohdSystemAir.curr_n_rate_adjustments + return "THROTTLE:\n"+_ohdSystemAir.curr_n_rate_adjustments } color: _ohdSystemAir.curr_n_rate_adjustments > 0 ? "red" : "black" + verticalAlignment: Qt.AlignVCenter + horizontalAlignment: Qt.AlignHCenter + font.bold: true + } + ButtonIconInfo{ + onClicked: { + var text="High Loss / Pollution / active throttle hint at a polluted channel." + _messageBoxInstance.set_text_and_show(text) + } } ButtonIconWarning{ visible: /*_ohdSystemAir.is_alive &&*/ (_ohdSystemGround.curr_rx_packet_loss_perc > 5 || _ohdSystemGround.wb_link_curr_foreign_pps > 20 || _ohdSystemAir.curr_n_rate_adjustments > 0) @@ -403,132 +383,115 @@ Rectangle{ color: m_background_color radius: 10 - GridLayout { + RowLayout { id: tx_power_layout Layout.fillWidth: true Layout.fillHeight: true Text{ - Layout.row: 0 - Layout.column: 0 - Layout.columnSpan: 2 text: "TX POWER" font.bold: true } Text{ - Layout.row: 1 - Layout.column: 0 + Layout.preferredWidth: 120 text: "AIR:\n "+get_text_wifi_tx_power(true) + verticalAlignment: Qt.AlignVCenter + horizontalAlignment: Qt.AlignHCenter + font.bold: true } Button{ - Layout.row: 1 - Layout.column: 1 - text: "CHANGE" + text: "EDIT" enabled: _ohdSystemAir.is_alive onClicked: { close_all_dialoques(); - change_tx_power_popup.m_is_air=true; - change_tx_power_popup.open() + popup_change_tx_power.m_is_air=true; + popup_change_tx_power.open() } } Text{ - Layout.row: 2 - Layout.column: 0 + Layout.preferredWidth: 120 text: "GND:\n"+get_text_wifi_tx_power(false) + verticalAlignment: Qt.AlignVCenter + horizontalAlignment: Qt.AlignHCenter + font.bold: true } Button{ - Layout.row: 2 - Layout.column: 1 - text: "CHANGE" + text: "EDIT" enabled: _ohdSystemGround.is_alive onClicked: { close_all_dialoques(); - change_tx_power_popup.m_is_air=false; - change_tx_power_popup.open() + popup_change_tx_power.m_is_air=false; + popup_change_tx_power.open() } } + } + } + Rectangle { + implicitWidth: main_scroll_view.width + implicitHeight: stbc_ldpc_layout.implicitHeight + id: stbc_ldpc_background + color: m_background_color + radius: 10 + + RowLayout { + id: stbc_ldpc_layout + Layout.fillWidth: true + Layout.fillHeight: true // STBC / LDPC Text{ width: 200 - Layout.row: 0 - Layout.column: 3 - Layout.columnSpan: 2 text: "ADVANCED (STBC,LDPC)" font.bold: true horizontalAlignment: Qt.AlignHCenter } Text{ - Layout.row: 1 - Layout.column: 3 + Layout.preferredWidth: 120 text: "AIR:\n"+get_text_stbc_ldpc(true); + verticalAlignment: Qt.AlignVCenter horizontalAlignment: Qt.AlignHCenter + font.bold: true } Text{ - Layout.row: 2 - Layout.column: 3 + Layout.preferredWidth: 120 text: "GND:\n"+get_text_stbc_ldpc(false); + verticalAlignment: Qt.AlignVCenter horizontalAlignment: Qt.AlignHCenter + font.bold: true } - ButtonIconInfo{ - Layout.row: 1 - Layout.column: 4 - onClicked: { - _messageBoxInstance.set_text_and_show("STBC / LDPC : Greatly increases range, but requires 2 RF paths (2 Antennas) on BOTH your air and ground station."+ - "WARNING: Enabling STBC with the wrong hardware (only 1 antenna / only one rf path) results in no connectivity "+ - "and you need to re-flash your air / ground unit to recover !"); - } - } + Button{ - Layout.row: 2 - Layout.column: 4 text: "EDIT"; //enabled: true enabled: _ohdSystemAir.is_alive && _ohdSystemGround.is_alive && (_wbLinkSettingsHelper.ui_rebuild_models>=0) && (_ohdSystemGround.wb_stbc_enabled!=true || _ohdSystemGround.wb_lpdc_enabled!=true || _ohdSystemAir.wb_stbc_enabled!=true || _ohdSystemAir.wb_lpdc_enabled!=true); onClicked: { + close_all_dialoques(); popup_enable_stbc_ldpc.open() } } - } - } - // - /*Rectangle { - implicitWidth: main_scroll_view.width - implicitHeight: tx_power_layout.implicitHeight - id: rpi_cam_selector_layout_background - color: m_background_color - radius: 10 - - GridLayout { - id: rpi_cam_selector_layout - Layout.fillWidth: true - Layout.fillHeight: true - Text{ - Layout.row: 0 - Layout.column: 0 - Layout.columnSpan: 2 - text: "RPI CAM SELECTOR" - font.bold: true - } - Button{ + ButtonIconInfo{ Layout.row: 1 - Layout.column: 0 - text: "EDIT" + Layout.column: 4 + onClicked: { + _messageBoxInstance.set_text_and_show("STBC / LDPC : Greatly increases range, but requires 2 RF paths (2 Antennas) on BOTH your air and ground station."+ + "WARNING: Enabling STBC with the wrong hardware (only 1 antenna / only one rf path) results in no connectivity "+ + "and you need to re-flash your air / ground unit to recover !"); + } } } - }*/ + } } } PopupAnalyzeChannels{ - id: pollution_chart_view + id: popup_analyze_channels } PopupScanChannels{ - id: channel_scan_progress_view + id: popup_scan_channels } PopupTxPowerEditor{ - id: change_tx_power_popup + id: popup_change_tx_power } PopupEnableSTBCLDPC{ id: popup_enable_stbc_ldpc @@ -537,7 +500,7 @@ Rectangle{ DialoqueFreqChangeGndOnly{ id: dialoqueFreqChangeGndOnly } - DialoqueFreqChangeArmed{ - id: dialoqueFreqChangeArmed + DialoqueFreqChangeAirGnd{ + id: dialoqueFreqChangeAirGnd } } diff --git a/qml/ui/configpopup/openhd_settings/MavlinkParamEditor.qml b/qml/ui/configpopup/openhd_settings/MavlinkParamEditor.qml index d1a0ce459..f1cbf6add 100644 --- a/qml/ui/configpopup/openhd_settings/MavlinkParamEditor.qml +++ b/qml/ui/configpopup/openhd_settings/MavlinkParamEditor.qml @@ -20,7 +20,7 @@ import "../../elements" // Aligned to the right, and width can be set by total_width property manually Rectangle{ - property int total_width: 300 + property int total_width: 400 width: total_width height: parent.height diff --git a/qml/ui/configpopup/openhd_settings/PopupAnalyzeChannels.qml b/qml/ui/configpopup/openhd_settings/PopupAnalyzeChannels.qml index b4b918395..223fa488f 100644 --- a/qml/ui/configpopup/openhd_settings/PopupAnalyzeChannels.qml +++ b/qml/ui/configpopup/openhd_settings/PopupAnalyzeChannels.qml @@ -17,14 +17,21 @@ import "../../elements" import QtCharts 2.0 Rectangle{ - width: parent.width-12 - height: parent.height*2/3; + id: main_background + //width: parent.width-12 + //height: parent.height*2/3; + width: parent.width + height: parent.height anchors.centerIn: parent color: "#ADD8E6" border.color: "black" border.width: 3 property bool m_normalize_data: false; + property int m_chart_view_minimum_width: 1280; + property int m_chart_view_minimum_width2: 640; + + property bool m_chart_enlarged: false; function open(){ visible=true @@ -38,97 +45,180 @@ Rectangle{ pollution_chart.update_pollution_graph(); } - property string m_info_string: "Analyze channels for pollution by wifi access points."+ -"NOTE: This only gives a hint at free channels, using a proper channel analyzer (e.g. on the phone) is recommended."+ -"PLEASE DO NOT CHANGE SETTINGS WHILE ANALYZING." + ListModel{ + id: model_filter + ListElement {title: "NO FILTER"; value: 0} + ListElement {title: "2.4G ONLY"; value: 1} + ListElement {title: "5.8G ONLY"; value: 2} + } + + property string m_info_string: "Analyze channels for pollution by wifi access points.\n"+ +"NOTE: This only gives a hint at free channels, using a proper channel analyzer (e.g. on the phone) is recommended !\n"+ +"In short: Any frequency with red bars (small or big) should not be used, unless there are no options / other reasons to do so." + + ColumnLayout{ + id: main_layout + anchors.fill: parent + anchors.leftMargin: 10 + anchors.rightMargin: 10 - RowLayout{ - id: top_elements - Layout.fillWidth: true - Item{ //Spacer + Item{ Layout.fillWidth: true - } - Switch{ - text: "NORMALIZE" - checked: m_normalize_data - onCheckedChanged: { - m_normalize_data=checked - pollution_chart.update_pollution_graph(); + Layout.preferredHeight: 60 + Text{ // TITLE + anchors.fill: parent + text: "ANALYZE (POLLUTION)"; + verticalAlignment: Qt.AlignVCenter + horizontalAlignment: Qt.AlignHCenter + font.bold: true } - } - Button{ - Layout.alignment: Qt.AlignHCenter - text: "START" - onClicked: { - var result=_wbLinkSettingsHelper.start_analyze_channels() - if(result!==true){ - _qopenhd.show_toast("Busy,please try again later",true); - }else{ - _qopenhd.show_toast("STARTED, THIS MIGHT TAKE A WHILE !"); + Button{ + anchors.right: parent.right + anchors.top: parent.top + text: "CLOSE" + onClicked: { + if(_ohdSystemGround.is_alive && _ohdSystemGround.wb_gnd_operating_mode==2){ + _qopenhd.show_toast("STILL ANALYZING, PLEASE WAIT ...",); + return; + } + close() } } - enabled: _ohdSystemGround.is_alive && _ohdSystemGround.wb_gnd_operating_mode==0 } - ButtonIconInfo{ - Layout.alignment: Qt.AlignHCenter - onClicked: { - _messageBoxInstance.set_text_and_show(m_info_string) + RowLayout{ + SimpleProgressBar{ + Layout.preferredWidth: 400 + Layout.minimumWidth: 100 + Layout.preferredHeight: 40 + impl_curr_progress_perc: _wbLinkSettingsHelper.analyze_progress_perc + impl_show_progress_text: true } - } - Item{ //Spacer - Layout.fillWidth: true - } - } - // Argh, need to manually place the button - Button{ - anchors.top: parent.top - anchors.right: parent.right - text: "CLOSE" - onClicked: { - if(_ohdSystemGround.is_alive && _ohdSystemGround.wb_gnd_operating_mode==2){ - _qopenhd.show_toast("STILL ANALYZING",); - return; + Button{ + Layout.alignment: Qt.AlignLeft + text: "START" + onClicked: { + var result=_wbLinkSettingsHelper.start_analyze_channels() + if(result!==true){ + _qopenhd.show_toast("Busy,please try again later",true); + }else{ + _qopenhd.show_toast("STARTED, THIS MIGHT TAKE A WHILE !"); + } + } + enabled: _ohdSystemGround.is_alive && _ohdSystemGround.wb_gnd_operating_mode==0 + } + ButtonIconInfo{ + Layout.alignment: Qt.AlignLeft + onClicked: { + _messageBoxInstance.set_text_and_show(m_info_string) + } } - close() } - } - ChartView { - anchors.top: top_elements.bottom - title: "WiFi pollution estimate" - width: parent.width - height: parent.height-top_elements.height - legend.alignment: Qt.AlignBottom - antialiasing: true - - id: pollution_chart - - function update_pollution_graph(){ - //const frequencies_list = _wbLinkSettingsHelper.get_pollution_qstringlist(); - //bar_axis_x.categories=frequencies_list; - //const supported_frequencies = _wbLinkSettingsHelper.get_supported_frequencies(); - const supported_frequencies = _wbLinkSettingsHelper.get_supported_frequencies_filtered(1); - var categories = _wbLinkSettingsHelper.pollution_frequencies_int_to_qstringlist(supported_frequencies); - var values = _wbLinkSettingsHelper.pollution_frequencies_int_get_pollution(supported_frequencies,m_normalize_data); - bar_axis_x.categories=categories; - bar_set.values=values; + RowLayout{ + Text{ + Layout.preferredWidth: 200 + Layout.minimumWidth: 100 + Layout.preferredHeight: 40 + text: { + if(_wbLinkSettingsHelper.current_analyze_frequency<=0){ + return ""; + } + return "Analyzed "+_wbLinkSettingsHelper.current_analyze_frequency+" Mhz ..."; + } + verticalAlignment: Qt.AlignVCenter + horizontalAlignment: Qt.AlignHCenter + } + ComboBox { + Layout.preferredWidth: 150 + Layout.minimumWidth: 50 + id: comboBoxFilter + model: model_filter + textRole: "title" + onCurrentIndexChanged: { + pollution_chart.update_pollution_graph(); + } + } + Switch{ + text: "NORMALIZE" + checked: m_normalize_data + onCheckedChanged: { + m_normalize_data=checked + pollution_chart.update_pollution_graph(); + } + } } + ScrollView{ + id: chart_scroll_view + Layout.fillWidth: true + Layout.fillHeight: true + contentWidth: pollution_chart.width + ScrollBar.horizontal.interactive: true + + ChartView { + id: pollution_chart + title: "WiFi pollution estimate" + //width: main_background.width>m_chart_view_minimum_width ? main_background.width : m_chart_view_minimum_width; + width: { + const screen_width = main_layout.width; + if(comboBoxFilter.currentIndex==0){ + return screen_width>m_chart_view_minimum_width ? screen_width : m_chart_view_minimum_width; + } + if(comboBoxFilter.currentIndex==1){ + return screen_width + } + return screen_width>m_chart_view_minimum_width2 ? screen_width : m_chart_view_minimum_width2; + } + //width: m_chart_enlarged ? 1280 : main_background.width + height: parent.height + legend.alignment: Qt.AlignBottom + antialiasing: true + + function update_pollution_graph(){ + //const frequencies_list = _wbLinkSettingsHelper.get_pollution_qstringlist(); + //bar_axis_x.categories=frequencies_list; + //const supported_frequencies = _wbLinkSettingsHelper.get_supported_frequencies(); + const all_40Mhz_frequencies_unfiltered=_frequencyHelper.get_frequencies_all_40Mhz(); + const all_40Mhz_frequencies = _frequencyHelper.filter_frequencies(all_40Mhz_frequencies_unfiltered,comboBoxFilter.currentIndex); + var categories = _pollutionHelper.pollution_frequencies_int_to_qstringlist(all_40Mhz_frequencies); + var values = _pollutionHelper.pollution_frequencies_int_get_pollution(all_40Mhz_frequencies,m_normalize_data); + bar_axis_x.categories=categories; + bar_set.values=values; + } - BarSeries { - id: hm_bar_series - axisX: BarCategoryAxis { - id: bar_axis_x - categories: ["DUMMY0", "DUMMY1", "DUMMY3", "DUMMY4" ] - //min: "0" - //max: "500" - } - BarSet { - id: bar_set - label: "Pollution (pps)"; - values: [5,10,3,100] - //values: [0,0,0,0] - color: "red" + BarSeries { + id: hm_bar_series + axisX: BarCategoryAxis { + id: bar_axis_x + categories: ["DUMMY0", "DUMMY1", "DUMMY3", "DUMMY4" ] + //min: "0" + //max: "500" + } + BarSet { + id: bar_set + label: "Pollution (pps)"; + values: [5,10,3,100] + //values: [0,0,0,0] + color: "red" + } + } } + /*Button{ + anchors.top: pollution_chart.top + anchors.left: pollution_chart.left + text: "ENLARGE" + onClicked: { + m_chart_enlarged = !m_chart_enlarged; + } + }*/ } + // Filler + //Item{ + // Layout.fillWidth: true + // Layout.fillHeight: true + //} } + + + + } diff --git a/qml/ui/configpopup/openhd_settings/PopupEnableSTBCLDPC.qml b/qml/ui/configpopup/openhd_settings/PopupEnableSTBCLDPC.qml index f5e7f6e7b..ec850adda 100644 --- a/qml/ui/configpopup/openhd_settings/PopupEnableSTBCLDPC.qml +++ b/qml/ui/configpopup/openhd_settings/PopupEnableSTBCLDPC.qml @@ -16,8 +16,10 @@ import "../../elements" Rectangle{ id: main_background - width: parent.width-12 - height: parent.height*2/3; + //width: parent.width-12 + //height: parent.height*2/3; + width: parent.width + height: parent.height anchors.centerIn: parent color: "#ADD8E6" border.color: "black" @@ -50,53 +52,36 @@ Rectangle{ ListElement {title: "GND: 2 RF PATHS / ANTENNAS"; value: 2} } - GridLayout{ + ColumnLayout{ id: main_row_layout - Layout.fillWidth: true - Layout.fillHeight: true - Layout.leftMargin: 5 - Layout.rightMargin: 5 + anchors.fill: parent + anchors.leftMargin: 10 + anchors.rightMargin: 10 - Text{ - id: stbc_warning_text - Layout.row: 0 - Layout.column: 0 - text: "WARNING:\n YOU NEED TO REFLASH YOUR AIR / GROUND UNIT\nIF YOU ENABLE STBC / LDPC ON UNSUPPORTED HW"; - color: "red" - width: main_background.width - height: 200 - horizontalAlignment: Qt.AlignHCenter - verticalAlignment: Qt.AlignVCenter - font.pixelSize: 15 - wrapMode: Text.WordWrap - SequentialAnimation { - running: false - loops: 3 - id: anim_warn_user_stbc - // Expand the button - PropertyAnimation { - target: stbc_warning_text - property: "scale" - to: 2.0 - duration: 300 - easing.type: Easing.InOutQuad - } - // Shrink back to normal - PropertyAnimation { - target: stbc_warning_text - property: "scale" - to: 1.0 - duration: 300 - easing.type: Easing.InOutQuad + Item{ + Layout.fillWidth: true + Layout.preferredHeight: 80 + Text{ // TITLE + anchors.fill: parent + text: "ADVANCED - STBC / LDPC" + verticalAlignment: Qt.AlignVCenter + horizontalAlignment: Qt.AlignHCenter + font.bold: true + } + Button{ + text: "CLOSE" + anchors.top: parent.top + anchors.right: parent.right + onClicked: { + close() } } } + ComboBox { - Layout.row: 1 - Layout.column: 0 id: comboBoxNAntennasAir Layout.minimumWidth: 100 - Layout.preferredWidth: 350 + Layout.preferredWidth: 450 model: model_n_antennas_air textRole: "title" font.pixelSize: 14 @@ -107,11 +92,9 @@ Rectangle{ } } ComboBox { - Layout.row: 2 - Layout.column: 0 id: comboBoxNAntennasGnd Layout.minimumWidth: 100 - Layout.preferredWidth: 350 + Layout.preferredWidth: 450 model: model_n_antennas_gnd textRole: "title" font.pixelSize: 14 @@ -123,8 +106,6 @@ Rectangle{ } Button{ id: button_enable - Layout.row: 3 - Layout.column: 0 text: "ENABLE" enabled: comboBoxNAntennasAir.currentIndex==2 && comboBoxNAntennasGnd.currentIndex==2; font.pixelSize: 14 @@ -138,24 +119,54 @@ Rectangle{ } } Text{ - Layout.row: 4 - Layout.column: 0 + Layout.fillWidth: true + Layout.preferredHeight: 40 visible: !button_enable.enabled text: "CAN ONLY BE ENABLED IF BOTH AIR AND GND UNIT HAVE 2 RF PATHS / ANTENNAS"; font.pixelSize: 14 + verticalAlignment: Qt.AlignVCenter + horizontalAlignment: Qt.AlignLeft } - // ---------------- - } - - Button{ - text: "CLOSE" - anchors.top: parent.top - anchors.right: parent.right - onClicked: { - close() + Text{ + id: stbc_warning_text + text: "WARNING:\n YOU NEED TO REFLASH YOUR AIR / GROUND UNIT\nIF YOU ENABLE STBC / LDPC ON UNSUPPORTED HW"; + color: "red" + Layout.fillWidth: true + height: 200 + verticalAlignment: Qt.AlignVCenter + horizontalAlignment: Qt.AlignHCenter + font.pixelSize: 15 + wrapMode: Text.WordWrap + SequentialAnimation { + running: false + loops: 3 + id: anim_warn_user_stbc + // Expand the button + PropertyAnimation { + target: stbc_warning_text + property: "scale" + to: 2.0 + duration: 300 + easing.type: Easing.InOutQuad + } + // Shrink back to normal + PropertyAnimation { + target: stbc_warning_text + property: "scale" + to: 1.0 + duration: 300 + easing.type: Easing.InOutQuad + } + } } + Item{ // Filler + Layout.row: 5 + Layout.column: 0 + Layout.columnSpan: 3 + Layout.fillWidth: true + Layout.fillHeight: true + } + // ---------------- } - - } diff --git a/qml/ui/configpopup/openhd_settings/PopupScanChannels.qml b/qml/ui/configpopup/openhd_settings/PopupScanChannels.qml index 277c1b461..3b4879578 100644 --- a/qml/ui/configpopup/openhd_settings/PopupScanChannels.qml +++ b/qml/ui/configpopup/openhd_settings/PopupScanChannels.qml @@ -15,8 +15,10 @@ import "../../../ui" as Ui import "../../elements" Rectangle{ - width: parent.width-12 - height: parent.height*2/3; + //width: parent.width-12 + //height: parent.height*2/3; + width: parent.width + height: parent.height anchors.centerIn: parent color: "#ADD8E6" border.color: "black" @@ -39,20 +41,68 @@ Rectangle{ ListElement {title: "All 5.8G channels (slow)"; value: 2} } - /*Rectangle{ - implicitWidth:main_grid_layout.width - implicitHeight: main_grid_layout.height - color: "#ADD8E6" - }*/ - - GridLayout{ - id: main_grid_layout - Layout.fillWidth: true - Layout.fillHeight: true + ColumnLayout{ + anchors.fill: parent + anchors.leftMargin: 10 + anchors.rightMargin: 10 + Item{ + Layout.fillWidth: true + Layout.preferredHeight: 80 + Text{ // TITLE + anchors.fill: parent + text: "SCAN (FIND AIR UNIT)"; + verticalAlignment: Qt.AlignVCenter + horizontalAlignment: Qt.AlignHCenter + font.bold: true + } + Button{ + anchors.right: parent.right + anchors.top: parent.top + text: "CLOSE" + onClicked: { + if(_ohdSystemGround.is_alive && _ohdSystemGround.wb_gnd_operating_mode==1){ + _qopenhd.show_toast("STILL SCANNING,PLEASE WAIT ..."); + return; + } + close() + } + } + } + RowLayout{ + SimpleProgressBar{ + Layout.preferredWidth: 400 + Layout.minimumWidth: 100 + Layout.preferredHeight: 40 + impl_curr_progress_perc: _wbLinkSettingsHelper.scan_progress_perc + impl_show_progress_text: true + } + Button{ + text: "START" + enabled: _ohdSystemGround.is_alive && _ohdSystemGround.wb_gnd_operating_mode==0 + onClicked: { + var how_many_freq_bands=comboBoxWhichFrequencyToScan.currentIndex + var how_many_bandwidths = 2; + console.log("Initate channel scan "+how_many_freq_bands+","+how_many_bandwidths) + var result = _wbLinkSettingsHelper.start_scan_channels(how_many_freq_bands,how_many_bandwidths) + if(result){ + _qopenhd.show_toast("Channel scan started, please wait",true) + }else{ + console.log("Cannot initiate channel scan"); + _qopenhd.show_toast("Busy,please try again later",true) + } + } + } + ButtonIconInfo{ + onClicked: { + _messageBoxInstance.set_text_and_show("Initiate Channel Scan (Find a running air unit). Similar to analogue TX / RX, this listens on each channel for a short time"+ + " to find a running openhd air unit."+ + "Quick if you are only using the 5 OpenHD recommended channels, otherwise"+ + " please specify the generic band and give it some time (There are a ton of possible channels, especially in 5.8G)") + } + } + } ComboBox { - Layout.row: 0 - Layout.column: 0 Layout.preferredWidth: 400 Layout.minimumWidth: 100 id: comboBoxWhichFrequencyToScan @@ -65,61 +115,18 @@ Rectangle{ } enabled: _ohdSystemGround.is_alive && _ohdSystemGround.wb_gnd_operating_mode==0 } - - Button{ - Layout.row: 0 - Layout.column: 1 - text: "START" - enabled: _ohdSystemGround.is_alive && _ohdSystemGround.wb_gnd_operating_mode==0 - onClicked: { - var how_many_freq_bands=comboBoxWhichFrequencyToScan.currentIndex - var how_many_bandwidths = 2; - console.log("Initate channel scan "+how_many_freq_bands+","+how_many_bandwidths) - var result = _wbLinkSettingsHelper.start_scan_channels(how_many_freq_bands,how_many_bandwidths) - if(result){ - _qopenhd.show_toast("Channel scan started, please wait",true) - }else{ - console.log("Cannot initiate channel scan"); - _qopenhd.show_toast("Busy,please try again later",true) - } - } - } - SimpleProgressBar{ - Layout.row: 1 - Layout.column: 0 - Layout.fillWidth: true - Layout.preferredHeight: 40 - Layout.preferredWidth: 400 - Layout.minimumWidth: 100 - impl_curr_progress_perc: _wbLinkSettingsHelper.scan_progress_perc - } - ButtonIconInfo{ - Layout.row: 1 - Layout.column: 1 - onClicked: { - _messageBoxInstance.set_text_and_show("Initiate Channel Scan (Find a running air unit). Similar to analogue TX / RX, this listens on each channel for a short time"+ - " to find a running openhd air unit."+ - "Quick if you are only using the 5 OpenHD recommended channels, otherwise"+ - " please specify the generic band and give it some time (There are a ton of possible channels, especially in 5.8G)") - } - } Text{ - Layout.row: 2 + Layout.row: 3 Layout.column: 0 text: _wbLinkSettingsHelper.scanning_text_for_ui font.pixelSize: 25 } - } - Button{ - anchors.top: parent.top - anchors.right: parent.right - text: "CLOSE" - onClicked: { - if(_ohdSystemGround.is_alive && _ohdSystemGround.wb_gnd_operating_mode==1){ - _qopenhd.show_toast("STILL SCANNING"); - return; - } - close() + Item{ // Filler + Layout.row: 4 + Layout.column: 0 + Layout.columnSpan: 3 + Layout.fillWidth: true + Layout.fillHeight: true } } } diff --git a/qml/ui/configpopup/openhd_settings/PopupTxPowerEditor.qml b/qml/ui/configpopup/openhd_settings/PopupTxPowerEditor.qml index 9ee38a2f5..2106a5856 100644 --- a/qml/ui/configpopup/openhd_settings/PopupTxPowerEditor.qml +++ b/qml/ui/configpopup/openhd_settings/PopupTxPowerEditor.qml @@ -15,13 +15,17 @@ import "../../../ui" as Ui import "../../elements" Rectangle{ - width: parent.width-12 - height: parent.height*2/3; + //width: parent.width-12 + //height: parent.height*2/3; + width: parent.width + height: parent.height anchors.centerIn: parent color: "#ADD8E6" border.color: "black" border.width: 3 + property int m_margin: 10 + property bool m_is_air: false property int m_user_selected_card_manufacturer: -1; @@ -214,10 +218,9 @@ Rectangle{ GridLayout{ id: main_row_layout - Layout.fillWidth: true - Layout.fillHeight: true - Layout.leftMargin: 5 - Layout.rightMargin: 5 + anchors.fill: parent + anchors.leftMargin: m_margin + anchors.rightMargin: m_margin //anchors.top: parent.top //anchors.bottom: parent.bottom //anchors.left: parent.left @@ -225,13 +228,28 @@ Rectangle{ //Layout.minimumWidth: 300 //Layout.preferredWidth: 600 - Text{ + Item{ Layout.row: 0 Layout.column: 0 - text: m_is_air ? "AIR TX Power" : "GND TX power"; - font.bold: true - horizontalAlignment: Qt.AlignHCenter - font.pixelSize: 14 + Layout.columnSpan: 4 + Layout.fillWidth: true + Layout.preferredHeight: 80 + Text{ // TITLE + anchors.fill: parent + text: "TX POWER "+(m_is_air ? "AIR" : "GROUND"); + verticalAlignment: Qt.AlignVCenter + horizontalAlignment: Qt.AlignHCenter + font.bold: true + } + Button{ + text: "CLOSE" + anchors.top: parent.top + anchors.right: parent.right + anchors.rightMargin: m_margin + onClicked: { + close() + } + } } // Text{ @@ -371,12 +389,6 @@ Rectangle{ "if armed or not."); } } - // FILLER - Item{ - Layout.row: 3 - Layout.column: 4 - Layout.fillWidth: true - } Text{ Layout.row: 4 Layout.column: 0 @@ -408,17 +420,13 @@ Rectangle{ verticalAlignment: Qt.AlignBottom font.pixelSize: 14 } - // ---------------- - } - - Button{ - text: "CLOSE" - anchors.top: parent.top - anchors.right: parent.right - onClicked: { - close() + Item{ // Filler + Layout.row: 6 + Layout.column: 0 + Layout.columnSpan: 3 + Layout.fillWidth: true + Layout.fillHeight: true } + // ---------------- } - - } diff --git a/qml/ui/configpopup/qopenhd_settings/AppDevSettingsView.qml b/qml/ui/configpopup/qopenhd_settings/AppDevSettingsView.qml index 535f60caa..6034c8132 100755 --- a/qml/ui/configpopup/qopenhd_settings/AppDevSettingsView.qml +++ b/qml/ui/configpopup/qopenhd_settings/AppDevSettingsView.qml @@ -18,7 +18,6 @@ ScrollView { width: parent.width height: parent.height contentHeight: manageColumn.height - visible: appSettingsBar.currentIndex == 5 clip: true diff --git a/qml/ui/configpopup/qopenhd_settings/AppGeneralSettingsView.qml b/qml/ui/configpopup/qopenhd_settings/AppGeneralSettingsView.qml index 89a963cba..b7a6c13c6 100755 --- a/qml/ui/configpopup/qopenhd_settings/AppGeneralSettingsView.qml +++ b/qml/ui/configpopup/qopenhd_settings/AppGeneralSettingsView.qml @@ -16,7 +16,6 @@ ScrollView { width: parent.width height: parent.height contentHeight: generalColumn.height - visible: appSettingsBar.currentIndex == 0 clip: true @@ -73,6 +72,56 @@ ScrollView { } } + Rectangle { + width: parent.width + height: rowHeight + color: (Positioner.index % 2 == 0) ? "#8cbfd7f3" : "#00000000" + + Text { + text: qsTr("Animation Smoothing,0 to disable") + font.weight: Font.Bold + font.pixelSize: 13 + anchors.leftMargin: 8 + verticalAlignment: Text.AlignVCenter + anchors.verticalCenter: parent.verticalCenter + width: 224 + height: elementHeight + anchors.left: parent.left + } + + Text { + text: Number(settings.smoothing).toLocaleString(Qt.locale(), 'f', 0) + "ms"; + font.pixelSize: 16 + anchors.right: smoothing_Slider.left + anchors.rightMargin: 12 + verticalAlignment: Text.AlignVCenter + anchors.verticalCenter: parent.verticalCenter + width: 32 + height: elementHeight + + } + + Slider { + id: smoothing_Slider + height: elementHeight + width: 210 + font.pixelSize: 14 + anchors.right: parent.right + anchors.verticalCenter: parent.verticalCenter + to : 1000 + from : 0 + stepSize: 25 + anchors.rightMargin: Qt.inputMethod.visible ? 78 : 18 + value: settings.smoothing + + // @disable-check M223 + onValueChanged: { + // @disable-check M222 + settings.smoothing = smoothing_Slider.value + } + } + } + Rectangle { width: parent.width diff --git a/qml/ui/configpopup/qopenhd_settings/AppScreenSettingsView.qml b/qml/ui/configpopup/qopenhd_settings/AppScreenSettingsView.qml index a100bd914..60915821b 100755 --- a/qml/ui/configpopup/qopenhd_settings/AppScreenSettingsView.qml +++ b/qml/ui/configpopup/qopenhd_settings/AppScreenSettingsView.qml @@ -16,7 +16,6 @@ ScrollView { width: parent.width height: parent.height contentHeight: screenColumn.height - visible: appSettingsBar.currentIndex == 3 clip: true diff --git a/qml/ui/configpopup/qopenhd_settings/AppSettingsPanel.qml b/qml/ui/configpopup/qopenhd_settings/AppSettingsPanel.qml index 69c827dcc..4c112a200 100755 --- a/qml/ui/configpopup/qopenhd_settings/AppSettingsPanel.qml +++ b/qml/ui/configpopup/qopenhd_settings/AppSettingsPanel.qml @@ -49,8 +49,14 @@ Rectangle { } TabButton { - y: 0 - text: qsTr("General") + text: qsTr("Widgets") + width: implicitWidth + height: 48 + font.pixelSize: 13 + } + + TabButton { + text: qsTr("Style") width: implicitWidth height: 48 font.pixelSize: 13 @@ -58,14 +64,15 @@ Rectangle { TabButton { y: 0 - text: qsTr("Vehicle") + text: qsTr("General") width: implicitWidth height: 48 font.pixelSize: 13 } TabButton { - text: qsTr("Widgets") + y: 0 + text: qsTr("Vehicle") width: implicitWidth height: 48 font.pixelSize: 13 @@ -104,23 +111,20 @@ Rectangle { anchors.bottom: parent.bottom anchors.bottomMargin: 0 - currentIndex: { - // console.log("index:"+appSettingsBar.currentIndex); - // for future use to set focus for goggle support - showAppSettings(appSettingsBar.currentIndex); + currentIndex: appSettingsBar.currentIndex - return appSettingsBar.currentIndex; + AppWidgetSettingsView{ + id: appWidgetSettingsView + } + AppWidgetStyleSettingsView{ + id: appWidgetStyleSettingsView } - AppGeneralSettingsView{ id: appGeneralSettingsView } AppVehicleSettingsView{ id: appVehicleSettingsView } - AppWidgetSettingsView{ - id: appWidgetSettingsView - } AppScreenSettingsView{ id: appScreenSettingsView } diff --git a/qml/ui/configpopup/qopenhd_settings/AppVehicleSettingsView.qml b/qml/ui/configpopup/qopenhd_settings/AppVehicleSettingsView.qml index a5c37e09f..ef6956e26 100755 --- a/qml/ui/configpopup/qopenhd_settings/AppVehicleSettingsView.qml +++ b/qml/ui/configpopup/qopenhd_settings/AppVehicleSettingsView.qml @@ -16,7 +16,6 @@ ScrollView { width: parent.width height: parent.height contentHeight: vehicleColumn.height - visible: appSettingsBar.currentIndex == 1 clip: true diff --git a/qml/ui/configpopup/qopenhd_settings/AppVideoSettingsView.qml b/qml/ui/configpopup/qopenhd_settings/AppVideoSettingsView.qml index a38441b32..740d53d1b 100755 --- a/qml/ui/configpopup/qopenhd_settings/AppVideoSettingsView.qml +++ b/qml/ui/configpopup/qopenhd_settings/AppVideoSettingsView.qml @@ -18,7 +18,6 @@ ScrollView { contentHeight: videoColumn.height clip: true - visible: appSettingsBar.currentIndex == 4 Item { anchors.fill: parent diff --git a/qml/ui/configpopup/qopenhd_settings/AppWidgetSettingsView.qml b/qml/ui/configpopup/qopenhd_settings/AppWidgetSettingsView.qml index 406c8b0af..22a0d4fca 100755 --- a/qml/ui/configpopup/qopenhd_settings/AppWidgetSettingsView.qml +++ b/qml/ui/configpopup/qopenhd_settings/AppWidgetSettingsView.qml @@ -16,7 +16,6 @@ ScrollView { width: parent.width height: parent.height contentHeight: widgetColumn.height - visible: appSettingsBar.currentIndex == 2 clip: true @@ -29,231 +28,13 @@ ScrollView { anchors.left: parent.left anchors.right: parent.right - Rectangle { - width: parent.width - height: rowHeight - color: (Positioner.index % 2 == 0) ? "#8cbfd7f3" : "#00000000" - - Text { - text: qsTr("Shape Color") - font.weight: Font.Bold - font.pixelSize: 13 - anchors.leftMargin: 8 - verticalAlignment: Text.AlignVCenter - anchors.verticalCenter: parent.verticalCenter - width: 224 - height: elementHeight - anchors.left: parent.left - } - - RoundButton { - //text: "Open" - - height: elementHeight - anchors.right: parent.right - anchors.rightMargin: Qt.inputMethod.visible ? 96 : 36 - anchors.verticalCenter: parent.verticalCenter - anchors.horizontalCenter: parent.horizonatalCenter - onClicked: { - colorPicker.previousColor = settings.color_shape - colorPicker.currentColorType = ColorPicker.ColorType.ShapeColor - colorPicker.visible = true - } - - Rectangle { - anchors.centerIn: parent - width: ((parent.width fetched from @property m_short_description +// Optional info popup -> icon visible when @property m_long_description!=="none" +// actuall seting element -> fill with e.g. your QT settings element, e.g. a Switch +Rectangle { + width: parent.width + height: rowHeight*2 / 3; + //color: "green" + //color: "#8cbfd7f3" + color: (Positioner.index % 2 == 0) ? "#8cbfd7f3" : "#00000000" + + Rectangle{ + width: parent.width + height: 2 + color: "black" + anchors.bottom: parent.bottom + anchors.left: parent.left + } + + property string m_description: "FILL ME" + + + Text { + id: description + text: qsTr(m_description) + font.weight: Font.Bold + font.pixelSize: 13 + anchors.leftMargin: 8 + anchors.rightMargin: 8 + anchors.fill: parent + + verticalAlignment: Text.AlignVCenter + horizontalAlignment: Text.AlignHCenter + + } +} diff --git a/qml/ui/elements/SimpleLeftRightText.qml b/qml/ui/elements/SimpleLeftRightText.qml new file mode 100644 index 000000000..2d824585d --- /dev/null +++ b/qml/ui/elements/SimpleLeftRightText.qml @@ -0,0 +1,31 @@ +import QtQuick 2.12 + +Item { + width: parent.width + //height: 24 + height: 20 + + property string m_left_text: "FILL ME" + property string m_right_text: "FILL ME" + + property color m_right_text_color: "white" + + Text { + text: m_left_text + color: "white" + font.bold: true + height: parent.height + font.pixelSize: detailPanelFontPixels + anchors.left: parent.left + verticalAlignment: Text.AlignVCenter + } + Text { + text: m_right_text + color: m_right_text_color; + font.bold: true; + height: parent.height + font.pixelSize: detailPanelFontPixels; + anchors.right: parent.right + verticalAlignment: Text.AlignVCenter + } +} diff --git a/qml/ui/elements/SimpleProgressBar.qml b/qml/ui/elements/SimpleProgressBar.qml index 0f2fdaa46..9179e6cae 100644 --- a/qml/ui/elements/SimpleProgressBar.qml +++ b/qml/ui/elements/SimpleProgressBar.qml @@ -8,6 +8,8 @@ Item { // Color of the bar property color impl_curr_color: "blue" + property bool impl_show_progress_text: false + Rectangle{ id: progress_background color: impl_curr_color @@ -20,14 +22,33 @@ Item { } + Text{ + width: parent.width + height: parent.height + verticalAlignment: Qt.AlignVCenter + horizontalAlignment: Qt.AlignHCenter + text: { + var ret="PROGRESS"; + if(impl_curr_progress_perc>=0 && impl_curr_progress_perc<=100){ + ret += ": "+impl_curr_progress_perc+"%"; + }else{ + ret += " "; + } + return ret; + } + color: "white" + visible: impl_show_progress_text + } + Rectangle{ id: progress_bar - opacity: 1.0 + opacity: impl_show_progress_text ? 0.5 : 1.0 width: progress_background.width * (impl_curr_progress_perc / 100.0) height: parent.height anchors.left: parent.left color: impl_curr_color - } + + } diff --git a/qml/ui/widgets/AltitudeWidget.qml b/qml/ui/widgets/AltitudeWidget.qml index 69296c241..3af92c2e7 100644 --- a/qml/ui/widgets/AltitudeWidget.qml +++ b/qml/ui/widgets/AltitudeWidget.qml @@ -61,7 +61,8 @@ BaseWidget { id: idBaseWidgetDefaultUiControlElements show_vertical_lock: true - show_horizontal_lock: true + //show_horizontal_lock: true + show_quickpainteditem_font_scale: true Item { width: parent.width @@ -192,6 +193,7 @@ BaseWidget { altitudeRange: settings.altitude_ladder_range Behavior on altitude {NumberAnimation { duration: settings.smoothing }} fontFamily: settings.font_text + custom_font_scale: bw_qquickpainteditem_font_scale } } //-----------------------ladder end--------------- diff --git a/qml/ui/widgets/BaseWidget.qml b/qml/ui/widgets/BaseWidget.qml index 24f52cbad..35d643eab 100644 --- a/qml/ui/widgets/BaseWidget.qml +++ b/qml/ui/widgets/BaseWidget.qml @@ -64,11 +64,34 @@ BaseWidgetForm { settings.sync(); } // Feature persist scale end -------------------------------------------------------------------------------------- - // Feature persist opacity begin + + // Feature persist opacity begin ------------------------------------------------------------------------------------ property string bw_opacity_identifier: "%1_opacity".arg(widgetIdentifier); // Default opacity is 1, the value is persistent property double bw_current_opacity : settings.value(bw_opacity_identifier,1.0); - // Feature persist opacity end + // Updates the current base widget scale (unique per widgetIdentifier) and persist the value for later use + function bw_set_current_opacity(opacity){ + if(opacity <=0 || opacity>1){ + console.warn("perhaps invalid widget opacity"); + } + bw_current_opacity=opacity + settings.setValue(bw_opacity_identifier, bw_current_opacity); + settings.sync(); + } + // Feature persist opacity end -------------------------------------------------------------------------------------- + + // Feature persist 'qquickpainteditem_font_scale' begin ------------------------------------------------------------ + // only for qquick painted items (few) + property string bw_qquickpainteditem_font_scale_identifier: "%1_qquickpainteditem_font_scale".arg(widgetIdentifier); + property double bw_qquickpainteditem_font_scale: settings.value(bw_qquickpainteditem_font_scale_identifier,1.0); + function bw_set_qquickpainteditem_font_scale(scale){ + bw_qquickpainteditem_font_scale=scale; + settings.setValue(bw_qquickpainteditem_font_scale_identifier,bw_qquickpainteditem_font_scale); + settings.sync(); + } + // Feature persist 'qquickpainteditem_font_scale' end -------------------------------------------------------------- + + // Feature: Show grid when dragging property bool m_show_grid_when_dragging: false onDraggingChanged: { @@ -81,16 +104,6 @@ BaseWidgetForm { } } - // Updates the current base widget scale (unique per widgetIdentifier) and persist the value for later use - function bw_set_current_opacity(opacity){ - if(opacity <=0 || opacity>1){ - console.warn("perhaps invalid widget opacity"); - } - bw_current_opacity=opacity - settings.setValue(bw_opacity_identifier, bw_current_opacity); - settings.sync(); - } - // Feature persist opacity end // Added by Consti10 - @@ -100,8 +113,6 @@ BaseWidgetForm { property bool disable_dragging: false // --------------------------------------------------------------------- // Custom keyboard KeyNavigation - // Must be also of type BaseWidget - property var m_next_item: // DIRTY function dirty_open_action_popup(){ widgetAction.open() @@ -142,12 +153,6 @@ BaseWidgetForm { // TODO: Go to the next item } } - function set_focus_next_item(){ - if(m_next_item==undefined){ - console.log("Next item undefined") - return; - } - } //layer.enabled: false diff --git a/qml/ui/widgets/BaseWidgetDefaultUiControlElements.qml b/qml/ui/widgets/BaseWidgetDefaultUiControlElements.qml index 2393da157..dfb736eb1 100644 --- a/qml/ui/widgets/BaseWidgetDefaultUiControlElements.qml +++ b/qml/ui/widgets/BaseWidgetDefaultUiControlElements.qml @@ -19,6 +19,8 @@ ColumnLayout{ property bool show_horizontal_lock: false property bool show_transparency: true + property bool show_quickpainteditem_font_scale: false + Item { width: parent.width height: 42 @@ -103,6 +105,36 @@ ColumnLayout{ } } } + Item { + width: parent.width + height: 32 + visible: show_quickpainteditem_font_scale + Text { + text: qsTr("Font Sale: x"+bw_qquickpainteditem_font_scale.toFixed(1)) + color: "white" + height: parent.height + font.bold: true + font.pixelSize: detailPanelFontPixels + anchors.left: parent.left + verticalAlignment: Text.AlignVCenter + } + Slider { + orientation: Qt.Horizontal + from: .5 + value: bw_qquickpainteditem_font_scale + to: 2 + stepSize: .1 + height: parent.height + anchors.rightMargin: 0 + anchors.right: parent.right + width: parent.width - 96 + + onValueChanged: { + bw_set_qquickpainteditem_font_scale(value); + } + } + } + Item { width: 230 diff --git a/qml/ui/widgets/HeadingWidget.qml b/qml/ui/widgets/HeadingWidget.qml index c7653559f..cf7500c21 100644 --- a/qml/ui/widgets/HeadingWidget.qml +++ b/qml/ui/widgets/HeadingWidget.qml @@ -37,6 +37,7 @@ BaseWidget { id: idBaseWidgetDefaultUiControlElements show_vertical_lock: true show_horizontal_lock: true + show_quickpainteditem_font_scale: true Item { width: 230 @@ -120,6 +121,7 @@ BaseWidget { color: settings.color_shape glow: settings.color_glow fontFamily: settings.font_text + custom_font_scale: bw_qquickpainteditem_font_scale } } diff --git a/qml/ui/widgets/HorizonWidget.qml b/qml/ui/widgets/HorizonWidget.qml index 8cad30524..9072afc32 100644 --- a/qml/ui/widgets/HorizonWidget.qml +++ b/qml/ui/widgets/HorizonWidget.qml @@ -35,6 +35,7 @@ BaseWidget { show_vertical_lock: true show_horizontal_lock: true + show_quickpainteditem_font_scale: true Item { width: 230 @@ -402,6 +403,7 @@ BaseWidget { showHorizonHeadingLadder: settings.show_horizon_heading_ladder showHorizonHome: settings.show_horizon_home //you dont want a floating home icon fontFamily: settings.font_text + custom_font_scale: bw_qquickpainteditem_font_scale } Rectangle{ // For debugging the area where the horizon clips // debug diff --git a/qml/ui/widgets/RecordVideoWidget.qml b/qml/ui/widgets/RecordVideoWidget.qml deleted file mode 100644 index c8d1f3147..000000000 --- a/qml/ui/widgets/RecordVideoWidget.qml +++ /dev/null @@ -1,427 +0,0 @@ -import QtQuick 2.12 -import QtQuick.Controls 2.12 -import QtQuick.Layouts 1.12 -import QtGraphicalEffects 1.12 -import QtQuick.Shapes 1.0 - -import Qt.labs.settings 1.0 - -import OpenHD 1.0 - -import "../elements" - -BaseWidget { - // width: 140*settings.recordTextSize/14 - // height: 48 - - function get_width(){ - if(settings.show_minimal_record_widget){ - if(settings.dev_qopenhd_n_cameras>1){ - return 35*2; - } - return 35; - } - return 150; - } - function get_height(){ - if(settings.show_minimal_record_widget){ - return 25; - } - return 48; - } - - width: get_width() - height: get_height() - visible: settings.show_record_widget - - widgetIdentifier: "record_video_widget" - bw_verbose_name: "AIR RECORDING" - - defaultAlignment: 0 - defaultXOffset: 200 - defaultYOffset: 2 - defaultHCenter: false - defaultVCenter: false - - hasWidgetDetail: true - hasWidgetAction: true - widgetActionWidth: 250 - widgetActionHeight: (settings.dev_qopenhd_n_cameras > 1) ? 230 : 130 - widgetDetailWidth:275 - widgetDetailHeight:175 - - // Set to true if the camera is currently doing recordng (the UI element(s) turn red in this case) - property bool m_camera1_is_currently_recording: _cameraStreamModelPrimary.air_recording_active - property bool m_camera2_is_currently_recording: _cameraStreamModelSecondary.air_recording_active - - // THIS IS A MAVLINK PARAM, SYNCHRONIZATION THEREFORE IS HARD AND HERE NOT WORTH IT - property int m_camera1_recording_mode: -1 - property int m_camera2_recording_mode: -1 - - function set_recording_mode_for_camera(cam_idx,mode){ - if(cam_idx===1){ - m_camera1_recording_mode=mode - }else{ - m_camera2_recording_mode=mode - } - } - - function try_set_recording_mode(camera_idx,mode){ - console.log("try_set_recording_mode "+camera_idx+" "+mode) - var camModel=_airCameraSettingsModel; - var camString="CAM1" - if(camera_idx===2){ - camModel=_airCameraSettingsModel2; - camString="CAM2" - } - if(!_ohdSystemAir.is_alive){ - _hudLogMessagesModel.signalAddLogMessage(6,"Air unit not alive, cannot set recording for "+camString) - return; - } - if(mode===0){ //mode off - var result=camModel.try_update_parameter_int("V_AIR_RECORDING",0)==="" - if(result){ - _hudLogMessagesModel.signalAddLogMessage(6,"recording "+camString+" disabled") - set_recording_mode_for_camera(camera_idx,0) - }else{ - _hudLogMessagesModel.signalAddLogMessage(6,"update "+camString+" failed") - } - } - if(mode===1){ //mode on - var result=camModel.try_update_parameter_int("V_AIR_RECORDING",1)==="" - if(result){ - _hudLogMessagesModel.signalAddLogMessage(6,"recording "+camString+" enabled") - set_recording_mode_for_camera(camera_idx,1) - }else{ - _hudLogMessagesModel.signalAddLogMessage(6,"update "+camString+" failed") - } - } - if(mode==2){ //mode auto - var result=camModel.try_update_parameter_int("V_AIR_RECORDING",2)==="" - if(result){ - _hudLogMessagesModel.signalAddLogMessage(6,"recording "+camString+" auto enabled") - set_recording_mode_for_camera(camera_idx,2) - }else{ - _hudLogMessagesModel.signalAddLogMessage(6,"update "+camString+" failed") - } - } - } - - widgetDetailComponent: ScrollView { - - contentHeight: idBaseWidgetDefaultUiControlElements.height - ScrollBar.horizontal.policy: ScrollBar.AlwaysOff - clip: true - - BaseWidgetDefaultUiControlElements{ - id: idBaseWidgetDefaultUiControlElements - - Item { - width: parent.width - height: 32 - Text { - text: qsTr("Minimal Layout") - color: "white" - height: parent.height - font.bold: true - font.pixelSize: detailPanelFontPixels - anchors.left: parent.left - verticalAlignment: Text.AlignVCenter - } - Switch { - height: parent.height - anchors.rightMargin: 0 - anchors.right: parent.right - width: parent.width - 96 - checked: settings.show_minimal_record_widget - onCheckedChanged:{ - if (checked) { - settings.show_minimal_record_widget = true - } - else{ - settings.show_minimal_record_widget = false - } - - } - - } - - } - Item { - //dummy for layout - width: 230 - height: 32 - } - - } - } - - widgetActionComponent: Item{ - - //color:"red" - width: parent.width-30 - height: parent.height - - ColumnLayout{ - id:recID - width: parent.width - height: parent.height - // - Text { - visible:true - id:airVideoSpaceLeft_minimal - text: "Free: "+_ohdSystemAir.curr_space_left_mb+" MB" - color: (_ohdSystemAir.curr_space_left_mb < 500) ? "red" : "green" - elide: Text.ElideNone - wrapMode: Text.NoWrap - font.pixelSize: settings.recordTextSize - font.family: settings.font_text - style: Text.Outline - onTextChanged: { - if (m_camera1_is_currently_recording || m_camera2_is_currently_recording ==true ) { - if (_ohdSystemAir.curr_space_left_mb < 500 && _ohdSystemAir.curr_space_left_mb > 200 && _ohdSystemAir.curr_space_left_mb % 10 == 0) { - _hudLogMessagesModel.signalAddLogMessage(4,"SD-Card getting full.") - } - } - } - } - Text { - text: qsTr("(Air) Record Camera 1"); - color: settings.color_text - elide: Text.ElideNone - wrapMode: Text.NoWrap - horizontalAlignment: Text.AlignLeft - font.pixelSize: settings.recordTextSize - font.family: settings.font_text - style: Text.Outline - styleColor: settings.color_glow - visible: true - } - Item{ - width: parent.width - height: 50 - //color:"green" - GridLayout{ - width: parent.width - height: parent.height - rows: 1 - columns: 3 - Button{ - text: "OFF" - onClicked: { - try_set_recording_mode(1,0) - } - highlighted: m_camera1_recording_mode==0 - } - Button{ - text: "ON" - onClicked: { - try_set_recording_mode(1,1) - } - highlighted: m_camera1_recording_mode==1 - } - Button{ - text: "AUTO" - onClicked: { - try_set_recording_mode(1,2) - } - highlighted: m_camera1_recording_mode==2 - } - } - } - Text { - text: qsTr("(Air) Record Camera 2"); - color: settings.color_text - elide: Text.ElideNone - wrapMode: Text.NoWrap - horizontalAlignment: Text.AlignLeft - font.pixelSize: settings.recordTextSize - font.family: settings.font_text - style: Text.Outline - styleColor: settings.color_glow - visible: settings.dev_qopenhd_n_cameras > 1 - } - Item{ - width: parent.width - height: 50 - //color:"green" - visible: settings.dev_qopenhd_n_cameras > 1 - GridLayout{ - width: parent.width - height: parent.height - rows: 1 - columns: 3 - Button{ - text: "OFF" - onClicked: { - try_set_recording_mode(2,0) - } - highlighted: m_camera2_recording_mode==0 - } - Button{ - text: "ON" - onClicked: { - try_set_recording_mode(2,1) - } - highlighted: m_camera2_recording_mode==1 - } - Button{ - text: "AUTO" - onClicked: { - try_set_recording_mode(2,2) - } - highlighted: m_camera2_recording_mode==2 - } - } - } - } - } - - - Item { - id: recordWidgetBig - visible: !settings.show_minimal_record_widget - anchors.fill: parent - Text { - text: qsTr("Record Video"); - color: settings.color_text - anchors.fill: parent - anchors.topMargin: 5*settings.recordTextSize/12 - verticalAlignment: Text.AlignVCenter - elide: Text.ElideNone - wrapMode: Text.NoWrap - horizontalAlignment: Text.AlignLeft - font.pixelSize: settings.recordTextSize - font.family: settings.font_text - style: Text.Outline - styleColor: settings.color_glow - visible: true - } - Text { - id:record_status_cam1 - text: "CAM1" - color: (m_camera1_is_currently_recording == true) ? "green" : "red" - anchors.fill: parent - anchors.leftMargin: 95*settings.recordTextSize/14 - anchors.topMargin: 5*settings.recordTextSize/12 - verticalAlignment: Text.AlignVCenter - elide: Text.ElideNone - wrapMode: Text.NoWrap - font.pixelSize: settings.recordTextSize - font.family: settings.font_text - style: Text.Outline - styleColor: settings.color_glow - visible: true - } - Text { - id:record_status_cam2 - text: "CAM2" - color: (m_camera2_is_currently_recording == true) ? "green" : "red" - anchors.fill: parent - anchors.leftMargin: 140*settings.recordTextSize/14 - anchors.topMargin: 5*settings.recordTextSize/12 - verticalAlignment: Text.AlignVCenter - elide: Text.ElideNone - wrapMode: Text.NoWrap - font.pixelSize: settings.recordTextSize - font.family: settings.font_text - style: Text.Outline - styleColor: settings.color_glow - visible: settings.dev_qopenhd_n_cameras > 1 - } - Text { - text: qsTr("Free Space"); - color: settings.color_text - anchors.leftMargin: 90 - elide: Text.ElideNone - wrapMode: Text.NoWrap - font.pixelSize: settings.recordTextSize - font.family: settings.font_text - style: Text.Outline - styleColor: settings.color_glow - visible: true - } - Text { - id:airVideoSpaceLeft - text: _ohdSystemAir.curr_space_left_mb+" MB" - color: (_ohdSystemAir.curr_space_left_mb < 500) ? "red" : "green" - anchors.fill: parent - anchors.leftMargin: 95*settings.recordTextSize/14 - anchors.topMargin: -30 - verticalAlignment: Text.AlignVCenter - elide: Text.ElideNone - wrapMode: Text.NoWrap - font.pixelSize: settings.recordTextSize - font.family: settings.font_text - style: Text.Outline - styleColor: settings.color_glow - visible: true - onTextChanged: { - if (m_camera1_is_currently_recording ==true || m_camera2_is_currently_recording ==true ) { - if (_ohdSystemAir.curr_space_left_mb < 500 && _ohdSystemAir.curr_space_left_mb > 200 && _ohdSystemAir.curr_space_left_mb % 10 == 0) { - _hudLogMessagesModel.signalAddLogMessage(4,"SD-Card getting full.") - } - } - } - } } - Item { - id: recordWidgetMinimal - visible: settings.show_minimal_record_widget - anchors.fill: parent - Text { - id:record_status_cam1_min - text: "\uf03d" - font.family: "Font Awesome 5 Free" - color: (m_camera1_is_currently_recording == true) ? "red" : "white" - anchors.fill: parent - anchors.leftMargin: 5*settings.recordTextSize/14 - anchors.topMargin: 5*settings.recordTextSize/12 - verticalAlignment: Text.AlignVCenter - elide: Text.ElideNone - wrapMode: Text.NoWrap - font.pixelSize: settings.recordTextSize*1.5 - style: Text.Outline - styleColor: settings.color_glow - visible: true - } - Text { - id:record_status_cam2_min - text: " \uf03d" - font.family: "Font Awesome 5 Free" - color: (m_camera2_is_currently_recording == true) ? "red" : "white" - anchors.fill: parent - anchors.leftMargin: 25*settings.recordTextSize/14 - anchors.topMargin: 5*settings.recordTextSize/12 - verticalAlignment: Text.AlignVCenter - elide: Text.ElideNone - wrapMode: Text.NoWrap - font.pixelSize: settings.recordTextSize*1.5 - style: Text.Outline - styleColor: settings.color_glow - visible: settings.dev_qopenhd_n_cameras > 1 - } - Text { - id:airVideoSpaceLeft_min - text: _ohdSystemAir.curr_space_left_mb+" MB" - color: (_ohdSystemAir.curr_space_left_mb < 500) ? "red" : "green" - anchors.fill: parent - anchors.leftMargin: 95*settings.recordTextSize/14 - anchors.topMargin: -30 - verticalAlignment: Text.AlignVCenter - elide: Text.ElideNone - wrapMode: Text.NoWrap - font.pixelSize: settings.recordTextSize - font.family: settings.font_text - style: Text.Outline - styleColor: settings.color_glow - visible: !settings.show_minimal_record_widget - onTextChanged: { - if (m_camera1_is_currently_recording ==true || m_camera2_is_currently_recording ==true ) { - if (_ohdSystemAir.curr_space_left_mb < 500 && _ohdSystemAir.curr_space_left_mb > 200 && _ohdSystemAir.curr_space_left_mb % 10 == 0) { - _hudLogMessagesModel.signalAddLogMessage(4,"SD-Card getting full.") - } - } - } - } - } -} diff --git a/qml/ui/widgets/SpeedWidget.qml b/qml/ui/widgets/SpeedWidget.qml index f47601112..c727480ee 100644 --- a/qml/ui/widgets/SpeedWidget.qml +++ b/qml/ui/widgets/SpeedWidget.qml @@ -69,6 +69,7 @@ BaseWidget { show_horizontal_lock: true show_vertical_lock: true + show_quickpainteditem_font_scale: true Item { width: parent.width @@ -252,6 +253,7 @@ BaseWidget { Behavior on speed {NumberAnimation { duration: settings.smoothing }} speed: get_speed_number() fontFamily: settings.font_text + custom_font_scale: bw_qquickpainteditem_font_scale } } diff --git a/qml/ui/widgets/VideoBitrateWidgetGeneric.qml b/qml/ui/widgets/VideoBitrateWidgetGeneric.qml index f4a1899ac..0df6c0a7e 100644 --- a/qml/ui/widgets/VideoBitrateWidgetGeneric.qml +++ b/qml/ui/widgets/VideoBitrateWidgetGeneric.qml @@ -7,6 +7,7 @@ import QtQuick.Shapes 1.0 import Qt.labs.settings 1.0 import OpenHD 1.0 +import "../elements" // Generic since we use the same widget for primary and secondary camera (allbei with different values, of course) BaseWidget { @@ -28,7 +29,7 @@ BaseWidget { hasWidgetDetail: true hasWidgetAction: true - widgetActionHeight: 400 + widgetActionHeight: 450 property var m_camera_stream_model: m_is_for_primary_camera ? _cameraStreamModelPrimary : _cameraStreamModelSecondary @@ -58,6 +59,66 @@ BaseWidget { return m_camera_stream_model.total_n_tx_dropped_frames+":"+m_camera_stream_model.count_blocks_lost; } + // Complicated + // Set to true if the camera is currently doing recordng (the UI element(s) turn red in this case) + property bool m_camera_is_currently_recording: m_is_for_primary_camera ? _cameraStreamModelPrimary.air_recording_active : _cameraStreamModelSecondary.air_recording_active + + // THIS IS A MAVLINK PARAM, SYNCHRONIZATION THEREFORE IS HARD AND HERE NOT WORTH IT + property int m_camera_recording_mode: -1 + + function try_set_recording_mode(mode){ + var camera_idx=m_is_for_primary_camera ? 0 : 1; + console.log("try_set_recording_mode "+camera_idx+" "+mode) + var camModel=_airCameraSettingsModel; + var camString="CAM1" + if(camera_idx===2){ + camModel=_airCameraSettingsModel2; + camString="CAM2" + } + if(!_ohdSystemAir.is_alive){ + _hudLogMessagesModel.signalAddLogMessage(6,"Air unit not alive, cannot set recording for "+camString) + return; + } + if(mode===0){ //mode off + var result=camModel.try_update_parameter_int("V_AIR_RECORDING",0)==="" + if(result){ + _hudLogMessagesModel.signalAddLogMessage(6,"recording "+camString+" disabled") + m_camera_recording_mode=0; + }else{ + _hudLogMessagesModel.signalAddLogMessage(6,"update "+camString+" failed") + } + } + if(mode===1){ //mode on + var result=camModel.try_update_parameter_int("V_AIR_RECORDING",1)==="" + if(result){ + _hudLogMessagesModel.signalAddLogMessage(6,"recording "+camString+" enabled") + m_camera_recording_mode=1; + }else{ + _hudLogMessagesModel.signalAddLogMessage(6,"update "+camString+" failed") + } + } + if(mode==2){ //mode auto + var result=camModel.try_update_parameter_int("V_AIR_RECORDING",2)==="" + if(result){ + _hudLogMessagesModel.signalAddLogMessage(6,"recording "+camString+" auto enabled") + m_camera_recording_mode=2; + }else{ + _hudLogMessagesModel.signalAddLogMessage(6,"update "+camString+" failed") + } + } + } + + ListModel{ + id: resolutions_model + ListElement {title: "480p60(16:9)"; value: "848x480@60"} + ListElement {title: "480p60(4:3)"; value: "640x480@60"} + ListElement {title: "720p49(16:9)"; value: "1280x720@49"} + ListElement {title: "720p60(4:3)"; value: "960x720@60"} + ListElement {title: "1080p30(16:9)"; value: "1920x1080@30"} + ListElement {title: "1080p30(4:3)"; value: "1440x1080@30"} + ListElement {title: "1080p49(4:3)"; value: "1440x1080@49"} + } + //----------------------------- DETAIL BELOW ---------------------------------- @@ -70,129 +131,85 @@ BaseWidget { BaseWidgetDefaultUiControlElements{ id: idBaseWidgetDefaultUiControlElements - } - } - - //---------------------------ACTION WIDGET COMPONENT BELOW----------------------------- - - widgetActionComponent: ScrollView{ - - ScrollBar.horizontal.policy: ScrollBar.AlwaysOff - clip: true - - ColumnLayout{ - width:200 Item { - width: parent.width + width: 230 height: 32 Text { - text: qsTr("Set(Enc):") + text: qsTr("Show RED recording active") color: "white" - font.bold: true height: parent.height - font.pixelSize: detailPanelFontPixels - anchors.left: parent.left - verticalAlignment: Text.AlignVCenter - } - Text { - text: m_camera_stream_model.curr_set_video_format_and_codec - color: "white"; - font.bold: true; - height: parent.height - font.pixelSize: detailPanelFontPixels; - anchors.right: parent.right - verticalAlignment: Text.AlignVCenter - } - } - Item { - width: parent.width - height: 32 - Text { - text: qsTr("Set(Enc):") - color: "white" font.bold: true - height: parent.height font.pixelSize: detailPanelFontPixels anchors.left: parent.left verticalAlignment: Text.AlignVCenter } - Text { - text: m_camera_stream_model.curr_recomended_video_bitrate_string - color: "white"; - font.bold: true; + Switch { + width: 32 height: parent.height - font.pixelSize: detailPanelFontPixels; + anchors.rightMargin: 6 anchors.right: parent.right - verticalAlignment: Text.AlignVCenter + checked: settings.camera_bitrate_widget_show_recording + onCheckedChanged: settings.camera_bitrate_widget_show_recording = checked } } - Item { - width: parent.width - height: 32 - Text { - text: qsTr("Measured(Enc):") - color: "white" - font.bold: true - height: parent.height - font.pixelSize: detailPanelFontPixels - anchors.left: parent.left - verticalAlignment: Text.AlignVCenter - } - Text { - text: m_camera_stream_model.curr_video_measured_encoder_bitrate - color: "white"; - font.bold: true; - height: parent.height - font.pixelSize: detailPanelFontPixels; - anchors.right: parent.right - verticalAlignment: Text.AlignVCenter + } + } + + //---------------------------ACTION WIDGET COMPONENT BELOW----------------------------- + + widgetActionComponent: ScrollView{ + + ScrollBar.horizontal.policy: ScrollBar.AlwaysOff + clip: true + + ColumnLayout{ + width:200 + + SimpleLeftRightText{ + m_left_text: qsTr("Status:") + m_right_text: { + if(!_ohdSystemAir.is_alive)return "no air"; + return _cameraStreamModelPrimary.camera_status_to_string(m_camera_stream_model.camera_status); } } - Item { - width: parent.width - height: 32 - Text { - text: qsTr("Injected(+FEC):") - color: "white" - font.bold: true - height: parent.height - font.pixelSize: detailPanelFontPixels - anchors.left: parent.left - verticalAlignment: Text.AlignVCenter + SimpleLeftRightText{ + m_left_text: qsTr("Type:") + m_right_text: { + if(!_ohdSystemAir.is_alive)return "n/a"; + return _cameraStreamModelPrimary.camera_type_to_string(m_camera_stream_model.camera_type); } - Text { - text: m_camera_stream_model.curr_video_injected_bitrate - color: "white"; - font.bold: true; - height: parent.height - font.pixelSize: detailPanelFontPixels; - anchors.right: parent.right - verticalAlignment: Text.AlignVCenter + } + SimpleLeftRightText{ + m_left_text: qsTr("Codec:") + m_right_text: { + if(!_ohdSystemAir.is_alive)return "n/a"; + return _cameraStreamModelPrimary.camera_codec_to_string(m_camera_stream_model.encoding_codec); } } - Item { - width: parent.width - height: 32 - Text { - text: qsTr("TX Dropped/RX lost:") - color: "white" - font.bold: true - height: parent.height - font.pixelSize: detailPanelFontPixels - anchors.left: parent.left - verticalAlignment: Text.AlignVCenter + + ComboBox{ + id: resolution_fps_cb + model: resolutions_model + textRole: "title" + width: 200 + Layout.preferredWidth: 200 + Layout.minimumWidth: 200 + height: 50 + currentIndex: 0 + displayText: { + if(!_ohdSystemAir.is_alive)return "Res@fps N/A"; + return m_curr_video_format; } - Text { - text: get_drop_str_tx_rx() - color: "white"; - font.bold: true; - height: parent.height - font.pixelSize: detailPanelFontPixels; - anchors.right: parent.right - verticalAlignment: Text.AlignVCenter + onActivated: { + console.log("onActivated:"+currentIndex); + if(currentIndex<0)return; + const resolution=model.get(currentIndex).value + console.log("Selected resolution: "+resolution); + set_camera_resolution(resolution); } + enabled: _ohdSystemAir.is_alive; } - Item{ + /*Item{ width: parent.width height: 150 //color: "green" @@ -205,7 +222,7 @@ BaseWidget { // 2 mmal // 3 veye // 4 libcamera - enabled: (m_camera_stream_model.camera_type==1 || m_camera_stream_model.camera_type==2 || m_camera_stream_model.camera_type==4) + //enabled: (m_camera_stream_model.camera_type==1 || m_camera_stream_model.camera_type==2 || m_camera_stream_model.camera_type==4) Button{ text: "480p60(16:9)" onClicked: set_camera_resolution("848x480@60") @@ -237,12 +254,91 @@ BaseWidget { highlighted: m_curr_video_format=="1440x1080@30" } } - } - /*Item{ - id: placeholder - width:parent.width - height: 10 }*/ + SimpleLeftRightText{ + m_left_text: qsTr("Bitrate SET:") + m_right_text: m_camera_stream_model.curr_recomended_video_bitrate_string + } + + SimpleLeftRightText{ + m_left_text: qsTr("MEASURED:") + m_right_text: m_camera_stream_model.curr_video_measured_encoder_bitrate + } + + SimpleLeftRightText{ + m_left_text: qsTr("Injected(+FEC):") + m_right_text: m_camera_stream_model.curr_video_injected_bitrate + } + + + SimpleLeftRightText{ + m_left_text: qsTr("TX Dropped/RX lost:") + m_right_text: get_drop_str_tx_rx() + } + + Item{ + width: parent.width + height: 32 + Text{ + width: parent.width + height: parent.height + verticalAlignment: Qt.AlignVCenter + horizontalAlignment: Qt.AlignHCenter + text: "AIR RECORDING" + color: "white" + } + } + SimpleLeftRightText{ + m_left_text: qsTr("FREE SPACE:") + m_right_text: { + if(!_ohdSystemAir.is_alive)return "N/A"; + return _ohdSystemAir.curr_space_left_mb+" MB" + } + m_right_text_color: { + if(!_ohdSystemAir.is_alive)return "white" + return (_ohdSystemAir.curr_space_left_mb < 500) ? "red" : "green" + } + } + SimpleLeftRightText{ + m_left_text: qsTr("AIR RECORD:"); + m_right_text: { + if(!_ohdSystemAir.is_alive)return "N/A"; + return _cameraStreamModelPrimary.camera_recording_mode_to_string(m_camera_stream_model.air_recording_active); + } + } + // For camera 1 + Item{ + width: parent.width + height: 50 + //color:"green" + GridLayout{ + width: parent.width + height: parent.height + rows: 1 + columns: 3 + Button{ + text: "OFF" + onClicked: { + try_set_recording_mode(0) + } + highlighted: m_camera_recording_mode==0 + } + Button{ + text: "ON" + onClicked: { + try_set_recording_mode(1) + } + highlighted: m_camera_recording_mode==1 + } + Button{ + text: "AUTO" + onClicked: { + try_set_recording_mode(2) + } + highlighted: m_camera_recording_mode==2 + } + } + } Item { width: parent.width height: 32 @@ -300,5 +396,17 @@ BaseWidget { style: Text.Outline styleColor: settings.color_glow } + + Rectangle{ + width: 12 + height: width + radius: width + color: "red"; + anchors.right: camera_icon.left + anchors.rightMargin: 2 + anchors.verticalCenter: parent.verticalCenter + visible: settings.camera_bitrate_widget_show_recording && m_camera_is_currently_recording + } + } } diff --git a/qml/ui/widgets/VideoBitrateWidgetSecondary.qml b/qml/ui/widgets/VideoBitrateWidgetSecondary.qml index d3c9e7216..3850bbc99 100644 --- a/qml/ui/widgets/VideoBitrateWidgetSecondary.qml +++ b/qml/ui/widgets/VideoBitrateWidgetSecondary.qml @@ -10,6 +10,6 @@ import OpenHD 1.0 VideoBitrateWidgetGeneric{ m_is_for_primary_camera: false - visible: settings.show_bitrate && settings.dev_qopenhd_n_cameras==2 - + // Also show it if air has a seconary cam + visible: (settings.show_bitrate && settings.dev_qopenhd_n_cameras>1) || (settings.show_bitrate && _ohdSystemAir.dirty_air_has_secondary_cam) } diff --git a/qml/video/SecondaryVideoGStreamer.qml b/qml/video/SecondaryVideoGStreamer.qml index 49af6a844..46203e77a 100644 --- a/qml/video/SecondaryVideoGStreamer.qml +++ b/qml/video/SecondaryVideoGStreamer.qml @@ -3,9 +3,6 @@ import QtGraphicalEffects 1.12 import QtQuick.Controls 2.15 import QtQuick.Layouts 1.15 -// QT creator might show "not found" on this import, this is okay, annoying qt specifics -import org.freedesktop.gstreamer.GLVideoItem 1.0; - import OpenHD 1.0 import "../ui/elements" @@ -16,6 +13,8 @@ import "../ui/elements" // Also, it is nice to automatically have all features needed for the secondary video like scaling, resizing ... Item { + id: secondary_video_item + visible: settings.dev_qopenhd_n_cameras>1 // We use the full screen since while usually small in the lower left corner, the secondary video can be resized anchors.fill: parent anchors.left: parent.left @@ -25,60 +24,151 @@ Item { property bool has_been_maximized: false function get_video_width(){ + var video_width = settings.secondary_video_minimized_width; if(has_been_maximized){ - var maximize_factor = settings.secondary_video_maximize_factor_perc / 100; - return settings.secondary_video_minimized_width * maximize_factor; + const maximize_factor = settings.secondary_video_maximize_factor_perc / 100; + video_width = video_width * maximize_factor; } - return settings.secondary_video_minimized_width; + const screen_width = secondary_video_item.width; + return video_width < screen_width ? video_width : screen_width; + //return video_width; } function get_video_height(){ + var video_height = settings.secondary_video_minimized_height; if(has_been_maximized){ - var maximize_factor = settings.secondary_video_maximize_factor_perc / 100; - return settings.secondary_video_minimized_height * maximize_factor; + const maximize_factor = settings.secondary_video_maximize_factor_perc / 100; + video_height = video_height * maximize_factor; } - return settings.secondary_video_minimized_height; + const screen_height = secondary_video_item.height; + return video_height < screen_height ? video_height : screen_height; + //return video_height; } // This is for debugging / showing the video widget area at run time Rectangle{ + z: 1.0 id: video_holder width: get_video_width() height: get_video_height() anchors.bottom: parent.bottom - anchors.left: parent.left - color: "red" - visible: popup.visible - } + //width: get_video_width() + //height: get_video_height() + //anchors.bottom: parent.bottom + //anchors.left: parent.left + //color: "red" + //color: popup.opened ? "red" : "transparent" + color: "gray" + opacity: 0.1 + //visible: popup.visible + MouseArea { + anchors.fill: parent + onClicked: { + console.log("onClicked"); + has_been_maximized = !has_been_maximized; + } + onPressAndHold: { + console.log("onPressAndHold"); + // open the popup containing the settings + popup.open() + } + } - GstGLVideoItem { - id: secondaryVideoGStreamer - objectName: "secondaryVideoGStreamer" + } - width: get_video_width() - height: get_video_height() - // We are always anchored to the lower left corner - anchors.bottom: parent.bottom - anchors.left: parent.left + Text{ + anchors.fill: video_holder + text: { + if (QOPENHD_ENABLE_GSTREAMER_QMLGLSINK){ + return "WAITING FOR\nSECONDARY VIDEO"; + } + return "SECONDARY VIEO\nNOT AVAILABLE\nON THIS PLATFORM"; + } + verticalAlignment: Qt.AlignVCenter + horizontalAlignment: Qt.AlignHCenter + font.pixelSize: 14 + color: "white" + } - Component.onCompleted: { - console.log("secondaryVideoGStreamer (Qmlglsink) created") - _secondary_video_gstreamer_qml.check_common_mistakes_then_init(secondaryVideoGStreamer) + Loader { + z: 0.0 + anchors.fill: video_holder + source: { + if(settings.dev_qopenhd_n_cameras>1){ + // R.N the only implementation for secondary video + if (QOPENHD_ENABLE_GSTREAMER_QMLGLSINK){ + return "SecondaryVideoGstreamerPane.qml"; + }else{ + console.warn("No secondary video implementation") + } + }else{ + console.debug("Scondary video disabled"); + } + return ""; } + } + /*Button{ + id: button_maximize + text: "\uf31e"; + width: 24 + height: 24 + anchors.right: video_holder.right + anchors.top: video_holder.top + onClicked: { + console.log("Button clicked"); + has_been_maximized = !has_been_maximized; + } + }*/ + /*Button{ + text:"S" + anchors.right: button_maximize.left + anchors.rightMargin: 2 + anchors.top: button_maximize.top + onClicked: { + popup.open() + } + visible: has_been_maximized + }*/ + /*Text{ + id: button_maximize + color: "white" + text: "\uf31e" + font.family: "Font Awesome 5 Free" + width: 40 + height: 40 + anchors.right: video_holder.right + anchors.top: video_holder.top + font.pixelSize: 19 + verticalAlignment: Qt.AlignVCenter + horizontalAlignment: Qt.AlignHCenter MouseArea { anchors.fill: parent onClicked: { - //console.log("Clicked") - // Toggle between maximized and minimized has_been_maximized = !has_been_maximized; } - onPressAndHold: { - console.log("onPressAndHold"); - // open the popup containing the settings + } + } + Text{ + id: button_settings + color: "white" + text: "\uf013" + font.family: "Font Awesome 5 Free" + width: 40 + height: 40 + anchors.right: button_maximize.left + anchors.rightMargin: 2 + anchors.top: button_maximize.top + font.pixelSize: 19 + verticalAlignment: Qt.AlignVCenter + horizontalAlignment: Qt.AlignHCenter + MouseArea { + anchors.fill: parent + onClicked: { popup.open() } } - } + }*/ + property int rowHeight: 64 // This popup allows changing the settings for this element Popup { @@ -88,12 +178,7 @@ Item { width: 500 height: 300 modal: true - //focus: true closePolicy: Popup.CloseOnEscape | Popup.CloseOnPressOutside - /*background: Rectangle { - color: "gray" - border.color: "black" - }*/ Pane{ ColumnLayout { anchors.fill: parent diff --git a/qml/video/SecondaryVideoGstreamerPane.qml b/qml/video/SecondaryVideoGstreamerPane.qml new file mode 100644 index 000000000..4b7b2df0a --- /dev/null +++ b/qml/video/SecondaryVideoGstreamerPane.qml @@ -0,0 +1,22 @@ +import QtQuick 2.12 +import QtGraphicalEffects 1.12 +import QtQuick.Controls 2.15 +import QtQuick.Layouts 1.15 + +// QT creator might show "not found" on this import, this is okay, annoying qt specifics +import org.freedesktop.gstreamer.GLVideoItem 1.0; + +import OpenHD 1.0 + +import "../ui/elements" + +GstGLVideoItem { + id: secondaryVideoGStreamer + objectName: "secondaryVideoGStreamer" + z: 0.0 + + Component.onCompleted: { + console.log("secondaryVideoGStreamer (Qmlglsink) created") + _secondary_video_gstreamer_qml.check_common_mistakes_then_init(secondaryVideoGStreamer) + } +}