System Environment
- Ubuntu Version: 24.04
- ROS Version:
jazzy
- Camera Model:
Femto Bolt
- Firmware Version: 1.1.2
- Branch:
v2-main
- Commit:
v2.5.5
Description
In the function convertToCameraInfo, the projection matrix P is set with the same intrinsic parameters as the camera matrix K:
|
sensor_msgs::msg::CameraInfo convertToCameraInfo(OBCameraIntrinsic intrinsic, |
|
OBCameraDistortion distortion, int width) { |
|
(void)width; |
|
sensor_msgs::msg::CameraInfo info; |
|
info.distortion_model = getDistortionModels(distortion); |
|
info.width = intrinsic.width; |
|
info.height = intrinsic.height; |
|
info.d.resize(8, 0.0); |
|
info.d[0] = distortion.k1; |
|
info.d[1] = distortion.k2; |
|
info.d[2] = distortion.p1; |
|
info.d[3] = distortion.p2; |
|
info.d[4] = distortion.k3; |
|
info.d[5] = distortion.k4; |
|
info.d[6] = distortion.k5; |
|
info.d[7] = distortion.k6; |
|
bool all_zero = std::all_of(info.d.begin(), info.d.end(), [](double val) { return val == 0.0; }); |
|
info.roi.do_rectify = all_zero; |
|
|
|
info.k.fill(0.0); |
|
info.k[0] = intrinsic.fx; |
|
info.k[2] = intrinsic.cx; |
|
info.k[4] = intrinsic.fy; |
|
info.k[5] = intrinsic.cy; |
|
info.k[8] = 1.0; |
|
|
|
info.r.fill(0.0); |
|
info.r[0] = 1; |
|
info.r[4] = 1; |
|
info.r[8] = 1; |
|
|
|
info.p.fill(0.0); |
|
info.p[0] = info.k[0]; |
|
info.p[2] = info.k[2]; |
|
info.p[5] = info.k[4]; |
|
info.p[6] = info.k[5]; |
|
info.p[10] = 1.0; |
|
return info; |
|
} |
According to the ROS documentation for the sensor_msgs/msg/CameraInfo, the camera (K) and projection (P) matrices are for the raw/distorted/unrectified and undistorted/rectified images, respectively.
Since the distortion coefficients d in the intrinsics are not 0, hence the camera publishes the raw unrectified images, both matrices should be different.
Should the published intrinsics in the K and P matrices be used for the raw images, i.e. K contains the true values, or for the rectified images, i.e. P contains the true values?
Also, can you just fix this issue by setting the K and P matrices correctly?
System Environment
jazzyFemto Boltv2-mainv2.5.5Description
In the function
convertToCameraInfo, the projection matrix P is set with the same intrinsic parameters as the camera matrix K:OrbbecSDK_ROS2/orbbec_camera/src/utils.cpp
Lines 22 to 60 in 7d517ea
According to the ROS documentation for the
sensor_msgs/msg/CameraInfo, the camera (K) and projection (P) matrices are for the raw/distorted/unrectified and undistorted/rectified images, respectively.Since the distortion coefficients
din the intrinsics are not 0, hence the camera publishes the raw unrectified images, both matrices should be different.Should the published intrinsics in the K and P matrices be used for the raw images, i.e. K contains the true values, or for the rectified images, i.e. P contains the true values?
Also, can you just fix this issue by setting the K and P matrices correctly?