Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Patch2 #722

Merged
merged 14 commits into from
Nov 24, 2024
6 changes: 3 additions & 3 deletions app/telemetry/models/camerastreammodel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,9 +63,9 @@ QString CameraStreamModel::camera_codec_to_string(int camera_codec)

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";
if(recording_mode<0)return " n/a";
if(recording_mode==0)return " off";
if(recording_mode==1)return " on";
return "error";
}

Expand Down
58 changes: 57 additions & 1 deletion app/telemetry/settings/frequencyhelper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,11 @@ QList<int> FrequencyHelper::get_frequencies(int filter)
for(auto& channel:tmp){
ret.push_back(channel.frequency);
}
}else if(filter==3){
auto tmp=openhd::get_openhd_channels_licensed();
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){
Expand All @@ -29,7 +34,7 @@ QList<int> FrequencyHelper::get_frequencies(int filter)
ret.push_back(item.frequency);
}
}else{
if(item.frequency>3000){
if(item.frequency>=5180 && item.frequency<=5865){
ret.push_back(item.frequency);
}
}
Expand Down Expand Up @@ -107,6 +112,57 @@ int FrequencyHelper::get_frequency_openhd_race_band(int frequency_mhz)
}
return -1;
}
int FrequencyHelper::get_frequency_openhd_licensed_band(int frequency_mhz)
{
// Frequencies: 5080,5100,5120,5140,5160,5905,5925,5945,5965,5985,6005,6025,6045,6065,6085
if(frequency_mhz==5080){
return 1;
}
if(frequency_mhz==5100){
return 2;
}
if(frequency_mhz==5120){
return 3;
}
if(frequency_mhz==5140){
return 4;
}
if(frequency_mhz==5160){
return 5;
}
if(frequency_mhz==5905){
return 6;
}
if(frequency_mhz==5925){
return 7;
}
if(frequency_mhz==5945){
return 8;
}
if(frequency_mhz==5965){
return 9;
}
if(frequency_mhz==5985){
return 10;
}
if(frequency_mhz==6005){
return 11;
}
if(frequency_mhz==6025){
return 12;
}
if(frequency_mhz==6045){
return 13;
}
if(frequency_mhz==6065){
return 14;
}
if(frequency_mhz==6085){
return 15;
}
return -1;
}


