Skip to content

Commit 3dc455e

Browse files
committed
Merge fix
2 parents f65bc13 + 85282e1 commit 3dc455e

File tree

4 files changed

+34
-5
lines changed

4 files changed

+34
-5
lines changed

CHANGELOG.rst

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

4+
2023-01-24
5+
----------
6+
- The parameter `general.sdk_verbose` has been moved to `debug.sdk_verbose` and set to `0` as default.
7+
- Add new parameter `general.optional_opencv_calibration_file` to use custom OpenCV camera calibrations.
8+
49
2023-12-21
510
----------
611
- Add [new tutorial](https://github.com/stereolabs/zed-ros2-examples/tree/master/tutorials/zed_robot_integration) to illustrate how to integrate one or more ZED cameras on a robot

zed_components/src/zed_camera/include/zed_camera_component.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -273,6 +273,7 @@ class ZedCamera : public rclcpp::Node
273273
bool mSvoRealtime = false;
274274
int mVerbose = 1;
275275
int mGpuId = -1;
276+
std::string mOpencvCalibFile;
276277
sl::RESOLUTION mCamResol = sl::RESOLUTION::HD1080; // Default resolution: RESOLUTION_HD1080
277278
PubRes mPubResolution = PubRes::NATIVE; // Use native grab resolution by default
278279
double mCustomDownscaleFactor = 1.0; // Used to rescale data with user factor

zed_components/src/zed_camera/src/zed_camera_component.cpp

Lines changed: 24 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -494,6 +494,8 @@ void ZedCamera::getDebugParams()
494494

495495
RCLCPP_INFO(get_logger(), "*** DEBUG parameters ***");
496496

497+
getParam("debug.sdk_verbose", mVerbose, mVerbose, " * SDK Verbose: ");
498+
497499
getParam("debug.debug_common", mDebugCommon, mDebugCommon);
498500
RCLCPP_INFO(get_logger(), " * Debug Common: %s", mDebugCommon ? "TRUE" : "FALSE");
499501

@@ -658,7 +660,6 @@ void ZedCamera::getGeneralParams()
658660
}
659661
RCLCPP_INFO_STREAM(get_logger(), " * Camera model: " << camera_model << " - " << mCamUserModel);
660662

661-
getParam("general.sdk_verbose", mVerbose, mVerbose, " * SDK Verbose: ");
662663
getParam("general.camera_name", mCameraName, mCameraName, " * Camera name: ");
663664
getParam("general.serial_number", mCamSerialNumber, mCamSerialNumber, " * Camera SN: ");
664665
getParam(
@@ -744,6 +745,10 @@ void ZedCamera::getGeneralParams()
744745
mCustomDownscaleFactor = 1.0;
745746
}
746747

748+
getParam(
749+
"general.optional_opencv_calibration_file", mOpencvCalibFile, mOpencvCalibFile,
750+
" * OpenCV custom calibration: ");
751+
747752
std::string parsed_str = getParam("general.region_of_interest", mRoiParam);
748753
RCLCPP_INFO_STREAM(get_logger(), " * Region of interest: " << parsed_str.c_str());
749754

@@ -3512,6 +3517,10 @@ bool ZedCamera::startCamera()
35123517
mInitParams.depth_minimum_distance = mCamMinDepth;
35133518
mInitParams.depth_maximum_distance = mCamMaxDepth;
35143519

3520+
if (!mOpencvCalibFile.empty()) {
3521+
mInitParams.optional_opencv_calibration_file = mOpencvCalibFile.c_str();
3522+
}
3523+
35153524
mInitParams.camera_disable_self_calib = !mCameraSelfCalib;
35163525
mInitParams.enable_image_enhancement = true;
35173526
mInitParams.enable_right_side_measure = false;
@@ -3540,6 +3549,20 @@ bool ZedCamera::startCamera()
35403549
break;
35413550
}
35423551

