Preliminary Checks
Description
Hello,
I am experiencing unexpected memory increase when using the ZED SDK with the following configuration:
- Positional tracking module: enabled
- Pose tracking mode: GEN_3
- Area memory: disabled
- Mapping module: disabled
When replaying an SVO2 file (1080p, 30fps, with camera movement) or using the camera directly (and moving it), memory usage increases significantly over time:
- Initial memory usage: ~5.4%
- After 10 minutes: ~21.6%
Screenshots showing this progression (using htop) are attached below:
Given this configuration (area memory set to false and mapping module disabled), I would not expect memory to increase, so I'm reporting this as a potential memory leak. Please enlighten me if this memory usage increase is a normal behavior.
Steps to Reproduce
Compile the following code (area_memory_test.cpp):
#include <sl/Camera.hpp>
#include <iostream>
int main(int argc, char **argv)
{
if (argc < 2)
{
std::cerr << "Usage: " << argv[0] << " <svo-file>" << std::endl;
return EXIT_FAILURE;
}
std::string svo_name = argv[1];
sl::Camera zed;
sl::InitParameters init_params;
init_params.input.setFromSVOFile(svo_name.c_str());
init_params.depth_mode = sl::DEPTH_MODE::NEURAL;
init_params.coordinate_units = sl::UNIT::METER;
sl::ERROR_CODE state = zed.open(init_params);
if (state != sl::ERROR_CODE::SUCCESS)
{
std::cout << "Error Opening Camera: " << state << std::endl;
return EXIT_FAILURE;
}
sl::PositionalTrackingParameters tracking_params;
tracking_params.enable_area_memory = false;
tracking_params.mode = sl::POSITIONAL_TRACKING_MODE::GEN_3;
state = zed.enablePositionalTracking(tracking_params);
if (state != sl::ERROR_CODE::SUCCESS)
{
std::cout << "Error Enable Tracking: " << state << std::endl;
zed.close();
return EXIT_FAILURE;
}
zed.disableSpatialMapping();
sl::RuntimeParameters runtime_params;
while (true)
{
state = zed.grab(runtime_params);
if (state == sl::ERROR_CODE::END_OF_SVOFILE_REACHED)
{
std::cout << "End of SVO file reached." << std::endl;
break;
}
if (state == sl::ERROR_CODE::SUCCESS)
{
sl::Pose pose;
zed.getPosition(pose, sl::REFERENCE_FRAME::WORLD);
sl::Translation translation = pose.getTranslation();
sl::Orientation orientation = pose.getOrientation();
}
}
zed.close();
return EXIT_SUCCESS;
}
I personally used: g++ area_memory_test.cpp -o area_memory_test -I/usr/local/zed/include -I/usr/local/cuda/include -L/usr/local/zed/lib -L/usr/local/cuda/lib64 -lsl_zed -Wl,-rpath,/usr/local/zed/lib -Wl,-rpath,/usr/local/cuda/lib64
Run it. Preferably use a long SVO file (with the camera moving) to observe the increase.
Open htop and monitor the process memory usage over time.
Expected Result
Memory usage should remain stable and not increase over time.
Actual Result
Memory usage increases over time.
ZED Camera model
ZED2i
Environment
Issue observed on my laptop, as well as on Stereolabs Orin NX 16GB.
OS: Ubuntu 22.04
CPU: Intel(R) Core(TM) i7-10750H CPU @ 2.60GHz
GPU: NVIDIA GeForce GTX 1650 Ti
ZED SDK version: issue observed on both 5.0.7 and 5.1.2
ROS version: ROS2 humble
Anything else?
The issue appears to be specific to the pose tracking mode. When set to GEN_1, memory usage remains stable over time.
This behavior was also observed with the ROS2 wrapper, in which i loop the SVO files. I observed that memory increases during the first SVO replay and then stabilizes at that level for all subsequent replays (no further increase on replay 2, 3, etc.).
Also, this behavior is not observed when the camera is not moving (no increase in memory in either case: SVO playback or camera connected to a laptop).
Preliminary Checks
Description
Hello,
I am experiencing unexpected memory increase when using the ZED SDK with the following configuration:
When replaying an SVO2 file (1080p, 30fps, with camera movement) or using the camera directly (and moving it), memory usage increases significantly over time:
Screenshots showing this progression (using htop) are attached below:
Given this configuration (area memory set to false and mapping module disabled), I would not expect memory to increase, so I'm reporting this as a potential memory leak. Please enlighten me if this memory usage increase is a normal behavior.
Steps to Reproduce
Compile the following code (
area_memory_test.cpp):I personally used:
g++ area_memory_test.cpp -o area_memory_test -I/usr/local/zed/include -I/usr/local/cuda/include -L/usr/local/zed/lib -L/usr/local/cuda/lib64 -lsl_zed -Wl,-rpath,/usr/local/zed/lib -Wl,-rpath,/usr/local/cuda/lib64Run it. Preferably use a long SVO file (with the camera moving) to observe the increase.
Open htop and monitor the process memory usage over time.
Expected Result
Memory usage should remain stable and not increase over time.
Actual Result
Memory usage increases over time.
ZED Camera model
ZED2i
Environment
Anything else?
The issue appears to be specific to the pose tracking mode. When set to GEN_1, memory usage remains stable over time.
This behavior was also observed with the ROS2 wrapper, in which i loop the SVO files. I observed that memory increases during the first SVO replay and then stabilizes at that level for all subsequent replays (no further increase on replay 2, 3, etc.).
Also, this behavior is not observed when the camera is not moving (no increase in memory in either case: SVO playback or camera connected to a laptop).