Skip to content

Commit

Permalink
Add missing self_calib to common.yaml
Browse files Browse the repository at this point in the history
  • Loading branch information
Myzhar committed Oct 22, 2024
1 parent 772c28d commit 159c610
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 1 deletion.
2 changes: 1 addition & 1 deletion zed_components/src/zed_camera/src/zed_camera_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3928,7 +3928,7 @@ bool ZedCamera::startCamera()
mInitParams.sdk_verbose = mVerbose;
mInitParams.sdk_gpu_id = mGpuId;
mInitParams.depth_stabilization = mDepthStabilization;
mInitParams.camera_image_flip = mCameraFlip;
mInitParams.camera_image_flip = (mCameraFlip?sl::FLIP_MODE::ON:sl::FLIP_MODE::OFF);
mInitParams.depth_minimum_distance = mCamMinDepth;
mInitParams.depth_maximum_distance = mCamMaxDepth;

Expand Down
1 change: 1 addition & 0 deletions zed_wrapper/config/common.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
camera_timeout_sec: 5
camera_max_reconnect: 5
camera_flip: false
self_calib: true # Enable the self-calibration process at camera opening. See https://www.stereolabs.com/docs/api/structsl_1_1InitParameters.html#affeaa06cfc1d849e311e484ceb8edcc5
serial_number: 0 # usually overwritten by launch file
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'
Expand Down

0 comments on commit 159c610

Please sign in to comment.