Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
5 changes: 5 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,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");
Expand Down Expand Up @@ -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);
Expand Down
16 changes: 16 additions & 0 deletions zed_wrapper/launch/include/zed_camera.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,14 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
<arg name="cam_pitch" default="0.0" />
<arg name="cam_yaw" default="0.0" />

<!-- Calibration -->
<arg name="self_calib" default="true" />
<arg name="optional_opencv_calibration_file" default="" /><!-- <arg name="optional_opencv_calibration_file" default="path/to/opencv/file.yaml"> -->

<!-- Depth -->
<arg name="min_depth" default="0.3" />
<arg name="max_depth" default="15.0" />

<!-- ROS URDF description of the ZED -->
<group if="$(arg publish_urdf)">
<param name="$(arg camera_name)_description"
Expand Down Expand Up @@ -87,5 +95,13 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

<!-- GPU ID -->
<param name="general/gpu_id" value="$(arg gpu_id)" />

<!-- Calibration -->
<param name="general/self_calib" value="$(arg self_calib)" />
<param name="general/optional_opencv_calibration_file" value="$(arg optional_opencv_calibration_file)" />

<!-- Depth -->
<param name="depth/min_depth" value="$(arg min_depth)" />
<param name="depth/max_depth" value="$(arg max_depth)" />
</node>
</launch>
9 changes: 9 additions & 0 deletions zed_wrapper/launch/zedxm.launch
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,11 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
<arg name="cam_roll" default="0.0" /> <!-- Orientation respect to base frame (i.e. "base_link) -->
<arg name="cam_pitch" default="0.0" /> <!-- Orientation respect to base frame (i.e. "base_link) -->
<arg name="cam_yaw" default="0.0" /> <!-- Orientation respect to base frame (i.e. "base_link) -->

<arg name="self_calib" default="true" />
<arg name="optional_opencv_calibration_file" default="" /> <!-- <arg name="optional_opencv_calibration_file" default="path/to/opencv/file.yaml"> -->
<arg name="min_depth" default="0.1" />
<arg name="max_depth" default="15.0" />

<group ns="$(arg camera_name)">
<include file="$(find zed_wrapper)/launch/include/zed_camera.launch.xml">
Expand All @@ -52,6 +57,10 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
<arg name="cam_roll" value="$(arg cam_roll)" />
<arg name="cam_pitch" value="$(arg cam_pitch)" />
<arg name="cam_yaw" value="$(arg cam_yaw)" />
<arg name="self_calib" value="$(arg self_calib)" />
<arg name="optional_opencv_calibration_file" value="$(arg optional_opencv_calibration_file)" />
<arg name="min_depth" value="$(arg min_depth)" />
<arg name="max_depth" value="$(arg max_depth)" />
</include>
</group>
</launch>
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: ''

#video:

Expand Down