The camera_calibration package contains a user-friendly calibration tool, cameracalibrator. This tool uses the following Python classes, which conveniently hide some of the complexities of using OpenCV’s calibration process and chessboard detection, and the details of constructing a ROS CameraInfo message. These classes are documented here for people who need to extend or make a new calibration tool.
For details on the camera model and camera calibration process, see http://docs.opencv.org/master/d9/d0c/group__calib3d.html
Calibration class for monocular cameras:
images = [cv2.imread("mono%d.png") for i in range(8)]
mc = MonoCalibrator()
mc.cal(images)
print mc.as_message()
Return the camera calibration as a CameraInfo message
Calibrate camera from given images
Parameters: | good ([(corners, ChessboardInfo)]) – Good corner positions and boards |
---|
Parameters: | images (list of cvMat) – source images containing chessboards |
---|
Find chessboards in all images.
Return [ (corners, ChessboardInfo) ]
Write images and calibration solution to a tarfile object
Initialize the camera calibration from a CameraInfo message
Detects the calibration target and, if found and provides enough new information, adds it to the sample database.
Returns a MonoDrawable message with the display image and progress info.
Returns the linear error for a set of corners detected in the unrectified image.
Detect the checkerboard and compute the linear error. Mainly for use in tests.
Parameters: | src (cvMat) – source image |
---|
Apply the post-calibration undistortion to the source image
Set the alpha value for the calibrated camera solution. The alpha value is a zoom, and ranges from 0 (zoomed in, all pixels in calibrated image are valid) to 1 (zoomed out, all pixels in original image are in calibrated image).
Parameters: | src (cvMat) – N source pixel points (u,v) as an Nx2 matrix |
---|
Apply the post-calibration undistortion to the source points
Calibration class for stereo cameras:
limages = [cv2.imread("left%d.png") for i in range(8)]
rimages = [cv2.imread("right%d.png") for i in range(8)]
sc = StereoCalibrator()
sc.cal(limages, rimages)
print sc.as_message()
Return the camera calibration as a pair of CameraInfo messages, for left and right cameras respectively.
Parameters: |
|
---|
Find chessboards in images, and runs the OpenCV calibration solver.
Compute the square edge length from two sets of matching undistorted points given the current calibration. :param msg: a tuple of (left_msg, right_msg)
For a sequence of left and right images, find pairs of images where both left and right have a chessboard, and return their corners as a list of pairs.
Write images and calibration solution to a tarfile object
Compute the epipolar error from two sets of matching undistorted points
Detect the checkerboard in both images and compute the epipolar error. Mainly for use in tests.
Initialize the camera calibration from a pair of CameraInfo messages.
Set the alpha value for the calibrated camera solution. The alpha value is a zoom, and ranges from 0 (zoomed in, all pixels in calibrated image are valid) to 1 (zoomed out, all pixels in original image are in calibrated image).