void ZEDCamera::loop() { ZED_TRACE("Start Camera Loop Thread"); setStatus(OpeningCamera); #ifdef ZED_NOISY_DEBUG ZED_TRACE("ZED_NOISY_DEBUG: Thread started successfully. Entering Phase 1 (GFX Sync)."); int gfxWaitWarnCount = 0; #endif // --- Phase 1: Graphics Initialization Sync --- while (!m_gfxReady && m_isAlive) { if (m_instances == 0 && m_trackings == 0) { m_thread->msleep(100); continue; } #ifdef ZED_NOISY_DEBUG // Print roughly every 1 second (15 * 64ms) if (++gfxWaitWarnCount % 15 == 0) { ZED_TRACE(QString("ZED_NOISY_DEBUG: Still waiting for GFX context to bind... m_gfxReady is false. Wait count: %1").arg(gfxWaitWarnCount)); } #endif emit gfxInitializationRequested(); m_thread->msleep(64); // Wait for GL context to bind } #ifdef ZED_NOISY_DEBUG if (m_isAlive) { ZED_TRACE("ZED_NOISY_DEBUG: Phase 1 Complete. GFX context bound successfully. Proceeding to main loop."); } #endif // Loop variables sl::ERROR_CODE err = sl::ERROR_CODE::SUCCESS; int frameWarningCount = 0; int frameErrorCount = 0; const int warningTries = 10000; const int errorTries = 10; int openRetryCount = 0; int retryOnSecs = 30; bool isFirstOpen = true; QTime retryTime = QTime::currentTime(); #ifdef ZED_NOISY_DEBUG uint64_t debugLoopCounter = 0; QElapsedTimer heartbeatTimer; heartbeatTimer.start(); #endif auto triggerRestart = [&](int seconds) { ZED_TRACE(QString("Restarting Camera (Delay: %1s)...").arg(seconds)); closeCamera(); // 1. MUST BE FIRST: Close the software handle cleanly, freeing GPU/AI memory sl::Camera::reboot(m_serial.toInt()); // 2. Hard reset the hardware m_restartCamera = false; retryTime = QTime::currentTime(); retryOnSecs = seconds; // Give Windows and the USB Controller time to re-enumerate the device setCameraInfo("🟡 Hardware reset triggered. Waiting for USB re-enumeration..."); }; // --- Phase 2: Main Operational Loop --- while (m_isAlive.load(std::memory_order_relaxed)) { #ifdef ZED_NOISY_DEBUG debugLoopCounter++; if (heartbeatTimer.hasExpired(5000)) { // <--- Safe check for 5000ms ZED_TRACE(QString("[THREAD HEARTBEAT] Plugin & Thread Alive | Iterations: %1 | GFX: %2 | Cam: %3 | Track: %4 | Status: %5 | Instances: %6") .arg(debugLoopCounter) .arg(m_gfxReady ? "OK" : "WAIT") .arg(m_cameraReady ? "OK" : "WAIT") .arg(m_trackingReady ? "OK" : "WAIT") .arg(statusStr()) .arg(m_instances.load())); heartbeatTimer.restart(); } #endif // A) CONNECTION MANAGEMENT if (!m_cameraReady) { if (!isFirstOpen && retryTime.secsTo(QTime::currentTime()) < retryOnSecs) { m_thread->msleep(200); continue; } setCameraInfo("🟡 Initializing camera..."); if (!isFirstOpen) { ZED_TRACE(QString("Retry Attempt %1. Cooldown: %2s").arg(openRetryCount).arg(retryOnSecs)); } err = openCamera(); if (err != sl::ERROR_CODE::SUCCESS) { isFirstOpen = false; openRetryCount++; retryTime = QTime::currentTime(); setCameraError(err, "Open Camera", QString(" Connection retry on %1 secs").arg(retryOnSecs)); if (openRetryCount > 1000) { setCameraInfo("🔴 Camera Not Found"); break; // Hard exit loop } continue; } // Success: Reset state isFirstOpen = false; openRetryCount = 0; frameWarningCount = 0; frameErrorCount = 0; setStatus(CameraOk); setCameraInfo("🟢 Ready"); } // B) TRACKING & AI SYNC if (m_cameraReady) { if (m_trackings > 0 && !m_trackingReady && m_status != ErrorTracking) { setStatus(InitializingTracking); setCameraInfo("🟡 Initializing Camera Tracking..."); err = initializeTracking(); if (err != sl::ERROR_CODE::SUCCESS) { setStatus(ErrorTracking); setCameraError(err, "AI Optimization"); } else { setStatus(CameraOk); setCameraInfo("🟢 Ready"); } } else if (m_trackings == 0 && m_trackingReady) { finalizeTracking(); } } // C) MANUAL RESTART CHECK (TestRequested or KeepAlive Timeout) if (m_restartCamera) { triggerRestart(15); continue; } // D) GRAB & PROCESS sl::ERROR_CODE grabErr = grabFrame(); sl::ERROR_CODE viewErr = (grabErr == sl::ERROR_CODE::SUCCESS) ? generateFrameViews() : grabErr; if (grabErr == sl::ERROR_CODE::SUCCESS && viewErr == sl::ERROR_CODE::SUCCESS) { frameWarningCount = 0; frameErrorCount = 0; if (generateBoxTracking()) { static int frameGood = 0; if (++frameGood % 600 == 0) { emit keepAliveConfirmed(); frameGood = 0; } } m_thread->msleep(2); // Breath room for the GPU context continue; } // E) ERROR HANDLING err = (grabErr != sl::ERROR_CODE::SUCCESS) ? grabErr : viewErr; if (err < sl::ERROR_CODE::SUCCESS) { // Periodic error logging for "Soft" errors (like darkness) if (++frameWarningCount % 1000 == 0) { ZED_TRACE(QString(">>> Grab Warning: %1. Counter: %2/%3") .arg(skCameraError(err)).arg(frameWarningCount).arg(warningTries)); setCameraError(err, "Grab Frame"); } if (frameWarningCount >= warningTries && err != sl::ERROR_CODE::CAMERA_REBOOTING) { ZED_TRACE(">>> Warning threshold reached. Restarting..."); setStatus(ErrorTracking); triggerRestart(30); } #ifdef ZED_NOISY_DEBUG ZED_TRACE(QString(">>> Grab Warning: %1. Counter: %2/%3") .arg(skCameraError(err)).arg(frameWarningCount).arg(warningTries)); #endif } else { // Bad errors if (++frameErrorCount >= errorTries) { ZED_TRACE(">>> Error threshold reached. Restarting..."); setStatus(ErrorTracking); triggerRestart(30); } else { // Wait a bit m_thread->msleep(500); } #ifdef ZED_NOISY_DEBUG ZED_TRACE(QString(">>> Grab Error: %1. Counter: %2/%3") .arg(skCameraError(err)).arg(frameErrorCount).arg(errorTries)); #endif } } // --- Phase 3: Exit Logic --- #ifdef ZED_NOISY_DEBUG ZED_TRACE("ZED_NOISY_DEBUG: m_isAlive became false. Thread breaking out of Phase 2 Loop. Initiating Shutdown."); #endif closeCamera(); // Preserve Error statuses for the Frontend to see why we stopped if (m_status != ErrorOpen && m_status != ErrorTracking) { setStatus(CameraClosed); } emit gfxFinalizationRequested(); ZED_TRACE("End Loop Thread"); } sl::ERROR_CODE ZEDCamera::openCamera() { if (m_camera) { closeCamera(); } QMutexLocker ml (&s_hardwareAccessMutex); // --- CHECK AND DOWNLOAD CALIBRATION FILE --- const QString settingsPath = "C:/ProgramData/Stereolabs/settings"; QDir settingsDir(settingsPath); if (settingsDir.mkpath(".")) { auto devices = sl::Camera::getDeviceList(); for (const auto& device : devices) { unsigned int serial = device.serial_number; if (serial == 0) continue; ZED_TRACE(QString("Checking calib file for SN: %1").arg(serial)); const QString confFileName = QString("SN%1.conf").arg(serial); const QString confFilePath = settingsDir.absoluteFilePath(confFileName); if (!QFile::exists(confFilePath)) { ZED_TRACE(QString("Calibration file %1 not found. Downloading...").arg(confFileName)); const QString urlStr = QString("https://www.stereolabs.com/developers/calib/?SN=%1").arg(serial); QNetworkAccessManager manager; QNetworkRequest request((QUrl(urlStr))); request.setAttribute(QNetworkRequest::RedirectPolicyAttribute, QNetworkRequest::NoLessSafeRedirectPolicy); request.setHeader(QNetworkRequest::UserAgentHeader, "Mozilla/4.0"); QEventLoop netLoop; QTimer netTimer; netTimer.setSingleShot(true); netTimer.setInterval(15000); // 15 seconds timeout QObject::connect(&netTimer, &QTimer::timeout, &netLoop, &QEventLoop::quit); QObject::connect(&manager, &QNetworkAccessManager::finished, &netLoop, &QEventLoop::quit); QNetworkReply *reply = manager.get(request); netTimer.start(); netLoop.exec(); if (netTimer.isActive()) { netTimer.stop(); if (reply->error() == QNetworkReply::NoError) { const QByteArray data = reply->readAll(); if (!data.isEmpty() && !data.contains("ERROR")) { QFile file(confFilePath); if (file.open(QIODevice::WriteOnly)) { file.write(data); file.close(); ZED_TRACE(QString("Successfully downloaded calibration file to %1").arg(confFilePath)); } else { ZED_TRACE(QString("Failed to write calibration file to %1").arg(confFilePath)); } } else { ZED_TRACE("Failed to download calibration file: response is empty or contains ERROR."); } } else { ZED_TRACE(QString("Network error downloading calibration file: %1").arg(reply->errorString())); } } else { ZED_TRACE("Network timeout downloading calibration file."); reply->abort(); } delete reply; } } } // ------------------------------------------- ZED_TRACE(QString("OPENING CAMERA [%1], Mode: %2").arg(m_serial, modeStr())); m_camera = new sl::Camera; sl::RESOLUTION res = sl::RESOLUTION::HD720; switch (m_mode) { case ZedLow: m_fps = 15; res = sl::RESOLUTION::HD720; break; case ZedMed: m_fps = 30; res = sl::RESOLUTION::HD720; break; case ZedMed2: m_fps = 15; res = sl::RESOLUTION::HD1080; break; case ZedHigh: m_fps = 30; res = sl::RESOLUTION::HD720; break; case ZedHigh2: m_fps = 30; res = sl::RESOLUTION::HD1080; break; } sl::InitParameters initParams {}; initParams.sdk_verbose = 0; #ifdef ZED_NOISY_DEBUG initParams.sdk_verbose = 1; #endif initParams.camera_fps = m_fps; initParams.camera_resolution = res; initParams.open_timeout_sec = 10.f; initParams.camera_disable_self_calib = true; initParams.depth_mode = sl::DEPTH_MODE::NEURAL_LIGHT; initParams.coordinate_units = sl::UNIT::METER; //initParams.grab_compute_capping_fps = qMin(m_fps, 30); /// REVIEW WHEN OTHER PROBLEMS SOLVED initParams.async_grab_camera_recovery = false; // We manage recovery initParams.enable_image_enhancement = false; initParams.enable_image_validity_check = false; initParams.depth_stabilization = 0; initParams.input.setFromSerialNumber(m_serial.toInt()); emit startOpenTimerRequested(); auto const err = m_camera->open(initParams); emit stopOpenTimerRequested(); if (err != sl::ERROR_CODE::SUCCESS) { // *** Errors Found: // - CAMERA_NOT_DETECTED: Bad USB connection. If Camera not connected, this point is not reached // - CORRUPTED_SDK_INSTALLATION: AI Resource Not Found, error trying to download it. No internet connection. // *** Possible Errors: // - NOT_ENOUGH_GPU_MEMORY, CUDA_ERROR, MODULE_NOT_COMPATIBLE_WITH_CUDA_VERSION closeCamera(); return err; } m_cameraReady = true; ZED_TRACE("OPENED"); return sl::ERROR_CODE::SUCCESS; } void ZEDCamera::closeCamera() { if (!m_camera) return; ZED_TRACE("CLOSING CAMERA AND CLEARING CUDA CONTEXT"); m_trackingReady = false; m_cameraReady = false; // 1. Stop timers using thread-safe calls QMetaObject::invokeMethod(&m_openTimer, "stop", Qt::QueuedConnection); QMetaObject::invokeMethod(&m_trackingTimer, "stop", Qt::QueuedConnection); QMetaObject::invokeMethod(&m_keepAliveTimer, "stop", Qt::QueuedConnection); // 2. Clear sl::Mat buffers FIRST, look at @warning from m_camera->close() m_viewBuffer.clear(); m_objects.object_list.clear(); // 3. Disable modules individually (ZED SDK sometimes hangs if you close() while AI is active) m_camera->disableObjectDetection(); // 1. MUST BE DISABLED FIRST m_camera->disablePositionalTracking(); // 2. THEN DISABLE TRACKING // 4. If it hangs on close, it is probably here // To prevent the destructor from hanging the app, we use a guard m_camera->close(); delete m_camera; m_camera = nullptr; ZED_TRACE("CLOSED SUCCESSFULLY"); }