diff --git a/app/telemetry/action/impl/xparam.cpp b/app/telemetry/action/impl/xparam.cpp index fd6b19a10..69efa01cf 100644 --- a/app/telemetry/action/impl/xparam.cpp +++ b/app/telemetry/action/impl/xparam.cpp @@ -223,25 +223,30 @@ bool XParam::handle_param_ext_ack(const mavlink_param_ext_ack_t &ack,int sender_ bool XParam::handle_param_ext_value(const mavlink_param_ext_value_t &response, int sender_sysid, int sender_compid) { - //qDebug()<<"Got mavlink_param_ext_value_t"; - auto opt_finished=find_remove_running_command_get_all_threadsafe(response,sender_sysid,sender_compid); - if(opt_finished.has_value()){ - //qDebug()<<"Finished get_all command"; - auto finished=opt_finished.value(); - //qDebug()<<"Got "< valid_param_set; - for(auto& param:finished.server_param_set){ + for (auto ¶m : finished.server_param_set) { assert(param.has_value()); valid_param_set.push_back(param.value()); } - GetAllParamResult result{true,valid_param_set}; + GetAllParamResult result{true, valid_param_set}; finished.cb(result); return true; } return true; } - std::optional XParam::find_remove_running_command_threadsafe(const mavlink_param_ext_ack_t &ack,int sender_sysid,int sender_compid) { std::lock_guard lock(m_mutex); @@ -348,12 +353,22 @@ void XParam::send_next_message_running_get_all(RunningParamCmdGetAll& running_cm running_cmd.n_transmissions++; } -void XParam::send_param_ext_set(const mavlink_param_ext_set_t &cmd) -{ - const auto self_sysid=QOpenHDMavlinkHelper::get_own_sys_id(); - const auto self_compid=QOpenHDMavlinkHelper::get_own_comp_id(); +void XParam::send_param_ext_set(const mavlink_param_ext_set_t &cmd) { + const auto self_sysid = QOpenHDMavlinkHelper::get_own_sys_id(); + const auto self_compid = QOpenHDMavlinkHelper::get_own_comp_id(); mavlink_message_t msg{}; - mavlink_msg_param_ext_set_encode(self_sysid,self_compid,&msg,&cmd); + mavlink_msg_param_ext_set_encode(self_sysid, self_compid, &msg, &cmd); + + // Display the MAVLink message details directly in this function + qDebug() << "MAVLink Message:"; + qDebug() << " Msg ID:" << msg.msgid; + qDebug() << " System ID:" << msg.sysid; + qDebug() << " Component ID:" << msg.compid; + qDebug() << " Command: PARAM_EXT_SET"; + qDebug() << " Param ID:" << cmd.param_id; + qDebug() << " Param Value:" << cmd.param_value; + qDebug() << " Param Type:" << cmd.param_type; + MavlinkTelemetry::instance().sendMessage(msg); } diff --git a/app/telemetry/settings/documentedparam.cpp b/app/telemetry/settings/documentedparam.cpp index 4fb0088ec..330b7c322 100644 --- a/app/telemetry/settings/documentedparam.cpp +++ b/app/telemetry/settings/documentedparam.cpp @@ -52,6 +52,42 @@ static std::vector> get_parameters_list(){ "Recommend a matching bitrate to the encoder depending on the selected link parameters,and reduce bitrate on TX errors (failed injections). On by default, but only works on select cameras. On Cameras that" "don't support changing the bitrate / are bad at targeting a given bitrate, you have to adjust your link according to your camera needs." ); + { + auto default_values=std::vector{ + {"AUTO (Default)", 0}, + {"10 (Very High Quality)", 10}, + {"12 (High Quality)", 12}, + {"15 (Good Quality)", 15}, + {"18 (Standard Quality)", 18}, + {"20 (Moderate Compression)", 20}, + {"25 (Balanced Quality & Compression)", 25}, + {"30 (Moderate Compression)", 30}, + {"40 (Low Quality)", 40}, + {"51 (Very Low Quality)", 51} + }; + append_int(ret,openhd::WB_QP_MAX, + ImprovedIntSetting(0,51,default_values), + "QP_MIN for Rockchip" + ); + } + { + auto default_values=std::vector{ + {"AUTO (Default)", 0}, + {"10 (Very High Quality)", 10}, + {"12 (High Quality)", 12}, + {"15 (Good Quality)", 15}, + {"18 (Standard Quality)", 18}, + {"20 (Moderate Compression)", 20}, + {"25 (Balanced Quality & Compression)", 25}, + {"30 (Moderate Compression)", 30}, + {"40 (Low Quality)", 40}, + {"51 (Very Low Quality)", 51} + }; + append_int(ret,openhd::WB_QP_MIN, + ImprovedIntSetting(0,51,default_values), + "QP_MIN for Rockchip" + ); + } { std::vector values{}; values.push_back("Disable"); @@ -756,6 +792,9 @@ static std::map get_whitelisted_params() ret["WB_V_FEC_PERC"]=nullptr; ret["WB_V_RATE_PERC"]=nullptr; ret["VARIABLE_BITRATE"]=nullptr; + ret["QP_MIN"]=nullptr; + ret["QP_MAX"]=nullptr; + // ret["TYPE_CAM0"]=nullptr; ret["TYPE_CAM1"]=nullptr; diff --git a/app/telemetry/settings/param_names.h b/app/telemetry/settings/param_names.h index 7885f9267..097382d45 100644 --- a/app/telemetry/settings/param_names.h +++ b/app/telemetry/settings/param_names.h @@ -22,6 +22,9 @@ static constexpr auto WB_RTL8812AU_TX_PWR_IDX_OVERRIDE="TX_POWER_I"; static constexpr auto WB_RTL8812AU_TX_PWR_IDX_ARMED="TX_POWER_I_ARMED"; // static constexpr auto WB_VIDEO_VARIABLE_BITRATE="VARIABLE_BITRATE"; +static constexpr auto WB_QP_MIN="QP_MIN"; +static constexpr auto WB_QP_MAX="QP_MAX"; + // static constexpr auto WB_ENABLE_STBC="WB_E_STBC"; static constexpr auto WB_ENABLE_LDPC="WB_E_LDPC"; diff --git a/qml/ui/HUDOverlayGrid.qml b/qml/ui/HUDOverlayGrid.qml index 1c58b906a..ee1aede88 100644 --- a/qml/ui/HUDOverlayGrid.qml +++ b/qml/ui/HUDOverlayGrid.qml @@ -202,7 +202,7 @@ Item { } Keys.onPressed: (event)=> { - console.log("HUDOverlayGrid::Key was pressed:"+event); + // console.log("HUDOverlayGrid::Key was pressed:"+event); if(event.key==Qt.Key_Left || event.key == Qt.Key_Right || event.key == Qt.Key_Up || event.key == Qt.Key_Down){ // If the user presses any navigation key, we open up the sidebar and hand over the inputs to it if(!sidebar.m_extra_is_visible){ diff --git a/qml/ui/configpopup/ConfigPopup.qml b/qml/ui/configpopup/ConfigPopup.qml index 83152c618..da63960e4 100644 --- a/qml/ui/configpopup/ConfigPopup.qml +++ b/qml/ui/configpopup/ConfigPopup.qml @@ -140,7 +140,7 @@ Rectangle { clip: true Keys.onPressed: (event)=> { - console.log("Sidebar Key was pressed:"+event); + // console.log("Sidebar Key was pressed:"+event); var tmp_index=mainStackLayout.currentIndex; if(event.key==Qt.Key_Up){ tmp_index--; diff --git a/qml/ui/sidebar/BaseJoyEditElement.qml b/qml/ui/sidebar/BaseJoyEditElement.qml index 2f227eae9..29b48b6f5 100644 --- a/qml/ui/sidebar/BaseJoyEditElement.qml +++ b/qml/ui/sidebar/BaseJoyEditElement.qml @@ -55,7 +55,7 @@ Item{ signal goto_next(); Keys.onPressed: (event)=> { - console.log("BaseJoyElement"+m_title+" key was pressed:"+event); + // console.log("BaseJoyElement"+m_title+" key was pressed:"+event); if(event.key == Qt.Key_Left){ if(m_button_left_activated){ choice_left() diff --git a/qml/ui/sidebar/ChoiceSelector.qml b/qml/ui/sidebar/ChoiceSelector.qml index d99acca03..915e09dcd 100644 --- a/qml/ui/sidebar/ChoiceSelector.qml +++ b/qml/ui/sidebar/ChoiceSelector.qml @@ -79,7 +79,7 @@ Rectangle{ Keys.onPressed: (event)=> { - console.log("ChoiceSelector key was pressed:"+event); + // console.log("ChoiceSelector key was pressed:"+event); if(event.key == Qt.Key_Left){ // Either close immediately or go back to the initial choice (don't save) if(m_current_user_selected_index==m_initial_index){ diff --git a/qml/ui/sidebar/GoBackElement.qml b/qml/ui/sidebar/GoBackElement.qml index 3c19aa6ee..18e24f577 100644 --- a/qml/ui/sidebar/GoBackElement.qml +++ b/qml/ui/sidebar/GoBackElement.qml @@ -36,7 +36,7 @@ Item{ } Keys.onPressed: (event)=> { - console.log("Go back element key was pressed:"+event); + // console.log("Go back element key was pressed:"+event); if(event.key == Qt.Key_Left || event.key == Qt.Key_Right || event.key == Qt.Key_Return){ close_and_go_back() } diff --git a/qml/ui/sidebar/MavlinkChoiceElement2.qml b/qml/ui/sidebar/MavlinkChoiceElement2.qml index 120a85697..96da862f3 100644 --- a/qml/ui/sidebar/MavlinkChoiceElement2.qml +++ b/qml/ui/sidebar/MavlinkChoiceElement2.qml @@ -46,7 +46,7 @@ BaseJoyEditElement2{ } Keys.onPressed: (event)=> { - console.log("BaseJoyElement"+m_title+" key was pressed:"+event); + // console.log("BaseJoyElement"+m_title+" key was pressed:"+event); if(event.key == Qt.Key_Left){ sidebar.regain_control_on_sidebar_stack(); event.accepted=true; diff --git a/qml/ui/sidebar/SidebarStackButton.qml b/qml/ui/sidebar/SidebarStackButton.qml index 773201c77..b3a010bec 100644 --- a/qml/ui/sidebar/SidebarStackButton.qml +++ b/qml/ui/sidebar/SidebarStackButton.qml @@ -59,7 +59,7 @@ Item { } Keys.onPressed: (event)=> { - console.log("SidebarStackButton"+override_tag+" key was pressed:"+event); + // console.log("SidebarStackButton"+override_tag+" key was pressed:"+event); if(event.key === Qt.Key_Up){ m_stack_index--; if(m_stack_index<-1){ diff --git a/qml/ui/widgets/BaseWidget.qml b/qml/ui/widgets/BaseWidget.qml index bf0aeeb86..d70954546 100644 --- a/qml/ui/widgets/BaseWidget.qml +++ b/qml/ui/widgets/BaseWidget.qml @@ -137,7 +137,7 @@ BaseWidgetForm { // react to the user opening the (currently focused) widget Keys.onPressed: (event)=> { - console.log("BaseWidget "+widgetIdentifier+" Key was pressed:"+event); + // console.log("BaseWidget "+widgetIdentifier+" Key was pressed:"+event); if (event.key == Qt.Key_Return) { console.log("enter was pressed"); event.accepted = true;