Skip to content
Draft
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
52 changes: 29 additions & 23 deletions app/telemetry/action/impl/xparam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -431,20 +431,23 @@ void XParam::check_timeout_param_set()
std::vector<std::pair<RunningParamCmdSet,SetParamResult>> timed_out_commands{};
{
std::lock_guard<std::mutex> lock(m_mutex);
for (auto it=m_running_commands.begin(); it!=m_running_commands.end(); ++it){
RunningParamCmdSet& running_cmd=*it;
const auto elapsed=std::chrono::steady_clock::now()-running_cmd.last_transmission;
if(elapsed>running_cmd.retransmit_delay){
qDebug()<<"Param cmd set timeout";
if(running_cmd.n_transmissions<running_cmd.n_wanted_retransmissions){
qDebug()<<"Param cmd retransmit "<<running_cmd.n_transmissions;
for (auto it = m_running_commands.begin(); it != m_running_commands.end(); ) {
RunningParamCmdSet& running_cmd = *it;
const auto elapsed = std::chrono::steady_clock::now() - running_cmd.last_transmission;
if (elapsed > running_cmd.retransmit_delay) {
qDebug() << "Param cmd set timeout";
if (running_cmd.n_transmissions < running_cmd.n_wanted_retransmissions) {
qDebug() << "Param cmd retransmit " << running_cmd.n_transmissions;
send_next_message_running_set(running_cmd);
}else{
qDebug()<<"Timeout after "<<running_cmd.n_transmissions<<" transmissions";
SetParamResult result{std::nullopt,running_cmd.n_transmissions};
timed_out_commands.push_back(std::make_pair(running_cmd,result));
it=m_running_commands.erase(it);
++it;
} else {
qDebug() << "Timeout after " << running_cmd.n_transmissions << " transmissions";
SetParamResult result{std::nullopt, running_cmd.n_transmissions};
timed_out_commands.push_back(std::make_pair(running_cmd, result));
it = m_running_commands.erase(it);
}
} else {
++it;
}
}
}
Expand All @@ -458,19 +461,22 @@ void XParam::check_timeout_param_get_all()
std::vector<std::pair<RunningParamCmdGetAll,GetAllParamResult>> timed_out_commands{};
{
std::lock_guard<std::mutex> lock(m_mutex);
for (auto it=m_running_get_all.begin(); it!=m_running_get_all.end(); ++it){
RunningParamCmdGetAll& running_cmd=*it;
const auto elapsed=std::chrono::steady_clock::now()-running_cmd.last_transmission;
if(elapsed>running_cmd.retransmit_delay){
qDebug()<<"Param get all timeout";
if(running_cmd.n_transmissions<running_cmd.n_wanted_retransmissions){
for (auto it = m_running_get_all.begin(); it != m_running_get_all.end(); ) {
RunningParamCmdGetAll& running_cmd = *it;
const auto elapsed = std::chrono::steady_clock::now() - running_cmd.last_transmission;
if (elapsed > running_cmd.retransmit_delay) {
qDebug() << "Param get all timeout";
if (running_cmd.n_transmissions < running_cmd.n_wanted_retransmissions) {
send_next_message_running_get_all(running_cmd);
}else{
qDebug()<<"Timeout after "<<running_cmd.n_transmissions<<" transmissions";
GetAllParamResult result{false,{}};
timed_out_commands.push_back(std::make_pair(running_cmd,result));
it=m_running_get_all.erase(it);
++it;
} else {
qDebug() << "Timeout after " << running_cmd.n_transmissions << " transmissions";
GetAllParamResult result{false, {}};
timed_out_commands.push_back(std::make_pair(running_cmd, result));
it = m_running_get_all.erase(it);
}
} else {
++it;
}
}
}
Expand Down
10 changes: 9 additions & 1 deletion app/telemetry/models/aohdsystem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,11 @@ AOHDSystem::AOHDSystem(const bool is_air,QObject *parent)
{
m_alive_timer = std::make_unique<QTimer>(this);
QObject::connect(m_alive_timer.get(), &QTimer::timeout, this, &AOHDSystem::update_alive);
m_alive_timer->start(1000);
if (QCoreApplication::instance()) {
m_alive_timer->start(1000);
} else {
qDebug() << "AOHDSystem: No QCoreApplication instance, deferring timer start";
}
}

AOHDSystem &AOHDSystem::instanceAir()
Expand All @@ -108,6 +112,10 @@ bool AOHDSystem::process_message(const mavlink_message_t &msg)
}
autofech_params_if_apropriate();
m_last_message_ms=QOpenHDMavlinkHelper::getTimeMilliseconds();
if (!m_is_alive) {
// If we were not alive, update status immediately to make UI responsive
update_alive();
}
bool consumed=false;
switch(msg.msgid){
case MAVLINK_MSG_ID_OPENHD_VERSION_MESSAGE:{
Expand Down
4 changes: 3 additions & 1 deletion app/telemetry/models/openhd_core/platform.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ static constexpr int X_PLATFORM_TYPE_X86 = 1;
static constexpr int X_PLATFORM_TYPE_RPI_OLD = 10;
static constexpr int X_PLATFORM_TYPE_RPI_4 = 11;
static constexpr int X_PLATFORM_TYPE_RPI_CM4 = 12;
static constexpr int X_PLATFORM_TYPE_RPI_5 = 12;
static constexpr int X_PLATFORM_TYPE_RPI_5 = 13;

// Numbers 20..30 are reserved for rockchip
static constexpr int X_PLATFORM_TYPE_ROCKCHIP_RK3566_RADXA_ZERO3W =
Expand Down Expand Up @@ -58,6 +58,8 @@ static std::string x_platform_type_to_string(int platform_type) {
return "RPI<=3";
case X_PLATFORM_TYPE_RPI_4:
return "RPI 4";
case X_PLATFORM_TYPE_RPI_CM4:
return "RPI CM4";
case X_PLATFORM_TYPE_RPI_5:
return "RPI 5";
// RPI END
Expand Down
8 changes: 6 additions & 2 deletions app/telemetry/models/wificard.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ static std::string wifi_card_type_to_string(const int card_type) {
case 3:
return "88X2EU";
case 4:
return "OPENHD_8852BU";
return "OPENHD_8814AU";
case 5:
return "ERR_88X2AU";
case 6:
Expand All @@ -33,8 +33,12 @@ static std::string wifi_card_type_to_string(const int card_type) {
case 11:
return "BROADCOM";
case 12:
return "INTERNAL";
return "OPENHD_8852BU";
case 13:
return "OPENHD_EMULATED";
case 14:
return "AIC";
case 15:
return "QUALCOMM";
default:
return "UNKNOWN";
Expand Down
4 changes: 4 additions & 0 deletions app/videostreaming/gstreamer/gst_helper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,11 @@ static void init_gstreamer(int argc,char* argv[]){
// NOTE: Basically, it looks as if you NEED to do this before QT loads any .qml file(s) and if it fails
// qmlglsink won't work !!
static bool init_qmlglsink(){
#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0)
GstElement *sink = gst_element_factory_make("qml6glsink", NULL);
#else
GstElement *sink = gst_element_factory_make("qmlglsink", NULL);
#endif
if(sink==nullptr){
return false;
}
Expand Down
8 changes: 8 additions & 0 deletions app/videostreaming/gstreamer/gstqmlglsinkstream.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,11 +109,19 @@ static std::string constructGstreamerPipeline(const QOpenHDVideoHelper::VideoStr

//ss<<" videoconvert n-threads=2 ! queue ! video/x-raw,format=RGBA !";
if(false){
#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0)
ss<<"nvvidconv ! glupload ! qml6glsink name=qmlglsink sync=false";
#else
ss<<"nvvidconv ! glupload ! qmlglsink name=qmlglsink sync=false";
#endif
}else{
ss << " queue ! ";
ss << " glupload ! glcolorconvert !";
#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0)
ss << " qml6glsink name=qmlglsink sync=false";
#else
ss << " qmlglsink name=qmlglsink sync=false";
#endif
}
return ss.str();
}
Expand Down
15 changes: 15 additions & 0 deletions build_qmake.sh
Original file line number Diff line number Diff line change
Expand Up @@ -28,3 +28,18 @@ else
make -j$(( $(nproc) / 2 ))
fi

echo "Installing QOpenHD..."
if [ -f "release/QOpenHD" ]; then
sudo cp release/QOpenHD /usr/local/bin/QOpenHD
elif [ -f "debug/QOpenHD" ]; then
sudo cp debug/QOpenHD /usr/local/bin/QOpenHD
elif [ -f "QOpenHD" ]; then
sudo cp QOpenHD /usr/local/bin/QOpenHD
else
echo "Warning: QOpenHD binary not found in build directory."
exit 0
fi

sudo chmod +x /usr/local/bin/QOpenHD
echo "QOpenHD installed to /usr/local/bin/QOpenHD"

4 changes: 3 additions & 1 deletion qml/ui/configpopup/openhd_settings/PopupScanChannels.qml
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,9 @@ PopupBigGeneric{
id: model_chann_to_scan
ListElement {title: qsTr("OpenHD [1-7] only"); value: 0}
ListElement {title: qsTr("All 2.4G channels"); value: 1}
ListElement {title: qsTr("All 5.8G channels"); value: 2}
ListElement {title: qsTr("All 5GHz channels"); value: 2}
ListElement {title: qsTr("5.2GHz Lower only"); value: 3}
ListElement {title: qsTr("5.8GHz Upper only"); value: 4}
}

ColumnLayout{
Expand Down
4 changes: 2 additions & 2 deletions qml/ui/configpopup/status/StatusCardBodyOpenHD.qml
Original file line number Diff line number Diff line change
Expand Up @@ -189,14 +189,14 @@ Column {
m_left_text: qsTr("SysId:")
m_right_text: {
var air_fc_sys_id=_ohdSystemAir.air_reported_fc_sys_id;
if(air_fc_sys_id==-1){
if(air_fc_sys_id==-1 || air_fc_sys_id==255){
return qsTr("NOT FOUND")
}
return qsTr("FOUND: %1").arg(air_fc_sys_id);
}
m_error_text: {
var air_fc_sys_id=_ohdSystemAir.air_reported_fc_sys_id;
if(air_fc_sys_id==-1){
if(air_fc_sys_id==-1 || air_fc_sys_id==255){
return qsTr("Your AIR Unit cannot find your FC (UART). Please check:\n1) Wiring\n2) Right serial port enabled (OpenHD AIR param set)\n3) MAVLINK selected on your FC uart");
}
return qsTr("Please make sure:\n1) ARDUPILOT / PX4: FC sys id needs to be set to 1 (DEFAULT ARDUPILOT SYSID)\n2) INAV / Betaflight: Nothing needs to be changed, sys id should be 0");
Expand Down
Loading