Skip to content
Next Next commit
Add optional_opencv_calibration_file as a yaml parameter
  • Loading branch information
jdcast committed Mar 29, 2024
commit 50f97f5f4360fc19cae944b957f06e390baa9fef
Original file line number Diff line number Diff line change
Expand Up @@ -652,6 +652,7 @@ class ZEDWrapperNodelet : public nodelet::Nodelet
bool mCameraSelfCalib;
bool mIsStatic = false;
double mPosTrkMinDepth = 0.0;
std::string mOptionalOpencvCalibrationFile;

// Flags
bool mGrabActive = false; // Indicate if camera grabbing is active (at least one topic subscribed)
Expand Down
4 changes: 4 additions & 0 deletions zed_nodelets/src/zed_nodelet/src/zed_wrapper_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -268,6 +268,7 @@ void ZEDWrapperNodelet::onInit()
mZedParams.open_timeout_sec = 10.0f;

mZedParams.enable_image_enhancement = true; // Always active
mZedParams.optional_opencv_calibration_file = mOptionalOpencvCalibrationFile.c_str();

mDiagUpdater.add("ZED Diagnostic", this, &ZEDWrapperNodelet::callback_updateDiagnostic);
mDiagUpdater.setHardwareID("ZED camera");
Expand Down Expand Up @@ -877,6 +878,9 @@ void ZEDWrapperNodelet::readGeneralParams()
NODELET_INFO_STREAM(" * Camera Flip\t\t\t-> " << sl::toString(mCameraFlip).c_str());
mNhNs.getParam("general/self_calib", mCameraSelfCalib);
NODELET_INFO_STREAM(" * Self calibration\t\t-> " << (mCameraSelfCalib ? "ENABLED" : "DISABLED"));

mNhNs.getParam("general/optional_opencv_calibration_file", mOptionalOpencvCalibrationFile);
NODELET_INFO_STREAM(" * Calibration File\t\t-> " << mOptionalOpencvCalibrationFile);

int tmp_sn = 0;
mNhNs.getParam("general/serial_number", tmp_sn);
Expand Down
1 change: 1 addition & 0 deletions zed_wrapper/params/common.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@ general:
#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.
#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.
#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.
optional_opencv_calibration_file: '/home/warp/Downloads/zedxm_warplab_tank_3_28_2024_cams-camchain-opencv.yaml'

#video:

Expand Down