Consistently Spaced Dropped Frames using c++ SDK

Hi there

We are using one zed2i on a Jetson Orin, with the zed SDK 4.1.1. jetson_clocks is running.

The zed2i is one of several sensors we have in our system, running on ROS. When we profiled the performance of the zed-ros-wrapper, we found it was dropping too many frames for our use case, and so we opted to instead write our own c++ script that calls the SDK directly and writes to svo2 files, which we post-process offboard.

This has some strange behaviour that we were hoping you may be able to help with or explain: when running a standalone c++ script, frames are dropped once per second consistently, seemingly agnostic to framerate.

Here’s my testing setup, let me know if I can provide you with anything else

Note: for all the tests below I overwrote the bag timestamps that rqt_bag uses with the image header timestamps, so that the rqt_bag visualization accurately reflects the capture times of the images.

Basline

I ran the zed-ros-wrapper configured as lightly as possible (no OD, mapping etc), at 15fps.

You can see that frames are dropped at varying intervals. This was the performance we wanted to improve upon.


Direct Comparison

Instead of running the zed-ros-wrapper, I ran our own custom ros node which is as lightweight as possible and only writes to an svo file, following the examples in your codebase. I ran the rest of our ROS system as well, for direct comparison to the zed-ros-wrapper performance in our system.

I post-processed via running the .svo2 files through a modified zed-ros-wrapper that publishes topics using the timestamps of the original svo image, and verified this works as expected. I then ran the same analysis as the baseline on the output rosbags.

You can see that frames are again dropped, but this time consistently around the second mark.


Standalone Tests

I also took the logic from our custom ROS node and put it in a standalone c++ script (included below), and then ran that without any other processes running on the Jetson and observed similar behaviour, with slightly different rates of frame drops.


And I ran the same test at 30fps, and saw something similar again. This seems to indicate we weren’t at the edge of the performance abilities at 15fps, seeing as most of the time it is able to consistently capture 30fps:


Conclusion

The odd pattern of the frame drops, and the fact that running at 30fps doesn’t change the pattern much, seems to me like the issue isn’t one of performance, and that there might be something blocking processing ~once per second. But I don’t know how to debug further.

At a high level, we are trying to ensure that frames don’t drop, and would gladly take any advice you have - we aren’t tied to using our custom ros node solution.

Thank you very much

Kappi

Here’s the standalone script:

#include <iostream>
#include <string>
#include <deque>
#include <atomic>
#include <chrono>
#include <thread>
#include <sl/Camera.hpp>

class ZedRecordingApp {
private:
    std::deque<sl::Timestamp> timestamps_;
    std::atomic<bool> recording_{false};
    sl::Camera zed_;
    std::string video_filename_;

public:
    ZedRecordingApp() {
        std::cout << "Initializing ZedRecordingApp..." << std::endl;
        openCamera();
    }

    ~ZedRecordingApp() {
        zed_.close();
    }

    void run() {
        while (true) {
            std::cout << "Waiting for recording to start..." << std::endl;
            if (recording_) {
                recordSvo();
            }
            std::this_thread::sleep_for(std::chrono::milliseconds(5));
        }
        zed_.close();
    }

    sl::RESOLUTION getResolutionFromString(const std::string& resolution) {
        if (resolution == "VGA") {
            return sl::RESOLUTION::VGA;
        } else if (resolution == "HD720") {
            return sl::RESOLUTION::HD720;
        } else if (resolution == "HD1080") {
            return sl::RESOLUTION::HD1080;
        } else if (resolution == "HD2K") {
            return sl::RESOLUTION::HD2K;
        } else {
            std::cerr << "Unknown resolution setting '" << resolution << "'. Defaulting to HD1080." << std::endl;
            return sl::RESOLUTION::HD1080;
        }
    }

