ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

How to change the camera model when using image_pipeline?

asked 2019-10-11 06:37:14 -0500

YancenBOB gravatar image

Hi, I do some binocular camera calibration tests with image_pipeline. For some reasons, I can not see the video in the image_pipeline/Tutorials page. I have to ask questions there. 1, How can I cange the camera model? You know that diferent cameras should choose the appropriate one. Further, I want to know all the models that image_pipeline supports. 2, How can I get the baseline after I do the calibration? I just get 3 files: left.yaml, right.yaml and ost.txt. I don't see the extrinsic parameters, which I mean a matrix to show transformation relationship between double cameras. Is there some commend to add it into the outputs? Thank you!

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2019-10-11 15:54:40 -0500

mjcarroll gravatar image

The PinholeCameraModel from image_geometry supports either the 5 parameter "Plumb Bob" model or the 8 parameter "Rational Polynomial" model. This is specified in REP 104, and implemented using cv::initUndistortRectifyMap in the image_geometry package.

The extrinsic calibration should be included in either the left.yaml or right.yaml file via the R and P parameters in the copmuted camera information. From the sensor_msgs/CameraInfo documentation:

# Projection/camera matrix
#     [fx'  0  cx' Tx]
# P = [ 0  fy' cy' Ty]
#     [ 0   0   1   0]
# ...snip...
# For a stereo pair, the fourth column [Tx Ty 0]' is related to the
#  position of the optical center of the second camera in the first
#  camera's frame. We assume Tz = 0 so both cameras are in the same
#  stereo image plane. The first camera always has Tx = Ty = 0. For
#  the right (second) camera of a horizontal stereo pair, Ty = 0 and
#  Tx = -fx' * B, where B is the baseline between the cameras.
edit flag offensive delete link more

Comments

Thank you! I have got the baseline. For the camera model, I have another question that dose image_pipeline only support Pinhole camera model and Plumb Bob distortion model? For other calibration tools I see some like equidistant model and so on. I need to use different tools to double check the result.

YancenBOB gravatar image YancenBOB  ( 2019-10-11 22:07:18 -0500 )edit

Yes, I believe that those are the only two it supports. At the time that this software was written, these were the only models that OpenCV supported. I believe in recent years, OpenCV has added support for a fisheye model as well, but image_geometry has not been updated to accomodate this.

mjcarroll gravatar image mjcarroll  ( 2019-10-14 10:58:58 -0500 )edit

Thanks for your help! Thank you!

YancenBOB gravatar image YancenBOB  ( 2019-10-15 02:52:31 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2019-10-11 06:37:14 -0500

Seen: 1,545 times

Last updated: Oct 11 '19