int FrequencyHelper::get_frequency_channel_nr(int frequency_mhz)
{
Expand Down
1 change: 1 addition & 0 deletions app/telemetry/settings/frequencyhelper.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@ class FrequencyHelper : public QObject

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_openhd_licensed_band(int frequency_mhz);
Q_INVOKABLE int get_frequency_channel_nr(int frequency_mhz);
// --------------
Q_INVOKABLE bool hw_supports_frequency_threadsafe(int frequency_mhz);
Expand Down
4 changes: 4 additions & 0 deletions app/telemetry/settings/wifi_channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -282,6 +282,10 @@ static std::vector<WifiChannel> get_openhd_channels_1_to_7() {
std::vector<uint32_t> frequencies = {5700, 5745, 5785, 5825, 5865, 5260, 5280};
return frequencies_to_channels(frequencies);
}
static std::vector<WifiChannel> get_openhd_channels_licensed() {
std::vector<uint32_t> frequencies = {5080,5100,5120,5140,5160,5905,5925,5945,5965,5985,6005,6025,6045,6065,6085};
return frequencies_to_channels(frequencies);
}

static std::vector<WifiChannel> filter_ht40plus_only(
const std::vector<uint32_t>& frequencies) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ Card {
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);
const channel_nr_openhd_licensed=_frequencyHelper.get_frequency_openhd_licensed_band(m_wanted_frequency);
return "Set AIR and GROUND to CHANNEL ["+channel_nr+"]\n"+
"("+m_wanted_frequency+" Mhz) ?";

Expand Down
2 changes: 2 additions & 0 deletions qml/ui/configpopup/openhd_settings/FreqComboBoxRow.qml
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,8 @@ Rectangle{
property bool m_show_radar: false

property int m_openhd_race_band: -1
property int m_openhd_licensed_band: -1


property int m_pollution_pps: -1

Expand Down
35 changes: 19 additions & 16 deletions qml/ui/configpopup/openhd_settings/LinkQuickPanel.qml
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ import QtQuick.Controls 2.12
import QtQuick.Layouts 1.12

import QtQuick.Controls.Material 2.12


import Qt.labs.settings 1.0

Expand Down Expand Up @@ -166,6 +166,7 @@ Rectangle{
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_openhd_licensed_band: _frequencyHelper.get_frequency_openhd_licensed_band(value_frequency_mhz)
m_pollution_pps: _pollutionHelper.pollution_get_last_scan_pollution_for_frequency(value_frequency_mhz)
}
highlighted: comboBoxFreq.highlightedIndex === index
Expand Down Expand Up @@ -206,40 +207,42 @@ Rectangle{
}
enabled: _ohdSystemGround.is_alive && _ohdSystemGround.wb_gnd_operating_mode==0;
}
TabBar{
TabBar {
id: filter_tab_bar
width: 200
width: 350
currentIndex: settings.qopenhd_frequency_filter_selection
onCurrentIndexChanged: {
if(currentIndex!=settings.qopenhd_frequency_filter_selection){
settings.qopenhd_frequency_filter_selection=currentIndex;
if (currentIndex != settings.qopenhd_frequency_filter_selection) {
settings.qopenhd_frequency_filter_selection = currentIndex;
console.log("Tab changed to index:", currentIndex);
function_rebuild_ui();
if(currentIndex==1){
_qopenhd.show_toast("2.4G is almost always polluted by WiFi. Not recommended.")
}else if(currentIndex==2){
_qopenhd.show_toast("Please watch out for wifi pollution. Using DEF is highly recommended !")
}
}
}
TabButton{
text: "DEF"
TabButton {
text: "OpenHD"
font.capitalization: Font.MixedCase
}
TabButton{
TabButton {
text: "2.4G"
enabled: {
if(_ohdSystemAir.is_alive && _ohdSystemAir.ohd_platform_type==30){
if (_ohdSystemAir.is_alive && _ohdSystemAir.ohd_platform_type == 30) {
// X20 does not support 2.4G
return false;
}
return true;

}
}
TabButton{
TabButton {
text: "5.8G"
}
enabled: comboBoxFreq.enabled
TabButton {
text: "Custom"
font.capitalization: Font.MixedCase
visible: settings.dev_show_5180mhz_lowband
}
}

/*ButtonIconInfo2{
Layout.alignment: Qt.AlignRight
visible:false
Expand Down
12 changes: 2 additions & 10 deletions qml/ui/sidebar/MavlinkChoiceElement.qml
Original file line number Diff line number Diff line change
Expand Up @@ -26,13 +26,7 @@ BaseJoyEditElement{
property var m_settings_model: _ohdSystemGroundSettings
// Int param is much more common, but string param is also possible
property bool override_takes_string_param: false
ListModel{
id: elements_frequency_scan
ListElement {value: 0; verbose:"OHD"}
ListElement {value: 1; verbose:"5.8"}
ListElement {value: 2; verbose:"2.4"}
ListElement {value: 3; verbose:"ALL"}
}

ListModel{
id: elements_model_brightness
ListElement {value: 0; verbose:"0%"}
Expand Down Expand Up @@ -97,7 +91,7 @@ BaseJoyEditElement{
id: elements_model_air_recording
ListElement {value: 0; verbose:"ALWAYS\nOFF"}
ListElement {value: 1; verbose:"ALWAYS\nON"}
ListElement {value: 2; verbose:"AUTO\n(WHEN ARMED)"}
ListElement {value: 2; verbose:"AUTO\n(WHEN ARMED)"}
}
ListModel{
id: elements_model_hotspot
Expand Down Expand Up @@ -156,8 +150,6 @@ BaseJoyEditElement{
property string m_actual_value_string: ""

function get_model(){
}else if(param_id=="FREQUENCY_SCAN"){
return elements_frequency_scan;
if(m_param_id=="BRIGHTNESS"){
return elements_model_brightness;
}else if(m_param_id=="SATURATION"){
Expand Down
25 changes: 6 additions & 19 deletions qml/ui/sidebar/MavlinkChoiceElement2.qml
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,6 @@ BaseJoyEditElement2{
// EXTRA
property string mPARAM_ID_CHANNEL_WIDTH: "CHANNEL_WIDTH"
property string mPARAM_ID_FREQUENCY: "FREQUENCY"
property string mPARAM_ID_FREQUENCY_SCAN: "FREQUENCY_SCAN"
property string mPARAM_ID_RATE: "RATE"


Expand Down Expand Up @@ -120,7 +119,8 @@ BaseJoyEditElement2{
property string populate_display_text:"I SHOULD NEVER APPEAR"

function populate(){
if(m_param_id==mPARAM_ID_CHANNEL_WIDTH || m_param_id==mPARAM_ID_FREQUENCY || mPARAM_ID_FREQUENCY_SCAN || m_param_id==mPARAM_ID_RATE){
// Don't mind those 3
if(m_param_id==mPARAM_ID_CHANNEL_WIDTH || m_param_id==mPARAM_ID_FREQUENCY || m_param_id==mPARAM_ID_RATE){
return;
}
// First, check if the system is alive
Expand Down Expand Up @@ -189,7 +189,7 @@ BaseJoyEditElement2{

function user_selected_value(value_new){
// A few need to be handled specially
if(m_param_id==mPARAM_ID_FREQUENCY || m_param_id==mPARAM_ID_FREQUENCY_SCAN){
if(m_param_id==mPARAM_ID_FREQUENCY){
if(_fcMavlinkSystem.armed){
if(settings.dev_allow_freq_change_when_armed){
// okay
Expand All @@ -204,11 +204,6 @@ BaseJoyEditElement2{
_qopenhd.set_busy_for_milliseconds(2000,"CHANGING FREQUENCY");
_wbLinkSettingsHelper.change_param_air_and_ground_frequency(value_new)
return;
}else if(m_param_id==mPARAM_ID_FREQUENCY_SCAN){
const frequency_scan=value_new;
_qopenhd.set_busy_for_milliseconds(2000,"Starting scan");
//PLATZHALTER
return;
}else if(m_param_id==mPARAM_ID_CHANNEL_WIDTH){
const channel_width_mhz=value_new;
if(!_ohdSystemAir.is_alive){
Expand Down Expand Up @@ -247,13 +242,8 @@ BaseJoyEditElement2{
onCurr_bandwidth_mhzChanged: {
extra_populate();
}
property bool curr_frequency_scan: (_ohdSystemGround.wb_gnd_operating_mode == 0)
onCurr_frequency_scanChanged: {
extra_populate();
}

function extra_populate(){
if(!(m_param_id==mPARAM_ID_CHANNEL_WIDTH || m_param_id==mPARAM_ID_FREQUENCY || mPARAM_ID_FREQUENCY_SCAN || m_param_id==mPARAM_ID_RATE )){
if(!(m_param_id==mPARAM_ID_CHANNEL_WIDTH || m_param_id==mPARAM_ID_FREQUENCY || m_param_id==mPARAM_ID_RATE)){
return;
}
// First, check if the system is alive
Expand All @@ -263,10 +253,6 @@ BaseJoyEditElement2{
populate_display_text="N/A";
return;
}
if(m_param_id==mPARAM_ID_FREQUENCY_SCAN){
populate_display_text="Debug";
return;
}
if(m_param_id==mPARAM_ID_FREQUENCY){
if(curr_channel_mhz<=0){
m_param_exists=false;
Expand All @@ -293,4 +279,5 @@ BaseJoyEditElement2{
m_param_exists=true;
}
}
}

}
2 changes: 1 addition & 1 deletion qml/ui/sidebar/Panel4Recording.qml
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ SideBarBasePanel {
anchors.centerIn: parent
anchors.leftMargin: 40
text: {
var tmp = " Status";
var tmp = " Status";
if (!_ohdSystemAir.is_alive) {
return tmp + " disabled ";
}
Expand Down
Loading