3552+
if (mConnStatus == sl::ERROR_CODE::INVALID_CALIBRATION_FILE) {
3553+
if (mOpencvCalibFile.empty()) {
3554+
RCLCPP_ERROR_STREAM(get_logger(), "Calibration file error: " << sl::toVerbose(mConnStatus));
3555+
} else {
3556+
RCLCPP_ERROR(get_logger(), "Custom OpenCV calibration file error.");
3557+
RCLCPP_ERROR_STREAM(
3558+
get_logger(),
3559+
"Please check the correctness of the path of the calibration file in the parameter 'general.optional_opencv_calibration_file': '" <<
3560+
mOpencvCalibFile << "'.");
3561+
RCLCPP_ERROR(get_logger(), "If the file exists, it may contain invalid information.");
3562+
}
3563+
return false;
3564+
}
3565+
35433566
if (mSvoMode) {
35443567
RCLCPP_WARN(get_logger(), "Error opening SVO: %s", sl::toString(mConnStatus).c_str());
35453568
return false;

zed_wrapper/config/common.yaml

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,11 @@
11
# config/common_yaml
22
# Common parameters to Stereolabs ZED and ZED mini cameras
3-
#
4-
# Note: the parameter svo_file is passed as exe argumet
3+
54
---
65
/**:
76
ros__parameters:
87

9-
use_sim_time: false # Set to `true` only if there is a publisher for the simulated clock to the `/clock` topic
8+
use_sim_time: false # Set to `true` only if there is a publisher for the simulated clock to the `/clock` topic. Normally used in simulation mode.
109

1110
simulation:
1211
sim_enabled: false # Set to `true` to enable the simulation mode and connect to a simulation server
@@ -25,11 +24,11 @@
2524
pub_downscale_factor: 2.0 # rescale factor used to rescale image before publishing when 'pub_resolution' is 'CUSTOM'
2625
pub_frame_rate: 15.0 # frequency of publishing of visual images and depth images
2726
gpu_id: -1
27+
optional_opencv_calibration_file: '' # Optional path where the ZED SDK can find a file containing the calibration information of the camera computed by OpenCV. Read the ZED SDK documentation for more information: https://www.stereolabs.com/docs/api/structsl_1_1InitParameters.html#a9eab2753374ef3baec1d31960859ba19
2828
region_of_interest: '[]' # A polygon defining the ROI where the ZED SDK perform the processing ignoring the rest. Coordinates must be normalized to '1.0' to be resolution independent.
2929
#region_of_interest: '[[0.25,0.33],[0.75,0.33],[0.75,0.5],[0.5,0.75],[0.25,0.5]]' # A polygon defining the ROI where the ZED SDK perform the processing ignoring the rest. Coordinates must be normalized to '1.0' to be resolution independent.
3030
#region_of_interest: '[[0.25,0.25],[0.75,0.25],[0.75,0.75],[0.25,0.75]]' # A polygon defining the ROI where the ZED SDK perform the processing ignoring the rest. Coordinates must be normalized to '1.0' to be resolution independent.
3131
#region_of_interest: '[[0.5,0.25],[0.75,0.5],[0.5,0.75],[0.25,0.5]]' # A polygon defining the ROI where the ZED SDK perform the processing ignoring the rest. Coordinates must be normalized to '1.0' to be resolution independent.
32-
sdk_verbose: 1
3332

3433
video:
3534
brightness: 4 # [DYNAMIC] Not available for ZED X/ZED X Mini
@@ -169,6 +168,7 @@
169168
thread_pointcloud_priority: 60 # ONLY with 'SCHED_FIFO' and 'SCHED_RR' - [1 (LOW) z-> 99 (HIGH)] - NOTE: 'sudo' required
170169

171170
debug:
171+
sdk_verbose: 0 # Set the verbose level of the ZED SDK
172172
debug_common: false
173173
debug_sim: false
174174
debug_video_depth: false

0 commit comments

Comments
 (0)