Sorry for the long response time; we conducted a bunch of tests.
Our Setup in the university lab:
- Robotics 360° Perception Kit
- Jetson Orin AGX running on Jetpack 6.2; jetson_clock enabled
- Stereolabs SDK 4.2.5 and zedlink-quad-1.2.2 driver
Our first problem:
We tried to stream all four cameras at once to a second machine using a Gigabit Ethernet direct link.
We started four processes of the attached streaming.cpp
code (also using the “High-level priority” in the scheduler for all four streaming processes).
What we observed was a massive load on the CPUs (all 12 cores at about 95%) and also on the GPU. We received the images on the second machine with four ZED_Explorer instances. As long as there is no change in the image, the FPS remains good at 1200p@60Hz for all cameras, but it drops instantly and proportionally to the changes in the image. This seems to be a problem, possibly with the codec. Could there be another bottleneck? The Jetson Orin load also changes proportionally to the image changes seen by the four cameras.
Our second problem (Timestamp differences):
We found the statement (ZED Link Quad GPIO Triggering - Stereolabs) that the two deserializers are not synced right now. So, when testing with two cameras (on different JP ports), we saw varying time deltas of about 1-8ms. We measured the two signals, as mentioned in the link, with the i2c settings and observed on an oscilloscope that there is always a changing time delta between the two deserializers. Our first thought was to measure this difference by acquiring the signals with the Jetson GPIO pins, calculate the time delta, and use this to synchronize the timestamps. Is this an appropriate solution? Are the timings changing (we already saw that they do change during resolution and FPS changes for a camera)?
/************************************************************************************************
** This sample shows how to stream remotely the video of a ZED camera. Any application using **
** the ZED SDK can receive and process this stream. See Camera Streaming/Receiver example. **
*************************************************************************************************/
// ZED includes
#include <sl/Camera.hpp>
// Sample includes
#include "utils.hpp"
// Using namespace
using namespace sl;
using namespace std;
void print(string msg_prefix, ERROR_CODE err_code = ERROR_CODE::SUCCESS, string msg_suffix = "");
int parseArgs(int argc, char **argv, sl::InitParameters& param, sl::StreamingParameters& sparam);
int main(int argc, char **argv) {
// Create a ZED camera
Camera zed;
StreamingParameters stream_params;
//stream_params.target_framerate = 60;
stream_params.codec = sl::STREAMING_CODEC::H265;
//stream_params.bitrate = 8000;
//stream_params.gop_size = 60;
stream_params.chunk_size = 1024;
stream_params.adaptative_bitrate = true;
// Set configuration parameters for the ZED
InitParameters init_parameters;
init_parameters.camera_resolution = sl::RESOLUTION::HD1080;
init_parameters.enable_image_enhancement = false;
init_parameters.enable_image_validity_check = false;
init_parameters.camera_disable_self_calib = true;
init_parameters.camera_fps = 60;
init_parameters.depth_mode = DEPTH_MODE::NONE;
init_parameters.depth_stabilization = 0;
init_parameters.coordinate_units = UNIT::METER;
init_parameters.depth_minimum_distance = 2.0f;
init_parameters.depth_maximum_distance = 3.0f;
init_parameters.async_image_retrieval = true;
int res_arg = parseArgs(argc, argv, init_parameters, stream_params);
// Open the camera
auto returned_state = zed.open(init_parameters);
if (returned_state != ERROR_CODE::SUCCESS) {
print("Camera Open", returned_state, "Exit program.");
return EXIT_FAILURE;
}
returned_state = zed.enableStreaming(stream_params);
if (returned_state != ERROR_CODE::SUCCESS) {
print("Streaming initialization error: ", returned_state);
return EXIT_FAILURE;
}
print("Streaming on port " + to_string(stream_params.port));
SetCtrlHandler();
while (!exit_app) {
if (zed.grab() != ERROR_CODE::SUCCESS)
sleep_us(10);
}
// disable Streaming
zed.disableStreaming();
// close the Camera
zed.close();
return EXIT_SUCCESS;
}
void print(string msg_prefix, ERROR_CODE err_code, string msg_suffix) {
cout << "[Sample]";
if (err_code != ERROR_CODE::SUCCESS)
cout << "[Error] ";
else
cout << " ";
cout << msg_prefix << " ";
if (err_code != ERROR_CODE::SUCCESS) {
cout << " | " << toString(err_code) << " : ";
cout << toVerbose(err_code);
}
if (!msg_suffix.empty())
cout << " " << msg_suffix;
cout << endl;
}
int parseArgs(int argc, char **argv, sl::InitParameters& param, sl::StreamingParameters& sparam) {
if (argc > 1 && string(argv[1]).find(".svo") != string::npos) {
// SVO input mode
param.input.setFromSVOFile(argv[1]);
cout << "[Sample] Using SVO File input: " << argv[1] << endl;
} else if (argc > 1 && string(argv[1]).find(".svo") == string::npos) {
string arg = string(argv[1]);
unsigned int a, b, c, d, port;
if (sscanf(arg.c_str(), "%u.%u.%u.%u:%d", &a, &b, &c, &d, &port) == 5) {
// Stream input mode - IP + port
string ip_adress = to_string(a) + "." + to_string(b) + "." + to_string(c) + "." + to_string(d);
param.input.setFromStream(sl::String(ip_adress.c_str()), port);
cout << "[Sample] Using Stream input, IP : " << ip_adress << ", port : " << port << endl;
} else if (sscanf(arg.c_str(), "%u.%u.%u.%u", &a, &b, &c, &d) == 4) {
// Stream input mode - IP only
param.input.setFromStream(sl::String(argv[1]));
cout << "[Sample] Using Stream input, IP : " << argv[1] << endl;
} else if (arg.find("HD2K") != string::npos) {
param.camera_resolution = RESOLUTION::HD2K;
cout << "[Sample] Using Camera in resolution HD2K" << endl;
}else if (arg.find("HD1200") != string::npos) {
param.camera_resolution = RESOLUTION::HD1200;
cout << "[Sample] Using Camera in resolution HD1200" << endl;
} else if (arg.find("HD1080") != string::npos) {
param.camera_resolution = RESOLUTION::HD1080;
cout << "[Sample] Using Camera in resolution HD1080" << endl;
} else if (arg.find("HD720") != string::npos) {
param.camera_resolution = RESOLUTION::HD720;
cout << "[Sample] Using Camera in resolution HD720" << endl;
}else if (arg.find("SVGA") != string::npos) {
param.camera_resolution = RESOLUTION::SVGA;
cout << "[Sample] Using Camera in resolution SVGA" << endl;
}else if (arg.find("VGA") != string::npos) {
param.camera_resolution = RESOLUTION::VGA;
cout << "[Sample] Using Camera in resolution VGA" << endl;
}
else if (arg.find("IN0") != string::npos) {
param.input.setFromCameraID(0);
}
else if (arg.find("CAM0") != string::npos) {
param.input.setFromSerialNumber(46899604);
sparam.port = 30000;
}
else if (arg.find("CAM1") != string::npos) {
param.input.setFromSerialNumber(43916681);
sparam.port = 30002;
}
else if (arg.find("CAM2") != string::npos) {
param.input.setFromSerialNumber(43804892);
sparam.port = 30004;
}
else if (arg.find("CAM3") != string::npos) {
param.input.setFromSerialNumber(43957242);
sparam.port = 30006;
}
else
return 1;
} else {
// Default
return 1;
}
return 0;
}