Description
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),
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
and
With
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
[5]: https://ksimek.github.io/2013/06/03/calibrated_cameras_in_opengl