    bool validateFramerateForResolution(const std::string& resolution, const int fps) {
        if (resolution == "VGA") {
            return (fps == 15 || fps == 30 || fps == 60 || fps == 100);
        } else if (resolution == "HD720") {
            return (fps == 15 || fps == 30 || fps == 60);
        } else if (resolution == "HD1080") {
            return (fps == 15 || fps == 30);
        } else if (resolution == "HD2K") {
            return (fps == 15);
        } else {
            std::cerr << "Unknown resolution setting '" << resolution << "'. Defaulting to HD1080." << std::endl;
            return (fps == 15 || fps == 30);
        }
    }

    void openCamera() {
        std::string camera_resolution = "HD1080";
        int camera_fps = 15;
        if (!validateFramerateForResolution(camera_resolution, camera_fps)) {
            std::cerr << "Invalid framerate for resolution. Shutting down the application." << std::endl;
            std::exit(EXIT_FAILURE);
        }

        sl::InitParameters init_params;
        init_params.camera_resolution = getResolutionFromString(camera_resolution);
        init_params.depth_mode = sl::DEPTH_MODE::NONE;
        init_params.camera_fps = camera_fps;
        init_params.input.setFromCameraID(0);

        sl::ERROR_CODE err = zed_.open(init_params);
        if (err != sl::ERROR_CODE::SUCCESS) {
            std::cerr << "ZED camera cannot be opened, error: " << sl::toString(err) << std::endl;
            std::exit(EXIT_FAILURE);
        }
        std::cout << "ZED camera opened successfully! Resolution: " << camera_resolution << ", FPS: " << camera_fps << std::endl;
    }

    void startRecording(const std::string& filename) {
        recording_ = true;
        video_filename_ = filename;
        std::cout << "Recording started. Filename: " << video_filename_ << std::endl;
    }

    void stopRecording() {
        recording_ = false;
        std::cout << "Recording stopped." << std::endl;
    }

 private:
    void recordSvo() {
        sl::RecordingParameters recording_params;
        recording_params.compression_mode = sl::SVO_COMPRESSION_MODE::H264;
        recording_params.video_filename = sl::String(video_filename_.c_str());

        auto err = zed_.enableRecording(recording_params);
        if (err != sl::ERROR_CODE::SUCCESS) {
            std::cerr << "Failed to start recording, error: " << sl::toString(err) << ". Shutting down the application." << std::endl;
            std::exit(EXIT_FAILURE);
        }

        while (recording_) {
            if (zed_.grab() == sl::ERROR_CODE::SUCCESS) {
                auto grab_ts = zed_.getTimestamp(sl::TIME_REFERENCE::IMAGE);
                timestamps_.push_back(grab_ts);
                if (timestamps_.size() > 10) {
                    timestamps_.pop_front();
                    auto window_size = 10;
                    auto time_span_nanos = timestamps_.back().getNanoseconds() - timestamps_.front().getNanoseconds();
                    double avg_hz = 1 / ((time_span_nanos / 1e9) / (window_size - 1));  // Calculate Hz
                    std::cout << "Publishing recording frequency: " << avg_hz << " Hz" << std::endl;
                }
            }
        }
        zed_.disableRecording();
        std::cout << "Recording ended." << std::endl;
    }
};

int main(int argc, char** argv) {
    ZedRecordingApp app;
    if (argc > 1 && std::string(argv[1]) == "start") {
        if (argc > 2) {
            app.startRecording(argv[2]);
        } else {
            std::cerr << "No filename provided for recording." << std::endl;
            return 1;
        }
    }
    app.run();
    return 0;
}

Hi @Kappibw
Welcome to the Stereolabs community and thank you for the exhaustive information.

The ZED SDK team received your report and we are analyzing all the information to eventually find the cause of the issue.

Can you please check if the latest ZED SDK v4.1.2 has the same issue?
An upgrade does not force you to change your code.

Hi there

I was wondering if you had a chance to look into this? I will try the latest SDK over the next week or so, but if you have any input that would be appreciated.

Hi again,

I updated to SDK 4.2 and the issue appears to be resolved! Thanks and I’ll reply if we run into it again.

1 Like