From 0152f45180e666c09675b207b34a68d62ece12f8 Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Tue, 1 Aug 2023 16:00:04 +0200 Subject: [PATCH 1/4] Add general.pub_resolution_scale param - Add new parameter `general.pub_resolution_scale` to be used with the new option `CUSTOM_RESCALE` for the parameter `general.pub_resolution` - `ULTRA` is the new default value for `depth.depth_mode` --- CHANGELOG.rst | 5 +++++ .../src/zed_camera/include/sl_types.hpp | 3 ++- .../include/zed_camera_component.hpp | 1 + .../zed_camera/src/zed_camera_component.cpp | 22 +++++++++++++++---- zed_wrapper/config/common.yaml | 5 +++-- zed_wrapper/config/zedx.yaml | 4 ++-- zed_wrapper/config/zedxm.yaml | 4 ++-- 7 files changed, 33 insertions(+), 11 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index e5f4a6ff..57cf835e 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -1,6 +1,11 @@ LATEST CHANGES ============== +2023-08-01 +---------- +- Add new parameter `general.pub_resolution_scale` to be used with the new option `CUSTOM_RESCALE` for the parameter `general.pub_resolution` +- `ULTRA` is the new default value for `depth.depth_mode` (better performance for odometry and positional tracking) + 2023-07-31 ---------- - Fix issue with Body Tracking start/stop by service call. Now Body Tracking can be restarted multiple times diff --git a/zed_components/src/zed_camera/include/sl_types.hpp b/zed_components/src/zed_camera/include/sl_types.hpp index b63f0a31..2d9288e7 100644 --- a/zed_components/src/zed_camera/include/sl_types.hpp +++ b/zed_components/src/zed_camera/include/sl_types.hpp @@ -154,7 +154,8 @@ typedef enum MEDIUM, //!< 896x512 SVGA, //!< 960x600 VGA, //!< 672x376 - LOW //!< Half-MEDIUM 448x256 + LOW, //!< Half-MEDIUM 448x256 + CUSTOM_RESCALE //!< Custom Rescale Factor } PubRes; // <---- Typedefs to simplify declarations } // namespace stereolabs diff --git a/zed_components/src/zed_camera/include/zed_camera_component.hpp b/zed_components/src/zed_camera/include/zed_camera_component.hpp index 538ca371..5fec7550 100644 --- a/zed_components/src/zed_camera/include/zed_camera_component.hpp +++ b/zed_components/src/zed_camera/include/zed_camera_component.hpp @@ -269,6 +269,7 @@ class ZedCamera : public rclcpp::Node int mGpuId = -1; sl::RESOLUTION mCamResol = sl::RESOLUTION::HD720; // Default resolution: RESOLUTION_HD720 PubRes mPubResolution = MEDIUM; // Use native DNN resolution for NEURAL depth to improve speed and quality. + double mCustomRescaleFactor = 2.0; // Used to rescale data with user factor sl::DEPTH_MODE mDepthMode = sl::DEPTH_MODE::PERFORMANCE; // Default depth mode: DEPTH_MODE_PERFORMANCE bool mDepthDisabled = false; // Indicates if depth calculation is not required (DEPTH_MODE::NONE se for ) diff --git a/zed_components/src/zed_camera/src/zed_camera_component.cpp b/zed_components/src/zed_camera/src/zed_camera_component.cpp index 691a13c3..2c8085c8 100644 --- a/zed_components/src/zed_camera/src/zed_camera_component.cpp +++ b/zed_components/src/zed_camera/src/zed_camera_component.cpp @@ -630,14 +630,15 @@ void ZedCamera::getGeneralParams() // TODO(walter) ADD SVO SAVE COMPRESSION PARAMETERS - std::string resol = "HD720"; + std::string resol = "AUTO"; getParam("general.grab_resolution", resol, resol); if (resol == "AUTO") { mCamResol = sl::RESOLUTION::AUTO; } else if (sl_tools::isZEDX(mCamUserModel)) { - // TODO(Walter) Add support for HD1080 when available if (resol == "HD1200") { mCamResol = sl::RESOLUTION::HD1200; + } else if (resol == "HD1080") { + mCamResol = sl::RESOLUTION::HD1080; } else if (resol == "SVGA") { mCamResol = sl::RESOLUTION::SVGA; } else { @@ -685,13 +686,21 @@ void ZedCamera::getGeneralParams() mPubResolution = PubRes::MEDIUM; } else if (out_resol == "LOW") { mPubResolution = PubRes::LOW; + } else if (out_resol == "CUSTOM_RESCALE") { + mPubResolution = PubRes::CUSTOM_RESCALE; } else { RCLCPP_INFO(get_logger(), "Not valid 'general.pub_resolution' value. Using default setting."); - out_resol = "MEDIUM"; - mPubResolution = PubRes::MEDIUM; + out_resol = "CUSTOM_RESCALE"; + mPubResolution = PubRes::CUSTOM_RESCALE; } RCLCPP_INFO_STREAM(get_logger(), " * Publishing resolution: " << out_resol.c_str()); + if (mPubResolution == PubRes::CUSTOM_RESCALE) { + getParam( + "general.pub_resolution_scale", mCustomRescaleFactor, mCustomRescaleFactor, + " * Publishing rescale factor: "); + } + std::string parsed_str = getParam("general.region_of_interest", mRoiParam); RCLCPP_INFO_STREAM(get_logger(), " * Region of interest: " << parsed_str.c_str()); @@ -3508,6 +3517,11 @@ bool ZedCamera::startCamera() pub_w = MEDIUM_W / 2; pub_h = MEDIUM_H / 2; break; + + case PubRes::CUSTOM_RESCALE: + pub_w = static_cast(mCamWidth / mCustomRescaleFactor); + pub_h = static_cast(mCamHeight / mCustomRescaleFactor); + break; } if (pub_w > mCamWidth || pub_h > mCamHeight) { diff --git a/zed_wrapper/config/common.yaml b/zed_wrapper/config/common.yaml index 0ef2e693..8c74fc47 100644 --- a/zed_wrapper/config/common.yaml +++ b/zed_wrapper/config/common.yaml @@ -15,7 +15,8 @@ camera_flip: false zed_id: 0 # IMPORTANT: to be used in simulation to distinguish individual cameras im multi-camera configurations - usually overwritten by launch file serial_number: 0 # usually overwritten by launch file - pub_resolution: 'MEDIUM' # The resolution used for output. 'HD2K', 'HD1080', 'HD1200', 'HD720', 'MEDIUM', 'SVGA', 'VGA', 'LOW' + pub_resolution: 'CUSTOM_RESCALE' # The resolution used for output. 'CUSTOM_RESCALE', 'HD2K', 'HD1080', 'HD1200', 'HD720', 'MEDIUM', 'SVGA', 'VGA', 'LOW' + pub_resolution_scale: 2.0 # rescale factor used to rescale image before publishing when 'pub_resolution' is 'CUSTOM_RESCALE' pub_frame_rate: 15.0 # [DYNAMIC] - frequency of publishing of visual images and depth images gpu_id: -1 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. @@ -42,7 +43,7 @@ qos_durability: 2 # '1': TRANSIENT_LOCAL - '2': VOLATILE depth: - depth_mode: 'NEURAL' # Matches the ZED SDK setting: 'NONE', 'PERFORMANCE', 'QUALITY', 'ULTRA', 'NEURAL' - Note: if 'NONE' all the modules that requires depth extraction are disabled by default (Pos. Tracking, Obj. Detection, Mapping, ...) + depth_mode: 'ULTRA' # Matches the ZED SDK setting: 'NONE', 'PERFORMANCE', 'QUALITY', 'ULTRA', 'NEURAL' - Note: if 'NONE' all the modules that requires depth extraction are disabled by default (Pos. Tracking, Obj. Detection, Mapping, ...) depth_stabilization: 1 # Forces positional tracking to start if major than 0 - Range: [0,100] openni_depth_mode: false # 'false': 32bit float [meters], 'true': 16bit unsigned int [millimeters] point_cloud_freq: 10.0 # [DYNAMIC] - frequency of the pointcloud publishing (equal or less to `grab_frame_rate` value) diff --git a/zed_wrapper/config/zedx.yaml b/zed_wrapper/config/zedx.yaml index d44e9040..9b7c2adc 100644 --- a/zed_wrapper/config/zedx.yaml +++ b/zed_wrapper/config/zedx.yaml @@ -6,8 +6,8 @@ general: camera_model: "zedx" camera_name: "zedx" # usually overwritten by launch file - grab_resolution: 'HD1200' # The native camera grab resolution. 'HD1200', 'SVGA', 'AUTO' - grab_frame_rate: 30 # ZED SDK internal grabbing rate (HD1200: 60 or 30 - SVGA: 120 or 60) + grab_resolution: 'HD1200' # The native camera grab resolution. 'HD1200', 'HD1080', 'SVGA', 'AUTO' + grab_frame_rate: 30 # ZED SDK internal grabbing rate (HD1200/hd1080: 60, 30, 15 - SVGA: 120, 60, 30, 15) video: exposure_time: 16000 # Defines the real exposure time in microseconds. Recommended to control manual exposure (instead of `video.exposure` setting) diff --git a/zed_wrapper/config/zedxm.yaml b/zed_wrapper/config/zedxm.yaml index 917bcc29..0fff00a8 100644 --- a/zed_wrapper/config/zedxm.yaml +++ b/zed_wrapper/config/zedxm.yaml @@ -6,8 +6,8 @@ general: camera_model: "zedxm" camera_name: "zedxm" # usually overwritten by launch file - grab_resolution: 'HD1200' # The native camera grab resolution. 'HD1200', 'SVGA', 'AUTO' - grab_frame_rate: 30 # ZED SDK internal grabbing rate (HD1200: 60 or 30 - SVGA: 120 or 60) + grab_resolution: 'HD1200' # The native camera grab resolution. 'HD1200', 'HD1080', 'SVGA', 'AUTO' + grab_frame_rate: 30 # ZED SDK internal grabbing rate (HD1200/hd1080: 60, 30, 15 - SVGA: 120, 60, 30, 15) video: exposure_time: 16666 # Defines the real exposure time in microseconds. Recommended to control manual exposure (instead of `video.exposure` setting) From 697785a47d66573a8513de7473982c8c5299478e Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Tue, 1 Aug 2023 19:00:04 +0200 Subject: [PATCH 2/4] Better rescale W/H approximation --- CHANGELOG.rst | 1 + zed_components/src/zed_camera/src/zed_camera_component.cpp | 4 ++-- zed_wrapper/config/common.yaml | 2 +- 3 files changed, 4 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 57cf835e..81b5f9e7 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -5,6 +5,7 @@ LATEST CHANGES ---------- - Add new parameter `general.pub_resolution_scale` to be used with the new option `CUSTOM_RESCALE` for the parameter `general.pub_resolution` - `ULTRA` is the new default value for `depth.depth_mode` (better performance for odometry and positional tracking) +- Add resolution `HD1080` for ZED X 2023-07-31 ---------- diff --git a/zed_components/src/zed_camera/src/zed_camera_component.cpp b/zed_components/src/zed_camera/src/zed_camera_component.cpp index 2c8085c8..32e49b81 100644 --- a/zed_components/src/zed_camera/src/zed_camera_component.cpp +++ b/zed_components/src/zed_camera/src/zed_camera_component.cpp @@ -3519,8 +3519,8 @@ bool ZedCamera::startCamera() break; case PubRes::CUSTOM_RESCALE: - pub_w = static_cast(mCamWidth / mCustomRescaleFactor); - pub_h = static_cast(mCamHeight / mCustomRescaleFactor); + pub_w = static_cast(std::round(mCamWidth / mCustomRescaleFactor)); + pub_h = static_cast(std::round(mCamHeight / mCustomRescaleFactor)); break; } diff --git a/zed_wrapper/config/common.yaml b/zed_wrapper/config/common.yaml index 8c74fc47..e5a3175b 100644 --- a/zed_wrapper/config/common.yaml +++ b/zed_wrapper/config/common.yaml @@ -16,7 +16,7 @@ zed_id: 0 # IMPORTANT: to be used in simulation to distinguish individual cameras im multi-camera configurations - usually overwritten by launch file serial_number: 0 # usually overwritten by launch file pub_resolution: 'CUSTOM_RESCALE' # The resolution used for output. 'CUSTOM_RESCALE', 'HD2K', 'HD1080', 'HD1200', 'HD720', 'MEDIUM', 'SVGA', 'VGA', 'LOW' - pub_resolution_scale: 2.0 # rescale factor used to rescale image before publishing when 'pub_resolution' is 'CUSTOM_RESCALE' + pub_resolution_scale: 1.8 # rescale factor used to rescale image before publishing when 'pub_resolution' is 'CUSTOM_RESCALE' pub_frame_rate: 15.0 # [DYNAMIC] - frequency of publishing of visual images and depth images gpu_id: -1 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. From edb63b65266bead3848c03d8b6da4fd4c3c18a55 Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Wed, 2 Aug 2023 14:23:36 +0200 Subject: [PATCH 3/4] Remove data publish size presets. * Add `NATIVE` and `CUSTOM` instead of all the fixed resolutions --- CHANGELOG.rst | 5 +- .../src/zed_camera/include/sl_types.hpp | 11 +-- .../include/zed_camera_component.hpp | 11 ++- .../zed_camera/src/zed_camera_component.cpp | 76 ++++--------------- zed_wrapper/config/common.yaml | 4 +- zed_wrapper/config/zedx.yaml | 2 +- zed_wrapper/config/zedxm.yaml | 2 +- 7 files changed, 27 insertions(+), 84 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 81b5f9e7..6a372567 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -1,9 +1,10 @@ LATEST CHANGES ============== -2023-08-01 +2023-08-02 ---------- -- Add new parameter `general.pub_resolution_scale` to be used with the new option `CUSTOM_RESCALE` for the parameter `general.pub_resolution` +- The parameter `general.pub_resolution` can now take only `NATIVE` and `CUSTOM` values. 'NATIVE' to use the same `general.grab_resolution` - `CUSTOM` to apply the `general.pub_downscale_factor` downscale factory to reduce bandwidth in transmission +- Add new parameter `general.pub_downscale_factor` to be used with the new option `CUSTOM` for the parameter `general.pub_resolution` - `ULTRA` is the new default value for `depth.depth_mode` (better performance for odometry and positional tracking) - Add resolution `HD1080` for ZED X diff --git a/zed_components/src/zed_camera/include/sl_types.hpp b/zed_components/src/zed_camera/include/sl_types.hpp index 2d9288e7..5f8d9374 100644 --- a/zed_components/src/zed_camera/include/sl_types.hpp +++ b/zed_components/src/zed_camera/include/sl_types.hpp @@ -147,15 +147,8 @@ typedef rclcpp::Service::SharedPtr fromLLSrvPtr */ typedef enum { - HD2K, //!< 2208x1242 - HD1080, //!< 1920x1080 - HD1200, //!< 1920x1200 - HD720, //!< 1280x720 - MEDIUM, //!< 896x512 - SVGA, //!< 960x600 - VGA, //!< 672x376 - LOW, //!< Half-MEDIUM 448x256 - CUSTOM_RESCALE //!< Custom Rescale Factor + NATIVE, //!< Same camera grab resolution + CUSTOM //!< Custom Rescale Factor } PubRes; // <---- Typedefs to simplify declarations } // namespace stereolabs diff --git a/zed_components/src/zed_camera/include/zed_camera_component.hpp b/zed_components/src/zed_camera/include/zed_camera_component.hpp index 5fec7550..eb3b6b68 100644 --- a/zed_components/src/zed_camera/include/zed_camera_component.hpp +++ b/zed_components/src/zed_camera/include/zed_camera_component.hpp @@ -267,12 +267,11 @@ class ZedCamera : public rclcpp::Node bool mSvoRealtime = false; int mVerbose = 1; int mGpuId = -1; - sl::RESOLUTION mCamResol = sl::RESOLUTION::HD720; // Default resolution: RESOLUTION_HD720 - PubRes mPubResolution = MEDIUM; // Use native DNN resolution for NEURAL depth to improve speed and quality. - double mCustomRescaleFactor = 2.0; // Used to rescale data with user factor - sl::DEPTH_MODE mDepthMode = sl::DEPTH_MODE::PERFORMANCE; // Default depth mode: DEPTH_MODE_PERFORMANCE - bool mDepthDisabled = - false; // Indicates if depth calculation is not required (DEPTH_MODE::NONE se for ) + sl::RESOLUTION mCamResol = sl::RESOLUTION::HD1080; // Default resolution: RESOLUTION_HD1080 + PubRes mPubResolution = PubRes::NATIVE; // Use native grab resolution by default + double mCustomDownscaleFactor = 1.0; // Used to rescale data with user factor + sl::DEPTH_MODE mDepthMode = sl::DEPTH_MODE::ULTRA; // Default depth mode: ULTRA + bool mDepthDisabled = false; // Indicates if depth calculation is not required (DEPTH_MODE::NONE) int mDepthStabilization = 1; std::vector> mRoiParam; int mCamTimeoutSec = 5; diff --git a/zed_components/src/zed_camera/src/zed_camera_component.cpp b/zed_components/src/zed_camera/src/zed_camera_component.cpp index 32e49b81..0e3efed0 100644 --- a/zed_components/src/zed_camera/src/zed_camera_component.cpp +++ b/zed_components/src/zed_camera/src/zed_camera_component.cpp @@ -47,10 +47,6 @@ using namespace std::placeholders; // Used for simulation data input #define ZED_SDK_PORT 30000 -// Custom output resolution -#define MEDIUM_W 896 -#define MEDIUM_H 512 - namespace stereolabs { #ifndef DEG2RAD @@ -670,35 +666,23 @@ void ZedCamera::getGeneralParams() std::string out_resol = "MEDIUM"; getParam("general.pub_resolution", out_resol, out_resol); - if (out_resol == "HD2K") { - mPubResolution = PubRes::HD2K; - } else if (out_resol == "HD1080") { - mPubResolution = PubRes::HD1080; - } else if (out_resol == "HD1200") { - mPubResolution = PubRes::HD1200; - } else if (out_resol == "HD720") { - mPubResolution = PubRes::HD720; - } else if (out_resol == "SVGA") { - mPubResolution = PubRes::SVGA; - } else if (out_resol == "VGA") { - mPubResolution = PubRes::VGA; - } else if (out_resol == "MEDIUM") { - mPubResolution = PubRes::MEDIUM; - } else if (out_resol == "LOW") { - mPubResolution = PubRes::LOW; - } else if (out_resol == "CUSTOM_RESCALE") { - mPubResolution = PubRes::CUSTOM_RESCALE; + if (out_resol == "NATIVE") { + mPubResolution = PubRes::NATIVE; + } else if (out_resol == "CUSTOM") { + mPubResolution = PubRes::CUSTOM; } else { RCLCPP_INFO(get_logger(), "Not valid 'general.pub_resolution' value. Using default setting."); - out_resol = "CUSTOM_RESCALE"; - mPubResolution = PubRes::CUSTOM_RESCALE; + out_resol = "NATIVE"; + mPubResolution = PubRes::NATIVE; } RCLCPP_INFO_STREAM(get_logger(), " * Publishing resolution: " << out_resol.c_str()); - if (mPubResolution == PubRes::CUSTOM_RESCALE) { + if (mPubResolution == PubRes::CUSTOM) { getParam( - "general.pub_resolution_scale", mCustomRescaleFactor, mCustomRescaleFactor, - " * Publishing rescale factor: "); + "general.pub_downscale_factor", mCustomDownscaleFactor, mCustomDownscaleFactor, + " * Publishing downscale factor: "); + } else { + mCustomDownscaleFactor = 1.0; } std::string parsed_str = getParam("general.region_of_interest", mRoiParam); @@ -3487,42 +3471,8 @@ bool ZedCamera::startCamera() get_logger(), " * Camera grab frame size -> " << mCamWidth << "x" << mCamHeight); int pub_w, pub_h; - switch (mPubResolution) { - case PubRes::HD2K: - pub_w = sl::getResolution(sl::RESOLUTION::HD2K).width; - pub_h = sl::getResolution(sl::RESOLUTION::HD2K).height; - break; - - case PubRes::HD1080: - pub_w = sl::getResolution(sl::RESOLUTION::HD1080).width; - pub_h = sl::getResolution(sl::RESOLUTION::HD1080).height; - break; - - case PubRes::HD720: - pub_w = sl::getResolution(sl::RESOLUTION::HD720).width; - pub_h = sl::getResolution(sl::RESOLUTION::HD720).height; - break; - - case PubRes::MEDIUM: - pub_w = MEDIUM_W; - pub_h = MEDIUM_H; - break; - - case PubRes::VGA: - pub_w = sl::getResolution(sl::RESOLUTION::VGA).width; - pub_h = sl::getResolution(sl::RESOLUTION::VGA).height; - break; - - case PubRes::LOW: - pub_w = MEDIUM_W / 2; - pub_h = MEDIUM_H / 2; - break; - - case PubRes::CUSTOM_RESCALE: - pub_w = static_cast(std::round(mCamWidth / mCustomRescaleFactor)); - pub_h = static_cast(std::round(mCamHeight / mCustomRescaleFactor)); - break; - } + pub_w = static_cast(std::round(mCamWidth / mCustomDownscaleFactor)); + pub_h = static_cast(std::round(mCamHeight / mCustomDownscaleFactor)); if (pub_w > mCamWidth || pub_h > mCamHeight) { RCLCPP_WARN_STREAM( diff --git a/zed_wrapper/config/common.yaml b/zed_wrapper/config/common.yaml index e5a3175b..ba9275ee 100644 --- a/zed_wrapper/config/common.yaml +++ b/zed_wrapper/config/common.yaml @@ -15,8 +15,8 @@ camera_flip: false zed_id: 0 # IMPORTANT: to be used in simulation to distinguish individual cameras im multi-camera configurations - usually overwritten by launch file serial_number: 0 # usually overwritten by launch file - pub_resolution: 'CUSTOM_RESCALE' # The resolution used for output. 'CUSTOM_RESCALE', 'HD2K', 'HD1080', 'HD1200', 'HD720', 'MEDIUM', 'SVGA', 'VGA', 'LOW' - pub_resolution_scale: 1.8 # rescale factor used to rescale image before publishing when 'pub_resolution' is 'CUSTOM_RESCALE' + pub_resolution: 'CUSTOM' # The resolution used for output. 'NATIVE' to use the same `general.grab_resolution` - `CUSTOM` to apply the `general.pub_downscale_factor` downscale factory to reduce bandwidth in transmission + pub_downscale_factor: 2.0 # rescale factor used to rescale image before publishing when 'pub_resolution' is 'CUSTOM' pub_frame_rate: 15.0 # [DYNAMIC] - frequency of publishing of visual images and depth images gpu_id: -1 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. diff --git a/zed_wrapper/config/zedx.yaml b/zed_wrapper/config/zedx.yaml index 9b7c2adc..4af4b45e 100644 --- a/zed_wrapper/config/zedx.yaml +++ b/zed_wrapper/config/zedx.yaml @@ -7,7 +7,7 @@ camera_model: "zedx" camera_name: "zedx" # usually overwritten by launch file grab_resolution: 'HD1200' # The native camera grab resolution. 'HD1200', 'HD1080', 'SVGA', 'AUTO' - grab_frame_rate: 30 # ZED SDK internal grabbing rate (HD1200/hd1080: 60, 30, 15 - SVGA: 120, 60, 30, 15) + grab_frame_rate: 30 # ZED SDK internal grabbing rate (HD1200/HD1080: 60, 30, 15 - SVGA: 120, 60, 30, 15) video: exposure_time: 16000 # Defines the real exposure time in microseconds. Recommended to control manual exposure (instead of `video.exposure` setting) diff --git a/zed_wrapper/config/zedxm.yaml b/zed_wrapper/config/zedxm.yaml index 0fff00a8..9a41fe57 100644 --- a/zed_wrapper/config/zedxm.yaml +++ b/zed_wrapper/config/zedxm.yaml @@ -7,7 +7,7 @@ camera_model: "zedxm" camera_name: "zedxm" # usually overwritten by launch file grab_resolution: 'HD1200' # The native camera grab resolution. 'HD1200', 'HD1080', 'SVGA', 'AUTO' - grab_frame_rate: 30 # ZED SDK internal grabbing rate (HD1200/hd1080: 60, 30, 15 - SVGA: 120, 60, 30, 15) + grab_frame_rate: 30 # ZED SDK internal grabbing rate (HD1200/HD1080: 60, 30, 15 - SVGA: 120, 60, 30, 15) video: exposure_time: 16666 # Defines the real exposure time in microseconds. Recommended to control manual exposure (instead of `video.exposure` setting) From 91dacb196b57fb53319874c1497af8a77dacd455 Mon Sep 17 00:00:00 2001 From: Walter Lucetti Date: Wed, 2 Aug 2023 14:28:44 +0200 Subject: [PATCH 4/4] Minor logging fix --- zed_components/src/zed_camera/src/zed_camera_component.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/zed_components/src/zed_camera/src/zed_camera_component.cpp b/zed_components/src/zed_camera/src/zed_camera_component.cpp index 0e3efed0..429e5d81 100644 --- a/zed_components/src/zed_camera/src/zed_camera_component.cpp +++ b/zed_components/src/zed_camera/src/zed_camera_component.cpp @@ -671,7 +671,9 @@ void ZedCamera::getGeneralParams() } else if (out_resol == "CUSTOM") { mPubResolution = PubRes::CUSTOM; } else { - RCLCPP_INFO(get_logger(), "Not valid 'general.pub_resolution' value. Using default setting."); + RCLCPP_WARN( + get_logger(), "Not valid 'general.pub_resolution' value: '%s'. Using default setting instead.", + out_resol.c_str()); out_resol = "NATIVE"; mPubResolution = PubRes::NATIVE; }