ros-pybullet / ros_pybullet_interface

ROS-PyBullet Interface.
https://ros-pybullet.github.io/ros_pybullet_interface/
BSD 3-Clause "New" or "Revised" License
77 stars 14 forks source link

Error in camera's K matrix #14

Open smnhdw opened 6 months ago

smnhdw commented 6 months ago

Hi,

I'm not using your code as interface between PyBullet and ROS but just stumbled over your work as you provide a nice definition of the camera's intrinsic matrix K.

While working with 2D projections I figured out that there seems to be an error in the matrix definition. While the y-coordinates of the projected points are correct, the x-coordinates aren't. This problem is especially visible if you change the aspect ratio, e.g., by increasing only the image width. \ After some debugging and reading (e.g., [1]) I figured out the problem seems to be the usage of two different focal lengths. [2]

While PyBullet only supports the vertical field of view (FOV), $f_x$ and $f_y$ have to be the same in my opinion.

To calculate the projection matrix from the FOV and aspect ratio, PyBullet uses Normalized Device Coordinates (NDC) (see [1]). The variable yscale [3] is calculated based on the vertical FOV. As xscale is calculated based on yscale the vertical FOV is also used here. In general PyBullet's b3ComputeProjectionMatrixFOV [3] is doing the same as gluPerspective [4].

My hypothesis that $f_x$ is equal to $f_y$ can also be derived from there. Based on [4] $\frac{f}{\textrm{aspect}} = \frac{2}{\textrm{width}} \cdot \alpha$ and $f = \frac{2}{\textrm{height}} \cdot \beta.$ With $\alpha=f_x$, $\beta=f_y$ 5 and $f=\frac{1}{tan(0.5\cdot\textrm{FOV})}$ we get: $f_x = f_y = \frac{\textrm{height}}{2} \cdot \frac{1}{tan(0.5\cdot\textrm{FOV})}$

After defining K as followed, my issues were solved.

self.f = (0.5 * self.h) / np.tan(np.deg2rad(fov)/2)
self.K = np.array([[self.f, 0, self.w/2],
                   [0, self.f, self.h/2],
                   [0, 0, 1]])

Due to the above definition of K and the calculation of the projection matrix it gets clear, that only a change of the image height result in a change of the projected objects, while different aspect ratios, i.e. due to changed image widths, are realized by clipping or extending the image view.

I hope this information help others while working with PyBullet and camera calibration matrix!

[1]: https://stackoverflow.com/questions/60430958/understanding-the-view-and-projection-matrix-from-pybullet \ [2]: https://github.com/ros-pybullet/ros_pybullet_interface/blob/main/ros_pybullet_interface/src/rpbi/pybullet_rgbd_sensor.py#L47 \ [3]: https://github.com/bulletphysics/bullet3/blob/master/examples/SharedMemory/PhysicsClientC_API.cpp#L4772 \ [4]: https://ksimek.github.io/2013/06/18/calibrated-cameras-and-gluperspective \