AprilRobotics / apriltag_ros

A ROS wrapper of the AprilTag 3 visual fiducial detector
Other
362 stars 338 forks source link

fix bug in single_image_client #103

Closed lianghongzhuo closed 3 years ago

lianghongzhuo commented 3 years ago

This fixes the bug in the single image client. The camera_info was using K matrix to convert the camera_info msg. However, it uses P matrix in the upstream code, see: https://github.com/ros-perception/vision_opencv/blob/noetic/image_geometry/src/pinhole_camera_model.cpp#L322-L327 By convert the K matrix to the P matrix, the apritag_ros can finally detect the tag pose. Otherwise, it will return a [0, 0, 0] pose instead.

wxmerkt commented 3 years ago

Thank you very much for the fix. While the fix is technically correct - image_geometry also returns from P for obtaining fx() etc. (cf. image_geometry/pinhole_camera_model.h#L311-L316) - the source of the issue is that both K and P should be filled in in the client. Particularly, the K[0]!=0.0 is used as a signal whether calibration parameters exist. Could you please also amend the client to fill in both K and P?

lianghongzhuo commented 3 years ago

Sure, I added the K matrix back. But curious to know where is the use of the K matrix though?

wxmerkt commented 3 years ago

Thank you! On a quick scan of image_geometry, we aren't using it. Based on the definition of the CameraInfo message, the presence/value of K[0] can be used to distinguish whether the camera is calibrated or not (https://github.com/ros/common_msgs/blob/20a833b56f9d7fd39655b8491a2ec1226d2639b3/sensor_msgs/msg/CameraInfo.msg#L22-L23)