Open arrfou99 opened 1 year ago
Hi @arrfou99, maybe you would find these documents useful:
Hi @lola-masson thanks for answering. However, the projection matrix P that is published seems not correct to me especially the coordinates of the principle point cx, cy in the P matrix. I have tried the Python examples and it rectifies images correctly. However, I would like to highlight the following notes about the ROS2 Node that I believe it would be great to have:
Here below I report the camera info for O3R 225 /// camera info msg with IFM3d // --- // header: // stamp: // sec: 1689755272 // nanosec: 405853965 // frame_id: cam_0_optical_link // height: 172 // width: 224 // distortion_model: plumb_bob // d: // - 0.5029289722442627 // - -0.40336400270462036 // - 0.0 // - 0.0 // - 0.0 // k: // - 131.15452575683594 // - 0.0 // - 0.8371342420578003 // - 0.0 // - 131.15452575683594 // - 0.6813130974769592 // - 0.0 // - 0.0 // - 1.0 // r: // - 0.0 // - 0.0 // - 0.0 // - 0.0 // - 0.0 // - 0.0 // - 0.0 // - 0.0 // - 0.0 // p: // - 131.15452575683594 // - 0.0 // - 0.8371342420578003 // - 0.0 // - 0.0 // - 131.15452575683594 // - 0.6813130974769592 // - 0.0 // - 0.0 // - 0.0 // - 1.0 //- 0.0
ROS calibration camera info /// camera info msg with ros calibration // header: // stamp: // sec: 1689755054 // nanosec: 354166267 // frame_id: cam_0_optical_link // height: 172 // width: 224 // distortion_model: plumb_bob // d: // - -0.306668 // - 0.078516 // - -0.000249 // - -0.001051 // - 0.0 // k: // - 129.20583157079326 // - 0.0 // - 108.986811 // - 0.0 // - 129.0723 // - 82.50482 // - 0.0 // - 0.0 // - 1.0 // r: // - 0.0 // - 0.0 // - 0.0 // - 0.0 // - 0.0 // - 0.0 // - 0.0 // - 0.0 // - 0.0 // p: // - 93.5715560913086 // - 0.0 // - 107.01353913861567 // - 0.0 // - 0.0 // - 107.26087188720703 // - 80.3732823687933 // - 0.0 // - 0.0 // - 0.0 // - 1.0 // - 0.0
Hi @arrfou99,
I will answer point 2 for now and once I have a complete answer for the rest I will add it here. Following the documentation about camera_info see the link So the P matrix is represented as:
[fx' 0 cx' tx] [ 0 fy' cy' ty] [ 0 0 1 0]
P: The 3x4 projection matrix. This matrix is a combination of the intrinsic matrix (K) and the 3x4 extrinsic matrix ([R | t]), where t is the translation vector of the camera with respect to the world coordinate system. fx' and fy' are scaling factors related to the focal length and image sensor size. cx' and cy' are the modified optical centers (principal points). tx and ty are the elements of the translation vector t.
In the buffer_conversions.hpp file both cx and cy are scaled to normalized coordinates (divided by fx and fy)which is not needed here
const float cy = (iy + 0.5 - my) / fy;
const float cx = (ix + 0.5 - mx) / fx - alpha * cy;
Got you. We will look into this in more details and publish a fix asap.
Hi, I am using the O3R system and I need to use point clouds 3D and distance images in ROS2. while trying to use camera info to overly the point clouds using RVIZ camera onto the distance images I ran into an incorrect mapping of the point cloud on the distance image.
debugging the camera info I have noticed that the coordinates of the principle point cx, cy are represented in the normalized image coordinates with values [0-1] while they should be in pixels like fx, and fy.