[ros-users] camera_info message and stereo_image_proc

Kurt Konolige konolige at willowgarage.com
Wed Apr 14 23:43:30 UTC 2010


All -

To (hopefully) clear up the confusion, I put up a new wiki page
explaining the CameraInfo parameters
(http://www.ros.org/wiki/image_pipeline/CameraInfo) .  It points out
that there can exist two different internal camera matrices K for the
same camera, depending on the rectification step, which can produce a
"virtual camera" with a different K.

Cheers --Kurt

On Tue, Apr 13, 2010 at 9:57 AM, Rosen Diankov <rosen.diankov at gmail.com> wrote:
> hi kurt,
>
> When D and K are optimized for in camera calibration, K is always
> performed after undistortion, therefore K always points to the
> undistorted image.
>
> The  "internal camera matrix describing the focal length and center of
> the original (distorted) image" should always be equivalent to the
> intrinsic matrix of the "undistorted, rectified image". P is usually
> used to change coordinate systems of the image to make other math
> simpler, one example being rectification.
>
> Regardless, given P, we can usually separate it into K*T where T is an
> affine matrix. And this K should always be equivalent to the intrinsic
> image of the camera unless the image is cropped or scaled (ie the ROI
> you describe in the wiki). Does any other transformation happen inside
> the stereo frame that explains why one CameraInfo message holds two
> sets of parameters?
>
> thank you,
> rosen,
>
> 2010/4/14 Kurt Konolige <konolige at willowgarage.com>:
>> Rosen, Dejan -
>>
>> Please see the sensor_msgs/CameraInfo.msg header file
>> (http://www.ros.org/doc/api/sensor_msgs/html/msg/CameraInfo.html), and
>> the description of the calibration process in OpenCV.  It would help
>> also, I think, if there were explicit information in the wiki
>> tutorials on the meaning of the CameraInfo parameters - we'll put this
>> in.  But the main idea is in the comments in the CameraInfo header
>> file.
>>
>> There are two sets of parameters.  One deals with the original,
>> distorted image.  These are D,K,R.  D, the distortion parameters,
>> describe the lens distortion.  K is the internal camera matrix, and
>> describes the focal length and center of the original (distorted)
>> image.  R is a rectification matrix for warping the image into a
>> "normal form" for stereo, if desired; if no rectification is done
>> (e.g., for monocular cameras), it is the identity matrix.
>>
>> The other parameter is the projection matrix P.  This matrix refers to
>> the undistorted, rectified image.  It gives the transform from XYZ
>> world points in the camera frame, to image points.  Note that it is
>> really the multiplication of the projection matrix for normalized
>> (focal length = 1) images, and the internal parameters of the
>> undistorted, rectified image:  P (CameraInfo) = K'P', where P' is the
>> standard projection matrix dealing with normalized images, and K' is
>> the undistorted, rectified image internal parameter matrix.
>>
>> Hope this helps...
>>
>> Kurt
>>
>>
>>
>> On Tue, Apr 13, 2010 at 9:27 AM, Rosen Diankov <rosen.diankov at gmail.com> wrote:
>>> Hi Blaise, Dejan,
>>>
>>> thank you for the responses.
>>>
>>> We have several ros nodes that compute the 6D pose of objects from
>>> images. This data can come from stereo cameras, or can compute from
>>> single cameras. Either way, the CameraInfo message explains how the
>>> image was generated and it provides an intrinsic matrix, so we try to
>>> be consistent and do all processing depending on what the CameraInfo
>>> dictates.
>>>
>>> I don't understand how nodes can just use rectified images without
>>> knowing the intrinsic parameters... is there a tf frame that does the
>>> intrinsic parameter computation?
>>>
>>> rosen,
>>>
>>> 2010/4/14 Blaise Gassend <blaise at willowgarage.com>:
>>>> Hi Rosen,
>>>>
>>>> I believe that the intent is that only image_proc and stereo_image_proc
>>>> are supposed to look at CameraInfo.D. All other nodes should be running
>>>> on rectified images and should disregard the distortion parameters.
>>>>
>>>> Do you have a use case of a node that needs to be able to run both on
>>>> rectified and unrectified images and, that needs to use the distortion
>>>> parameters?
>>>>
>>>> Blaise
>>>>
>>>> On Tue, 2010-04-13 at 17:42 +0900, Rosen Diankov wrote:
>>>>> hi guys,
>>>>>
>>>>> currently i'm using the videre_stereo_cam package by Antons to get
>>>>> stereo data. This publishes the image_raw and camera_info messages as
>>>>> expected, which is then fed into stereo_image_proc.
>>>>>
>>>>> stereo_image_proc itself publishes image_rect, image_color,
>>>>> image_mono, which I'm guessing undistort the raw images. However, a
>>>>> new camera_info isn't published that has CameraInfo.D set to all
>>>>> zeros. This confuses other nodes taking in the processed images and
>>>>> the camera_info, so is it possible to publish a new camera_info
>>>>> message to use for the output images?
>>>>>
>>>>> rosen,
>>>>> _______________________________________________
>>>>> ros-users mailing list
>>>>> ros-users at code.ros.org
>>>>> https://code.ros.org/mailman/listinfo/ros-users
>>>>
>>>>
>>>> _______________________________________________
>>>> ros-users mailing list
>>>> ros-users at code.ros.org
>>>> https://code.ros.org/mailman/listinfo/ros-users
>>>>
>>> _______________________________________________
>>> ros-users mailing list
>>> ros-users at code.ros.org
>>> https://code.ros.org/mailman/listinfo/ros-users
>>>
>> _______________________________________________
>> ros-users mailing list
>> ros-users at code.ros.org
>> https://code.ros.org/mailman/listinfo/ros-users
>>
> _______________________________________________
> ros-users mailing list
> ros-users at code.ros.org
> https://code.ros.org/mailman/listinfo/ros-users
>



More information about the ros-users mailing list