Skip to content

Commit 5d43df2

Browse files
committed
Merge branch 'improve_logging' into add_new_msg_srv
2 parents 04d1ffd + bed2863 commit 5d43df2

File tree

7 files changed

+16
-0
lines changed

7 files changed

+16
-0
lines changed

CHANGELOG.rst

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,10 @@
11
LATEST CHANGES
22
==============
33

4+
2025-04-18
5+
----------
6+
- Add parameter 'debug.sdk_verbose_log_file' to Stereo and Mono components to set the path of the SDK verbose log file
7+
48
2025-04-16
59
----------
610
- Fix realtime IMU data publishing when using SVO2

zed_components/src/zed_camera/include/zed_camera_component.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -318,6 +318,7 @@ class ZedCamera : public rclcpp::Node
318318
int mSvoFrameStart = 0;
319319
bool mUseSvoTimestamp = false;
320320
int mVerbose = 1;
321+
std::string mVerboseLogFile = "";
321322
int mGpuId = -1;
322323
std::string mOpencvCalibFile;
323324
sl::RESOLUTION mCamResol = sl::RESOLUTION::HD1080; // Default resolution: RESOLUTION_HD1080

zed_components/src/zed_camera/include/zed_camera_one_component.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -214,6 +214,7 @@ class ZedCameraOne : public rclcpp::Node
214214
bool _enableHDR = false; // Enable HDR if supported?
215215
std::string _opencvCalibFile; // Custom OpenCV calibration file
216216
int _sdkVerbose = 0; // SDK verbose level
217+
std::string _sdkVerboseLogFile = ""; // SDK Verbose Log file
217218
int _gpuId = -1; // GPU ID
218219

219220
int _camSerialNumber = 0; // Camera serial number

zed_components/src/zed_camera/src/zed_camera_component.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -541,6 +541,9 @@ void ZedCamera::getDebugParams()
541541
RCLCPP_INFO(get_logger(), "*** DEBUG parameters ***");
542542

543543
getParam("debug.sdk_verbose", mVerbose, mVerbose, " * SDK Verbose: ");
544+
getParam(
545+
"debug.sdk_verbose_log_file", mVerboseLogFile, mVerboseLogFile,
546+
" * SDK Verbose File: ");
544547

545548
getParam("debug.debug_common", _debugCommon, _debugCommon);
546549
RCLCPP_INFO(
@@ -4013,6 +4016,7 @@ bool ZedCamera::startCamera()
40134016
mInitParams.coordinate_units = ROS_MEAS_UNITS;
40144017
mInitParams.depth_mode = mDepthMode;
40154018
mInitParams.sdk_verbose = mVerbose;
4019+
mInitParams.sdk_verbose_log_file = mVerboseLogFile;
40164020
mInitParams.sdk_gpu_id = mGpuId;
40174021
mInitParams.depth_stabilization = mDepthStabilization;
40184022
mInitParams.camera_image_flip = (mCameraFlip ? sl::FLIP_MODE::ON : sl::FLIP_MODE::OFF);

zed_components/src/zed_camera/src/zed_camera_one_component.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -438,6 +438,9 @@ void ZedCameraOne::getDebugParams()
438438
RCLCPP_INFO(get_logger(), "*** DEBUG parameters ***");
439439

440440
getParam("debug.sdk_verbose", _sdkVerbose, _sdkVerbose, " * SDK Verbose: ", false, 0, 1000);
441+
getParam(
442+
"debug.sdk_verbose_log_file", _sdkVerboseLogFile, _sdkVerboseLogFile,
443+
" * SDK Verbose File: ");
441444

442445
getParam("debug.debug_common", _debugCommon, _debugCommon, " * Debug Common: ");
443446
getParam("debug.debug_video_depth", _debugVideoDepth, _debugVideoDepth, " * Debug Image/Depth: ");
@@ -701,6 +704,7 @@ bool ZedCameraOne::startCamera()
701704
_initParams.optional_opencv_calibration_file = _opencvCalibFile.c_str();
702705
}
703706
_initParams.sdk_verbose = _sdkVerbose;
707+
_initParams.sdk_verbose_log_file = _sdkVerboseLogFile;
704708
// <---- ZED configuration
705709

706710
// ----> Try to connect to a camera, to a stream, or to load an SVO

zed_wrapper/config/common_mono.yaml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,7 @@
5454

5555
debug:
5656
sdk_verbose: 1 # Set the verbose level of the ZED SDK
57+
sdk_verbose_log_file: '' # Path to the file where the ZED SDK will log its messages. If empty, no file will be created. The log level can be set using the `sdk_verbose` parameter.
5758
debug_common: false
5859
debug_video_depth: false
5960
debug_camera_controls: false

zed_wrapper/config/common_stereo.yaml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -172,6 +172,7 @@
172172

173173
debug:
174174
sdk_verbose: 1 # Set the verbose level of the ZED SDK
175+
sdk_verbose_log_file: '' # Path to the file where the ZED SDK will log its messages. If empty, no file will be created. The log level can be set using the `sdk_verbose` parameter.
175176
debug_common: false
176177
debug_sim: false
177178
debug_video_depth: false

0 commit comments

Comments
 (0)