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

Rapha dev #734

Merged
merged 17 commits into from
Mar 1, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
43 changes: 29 additions & 14 deletions app/telemetry/action/impl/xparam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 "<<finished.server_param_set.size()<<" params";
qDebug() << "Incoming PARAM_EXT_VALUE:";
qDebug() << " Param ID:" << get_param_id(response.param_id).c_str();
qDebug() << " Param Value:" << get_param_value_string(response.param_value).c_str();
qDebug() << " Param Type:" << response.param_type;
qDebug() << " Target SysID:" << sender_sysid;
qDebug() << " Target CompID:" << sender_compid;
qDebug() << " Param Count:" << response.param_count;
qDebug() << " Param Index:" << response.param_index;

auto opt_finished = find_remove_running_command_get_all_threadsafe(response, sender_sysid, sender_compid);
if (opt_finished.has_value()) {
auto finished = opt_finished.value();
std::vector<mavlink_param_ext_value_t> valid_param_set;
for(auto& param:finished.server_param_set){
for (auto &param : 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::RunningParamCmdSet> XParam::find_remove_running_command_threadsafe(const mavlink_param_ext_ack_t &ack,int sender_sysid,int sender_compid)
{
std::lock_guard<std::mutex> lock(m_mutex);
Expand Down Expand Up @@ -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);
}

Expand Down
41 changes: 40 additions & 1 deletion app/telemetry/settings/documentedparam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,42 @@ static std::vector<std::shared_ptr<XParam>> 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<ImprovedIntSetting::Item>{
{"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<ImprovedIntSetting::Item>{
{"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<std::string> values{};
values.push_back("Disable");
Expand Down Expand Up @@ -755,7 +791,10 @@ static std::map<std::string, void *> get_whitelisted_params()
//
ret["WB_V_FEC_PERC"]=nullptr;
ret["WB_V_RATE_PERC"]=nullptr;
ret["VARIABLE_BITRATE"]=nullptr;
ret["VARIcABLE_BITRATE"]=nullptr;
ret["QP_MIN"]=nullptr;
ret["QP_MAX"]=nullptr;

//
ret["TYPE_CAM0"]=nullptr;
ret["TYPE_CAM1"]=nullptr;
Expand Down
3 changes: 3 additions & 0 deletions app/telemetry/settings/param_names.h
Original file line number Diff line number Diff line change
Expand Up @@ -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";
Expand Down
29 changes: 19 additions & 10 deletions app/videostreaming/avcodec/avcodec_decoder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,15 +16,16 @@

#include "ExternalDecodeService.hpp"

static int hw_decoder_init(AVCodecContext *ctx, const enum AVHWDeviceType type){
static int hw_decoder_init(AVCodecContext *ctx, const enum AVHWDeviceType type) {
int err = 0;
ctx->hw_frames_ctx = NULL;
// ctx->hw_device_ctx gets freed when we call avcodec_free_context
if ((err = av_hwdevice_ctx_create(&ctx->hw_device_ctx, type,
NULL, NULL, 0)) < 0) {
fprintf(stderr, "Failed to create specified HW device.\n");
if ((err = av_hwdevice_ctx_create(&ctx->hw_device_ctx, type, NULL, NULL, 0)) < 0) {
char errbuf[128];
av_strerror(err, errbuf, sizeof(errbuf));
fprintf(stderr, "Failed to create HW device (%s): %s\n", av_hwdevice_get_type_name(type), errbuf);
return err;
}
qDebug() << "HW device created: " << av_hwdevice_get_type_name(type);
return err;
}

Expand Down Expand Up @@ -353,11 +354,11 @@ void AVCodecDecoder::on_new_frame(AVFrame *frame)
std::stringstream ss;
ss<<safe_av_get_pix_fmt_name((AVPixelFormat)frame->format)<<" "<<frame->width<<"x"<<frame->height;
DecodingStatistcs::instance().set_primary_stream_frame_format(QString(ss.str().c_str()));
//qDebug()<<"Got frame:"<<ss.str().c_str();
// qDebug()<<"Got frame:"<<ss.str().c_str();
}
// Once we got the first frame, reduce the log level
av_log_set_level(AV_LOG_WARNING);
//qDebug()<<debug_frame(frame).c_str();
// qDebug()<<debug_frame(frame).c_str();
TextureRenderer::instance().queue_new_frame_for_display(frame);
if(last_frame_width==-1 || last_frame_height==-1){
last_frame_width=frame->width;
Expand Down Expand Up @@ -508,14 +509,21 @@ int AVCodecDecoder::open_and_decode_until_error(const QOpenHDVideoHelper::VideoS
return 0;
}

const AVHWDeviceType kAvhwDeviceType = AV_HWDEVICE_TYPE_DRM;
#ifdef _WIN32
const AVHWDeviceType kAvhwDeviceType = AV_HWDEVICE_TYPE_D3D11VA;
#else
const AVHWDeviceType kAvhwDeviceType = AV_HWDEVICE_TYPE_DRM;
#endif

//const AVHWDeviceType kAvhwDeviceType = AV_HWDEVICE_TYPE_D3D11VA;
//const AVHWDeviceType kAvhwDeviceType = AV_HWDEVICE_TYPE_DXVA2;
//const AVHWDeviceType kAvhwDeviceType = AV_HWDEVICE_TYPE_DRM;
//const AVHWDeviceType kAvhwDeviceType = AV_HWDEVICE_TYPE_VAAPI;
//const AVHWDeviceType kAvhwDeviceType = AV_HWDEVICE_TYPE_CUDA;
//const AVHWDeviceType kAvhwDeviceType = AV_HWDEVICE_TYPE_VDPAU;

bool is_mjpeg=false;
if (decoder->id == AV_CODEC_ID_H264) {
qDebug()<<"H264 decode";
qDebug()<<all_hw_configs_for_this_codec(decoder).c_str();
if(!stream_config.enable_software_video_decoder){
// weird workaround needed for pi + DRM_PRIME
Expand Down Expand Up @@ -719,7 +727,8 @@ void AVCodecDecoder::open_and_decode_until_error_custom_rtp(const QOpenHDVideoHe
wanted_hw_pix_fmt = AV_PIX_FMT_MMAL;
use_pi_hw_decode=true;
}else{
wanted_hw_pix_fmt = AV_PIX_FMT_YUV420P;
qDebug()<<"Starting HW decode";
wanted_hw_pix_fmt = AV_PIX_FMT_DXVA2_VLD;
}
}else{
wanted_hw_pix_fmt = AV_PIX_FMT_YUV420P;
Expand Down
73 changes: 62 additions & 11 deletions app/videostreaming/avcodec/gl/gl_videorenderer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
#include "../avcodec_helper.hpp"
#include <libavutil/error.h>
#include <vector>
#include <cmath> // For dithering calculations

static EGLint texgen_attrs[] = {
EGL_DMA_BUF_PLANE0_FD_EXT,
Expand Down Expand Up @@ -357,18 +358,68 @@ static std::string safe_glGetString(GLenum name){
return std::string((const char*)tmp); // NOLINT(modernize-return-braced-init-list)
}
std::string GL_VideoRenderer::debug_info() {
const auto gl_vendor= safe_glGetString(GL_VENDOR);
const auto gl_renderer= safe_glGetString(GL_RENDERER);
const auto gl_version= safe_glGetString(GL_VERSION);
const auto gl_shading_language_version= safe_glGetString(GL_SHADING_LANGUAGE_VERSION);
std::stringstream ss;
ss<<"GL_VENDOR : "<< gl_vendor<<"\n";
ss<<"GL_RENDERER : "<< gl_renderer<<"\n";
ss<<"GL_VERSION : "<< gl_version<<"\n";
ss<<"GL_SHADING_LANGUAGE_VERSION : "<< gl_shading_language_version<<"\n";
return ss.str();
}
const auto gl_vendor = safe_glGetString(GL_VENDOR);
const auto gl_renderer = safe_glGetString(GL_RENDERER);
const auto gl_version = safe_glGetString(GL_VERSION);
const auto gl_shading_language_version = safe_glGetString(GL_SHADING_LANGUAGE_VERSION);
std::stringstream ss;

// Basic OpenGL Information
ss << "GL_VENDOR : " << gl_vendor << "\n";
ss << "GL_RENDERER : " << gl_renderer << "\n";
ss << "GL_VERSION : " << gl_version << "\n";
ss << "GL_SHADING_LANGUAGE_VERSION : " << gl_shading_language_version << "\n";

// Maximum texture size
GLint maxTextureSize = 0;
glGetIntegerv(GL_MAX_TEXTURE_SIZE, &maxTextureSize);
ss << "GL_MAX_TEXTURE_SIZE : " << maxTextureSize << "\n";

// Maximum texture units
GLint maxTextureUnits = 0;
glGetIntegerv(GL_MAX_TEXTURE_IMAGE_UNITS, &maxTextureUnits);
ss << "GL_MAX_TEXTURE_IMAGE_UNITS : " << maxTextureUnits << "\n";

// Extensions
std::string extensions = (const char*)glGetString(GL_EXTENSIONS);
ss << "Supported Extensions:\n" << extensions << "\n";

if (extensions.find("GL_OES_texture_float") != std::string::npos) {
ss << "Supports GL_OES_texture_float\n";
} else {
ss << "Does not support GL_OES_texture_float\n";
}

if (extensions.find("GL_OES_texture_half_float") != std::string::npos) {
ss << "Supports GL_OES_texture_half_float\n";
} else {
ss << "Does not support GL_OES_texture_half_float\n";
}

if (extensions.find("GL_EXT_color_buffer_half_float") != std::string::npos) {
ss << "Supports GL_EXT_color_buffer_half_float\n";
} else {
ss << "Does not support GL_EXT_color_buffer_half_float\n";
}

// Shader precision
GLint precisionRange[2];
GLint precisionBits;

glGetShaderPrecisionFormat(GL_FRAGMENT_SHADER, GL_HIGH_FLOAT, precisionRange, &precisionBits);
ss << "Fragment Shader High Float Precision: Range [" << precisionRange[0] << ", " << precisionRange[1]
<< "], Bits: " << precisionBits << "\n";

glGetShaderPrecisionFormat(GL_FRAGMENT_SHADER, GL_MEDIUM_FLOAT, precisionRange, &precisionBits);
ss << "Fragment Shader Medium Float Precision: Range [" << precisionRange[0] << ", " << precisionRange[1]
<< "], Bits: " << precisionBits << "\n";

glGetShaderPrecisionFormat(GL_FRAGMENT_SHADER, GL_LOW_FLOAT, precisionRange, &precisionBits);
ss << "Fragment Shader Low Float Precision: Range [" << precisionRange[0] << ", " << precisionRange[1]
<< "], Bits: " << precisionBits << "\n";

return ss.str();
}

std::vector<int> GL_VideoRenderer::supported_av_hw_formats()
{
Expand Down
26 changes: 16 additions & 10 deletions app/videostreaming/vscommon/QOpenHDVideoHelper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -199,20 +199,26 @@ static VideoStreamConfig read_config_from_settings(){
return ret;
}



// For OpenHD images, these files are copied over by the image builder and therefore can
// be used for testing / validation
static std::string get_default_openhd_test_file(const VideoCodec video_codec){
static std::string get_default_openhd_test_file(const VideoCodec video_codec) {
std::stringstream in_filename;
in_filename<<"/usr/local/share/testvideos/";
if(video_codec==QOpenHDVideoHelper::VideoCodecH264){
in_filename<<"rpi_1080.h264";
}else if(video_codec==QOpenHDVideoHelper::VideoCodecH265){
in_filename<<"jetson_test.h265";
}else{
in_filename<<"uv_640x480.mjpeg";
#ifdef _WIN32
// Use Windows path
in_filename << "C:\\\\testvideos\\\\";
#else
// Use Linux path
in_filename << "/usr/local/share/testvideos/";
#endif

if (video_codec == QOpenHDVideoHelper::VideoCodecH264) {
in_filename << "rpi_1080.h264";
} else if (video_codec == QOpenHDVideoHelper::VideoCodecH265) {
in_filename << "jetson_test.h265";
} else {
in_filename << "uv_640x480.mjpeg";
}

return in_filename.str();
}

Expand Down
2 changes: 1 addition & 1 deletion qml/ui/HUDOverlayGrid.qml
Original file line number Diff line number Diff line change
Expand Up @@ -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){
Expand Down
2 changes: 1 addition & 1 deletion qml/ui/configpopup/ConfigPopup.qml
Original file line number Diff line number Diff line change
Expand Up @@ -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--;
Expand Down
Loading
Loading