Skip to content

Conversation

@jangernert
Copy link
Contributor

#6609
set the distortion model of the l500 depth sensor to NONE & initialize coeffs

@dorodnic
Copy link
Contributor

Hi @jangernert
Thank you for the pull-request, we will make sure to include it in the upcoming release

@dorodnic dorodnic added the l500 label Jun 18, 2020
@dorodnic dorodnic changed the base branch from master to development June 18, 2020 15:21
intrinsics.fy = intrinsic_params.pinhole_cam_model.ipm.focal_length.y;
intrinsics.ppx = intrinsic_params.pinhole_cam_model.ipm.principal_point.x;
intrinsics.ppy = intrinsic_params.pinhole_cam_model.ipm.principal_point.y;
intrinsics.coeffs[0] = 0;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@jangernert hi ,
it might not necessary apply here, but in general case the coefficients should be copied from the source rather than assigned.
You can either change it (preferred) or add explanation in code why it can be avoided in the particular case.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I honestly didn't check if the distortion struct had any valid values since the image is not distorted.

intrinsics.coeffs[2] = intrinsic_params.pinhole_cam_model.distort.radial_k3;
intrinsics.coeffs[3] = intrinsic_params.pinhole_cam_model.distort.tangential_p1;
intrinsics.coeffs[4] = intrinsic_params.pinhole_cam_model.distort.tangential_p2;
intrinsics.model = RS2_DISTORTION_NONE;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for the quick response, the parameters should be reordered and to be aligned with the struct's layout,
similar to https://github.com/IntelRealSense/librealsense/blob/ac/src/l500/l500-color.cpp#L202-L206:

                if( model.distort.radial_k1 || model.distort.radial_k2 || model.distort.tangential_p1 || model.distort.tangential_p2 || model.distort.radial_k3 )
                {
                    intrinsics.coeffs[0] = model.distort.radial_k1;
                    intrinsics.coeffs[1] = model.distort.radial_k2;
                    intrinsics.coeffs[2] = model.distort.tangential_p1;
                    intrinsics.coeffs[3] = model.distort.tangential_p2;
                    intrinsics.coeffs[4] = model.distort.radial_k3;

                    intrinsics.model = RS2_DISTORTION_INVERSE_BROWN_CONRADY;
                }

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Oh that is a bit confusing. Any reason why the coeffs are handed out in an array rather than the distortion struct directly? Would make things a lot clearer.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The parameters are unique per distortion model in use, so apparently the names cannot be hard-coded/reused.
As for the Brown-Conrady distortion and its coefficients - this convention used throughout the SDK for all sensor's that are modeled after it

@ev-mp
Copy link
Contributor

ev-mp commented Jun 30, 2020

@jangernert , thanks again for the contribution!

@ev-mp ev-mp changed the base branch from development to ac June 30, 2020 17:07
@ev-mp ev-mp merged commit 18ad157 into realsenseai:ac Jun 30, 2020
@jangernert jangernert deleted the fix-6609 branch July 1, 2020 08:04
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants