diff --git a/zed_nodelets/src/zed_nodelet/include/zed_wrapper_nodelet.hpp b/zed_nodelets/src/zed_nodelet/include/zed_wrapper_nodelet.hpp index cc33cec5..a2ecbd99 100644 --- a/zed_nodelets/src/zed_nodelet/include/zed_wrapper_nodelet.hpp +++ b/zed_nodelets/src/zed_nodelet/include/zed_wrapper_nodelet.hpp @@ -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) diff --git a/zed_nodelets/src/zed_nodelet/src/zed_wrapper_nodelet.cpp b/zed_nodelets/src/zed_nodelet/src/zed_wrapper_nodelet.cpp index 5492de5e..576a8a6d 100644 --- a/zed_nodelets/src/zed_nodelet/src/zed_wrapper_nodelet.cpp +++ b/zed_nodelets/src/zed_nodelet/src/zed_wrapper_nodelet.cpp @@ -268,6 +268,8 @@ void ZEDWrapperNodelet::onInit() mZedParams.open_timeout_sec = 10.0f; mZedParams.enable_image_enhancement = true; // Always active + sl::String optional_opencv_calibration_file(mOptionalOpencvCalibrationFile.c_str()); + mZedParams.optional_opencv_calibration_file = optional_opencv_calibration_file; mDiagUpdater.add("ZED Diagnostic", this, &ZEDWrapperNodelet::callback_updateDiagnostic); mDiagUpdater.setHardwareID("ZED camera"); @@ -877,6 +879,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); diff --git a/zed_wrapper/launch/include/zed_camera.launch.xml b/zed_wrapper/launch/include/zed_camera.launch.xml index 9a50e661..d70b0e08 100644 --- a/zed_wrapper/launch/include/zed_camera.launch.xml +++ b/zed_wrapper/launch/include/zed_camera.launch.xml @@ -46,6 +46,14 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + + + + + + + + + + + + + + + diff --git a/zed_wrapper/launch/zedxm.launch b/zed_wrapper/launch/zedxm.launch index adcc9e63..9f783649 100644 --- a/zed_wrapper/launch/zedxm.launch +++ b/zed_wrapper/launch/zedxm.launch @@ -35,6 +35,11 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + + + + @@ -52,6 +57,10 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + + + diff --git a/zed_wrapper/params/common.yaml b/zed_wrapper/params/common.yaml index ad73a711..0f0802ca 100644 --- a/zed_wrapper/params/common.yaml +++ b/zed_wrapper/params/common.yaml @@ -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: '' #video: