Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add Fisheye calibration tool #440

Conversation

DavidTorresOcana
Copy link
Contributor

@DavidTorresOcana DavidTorresOcana commented Jul 31, 2019

This PR introduces changes to be able to calibrate fisheye cameras and aim to Fix #146

This PR is related with ros/common_msgs#151 , ros-perception/vision_opencv#306 and ros-perception/image_common#146

Main changes it introduces are:

  • Upgrade current calibration tool to:
    • Allow user select between pinhole and fisheye model
    • Calibrate Monocular and Stereo with fisheye model

@DavidTorresOcana
Copy link
Contributor Author

Hello
With respect this calibration tool, I though to put it together but I do not know how to modify the application GUI. I hope somebody can help on this.
With respect calibration, when you try: Depending on the camera, results would vary. The general recommendation with fisheye is to collect points on the corners of the image.

@DavidTorresOcana DavidTorresOcana deleted the Branch_8d01c930e66bdeb58c4b138539a64ddea0b17e10 branch October 27, 2019 19:42
@DavidTorresOcana DavidTorresOcana restored the Branch_8d01c930e66bdeb58c4b138539a64ddea0b17e10 branch October 27, 2019 19:59
@DavidTorresOcana DavidTorresOcana changed the base branch from indigo to melodic October 27, 2019 20:01
@DavidTorresOcana DavidTorresOcana force-pushed the Branch_8d01c930e66bdeb58c4b138539a64ddea0b17e10 branch from 4894735 to 54c271e Compare October 27, 2019 20:33
@DavidTorresOcana
Copy link
Contributor Author

Looks promising! I think I'll try it out on real data in a few days.
One high-level comment: could the new functionality be merged into the existing respective packages instead of creating new ones? Even better if it's possible to merge it into the existing nodes instead of adding new ones as well.

I mange to find some time to look into this: Modifications done.

Copy link
Member

@SteveMacenski SteveMacenski left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Just come cleanup. I also noticed you changed the permissions on a bunch of files, why is that necessary?

camera_calibration/src/camera_calibration/calibrator.py Outdated Show resolved Hide resolved
camera_calibration/src/camera_calibration/calibrator.py Outdated Show resolved Hide resolved
camera_calibration/src/camera_calibration/calibrator.py Outdated Show resolved Hide resolved
camera_calibration/src/camera_calibration/calibrator.py Outdated Show resolved Hide resolved
camera_calibration/src/camera_calibration/calibrator.py Outdated Show resolved Hide resolved
camera_calibration/src/camera_calibration/calibrator.py Outdated Show resolved Hide resolved
camera_calibration/src/camera_calibration/calibrator.py Outdated Show resolved Hide resolved
camera_calibration/src/camera_calibration/calibrator.py Outdated Show resolved Hide resolved
camera_calibration/src/camera_calibration/calibrator.py Outdated Show resolved Hide resolved
For some reason estimateNewCameraMatrixForUndistortRectify is not producing the expected result, hence a workaround was implemented
Copy link
Member

@SteveMacenski SteveMacenski left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Last issue. Please also articulate how you tested this since there is no test coverage

camera_calibration/src/camera_calibration/calibrator.py Outdated Show resolved Hide resolved
@DavidTorresOcana
Copy link
Contributor Author

DavidTorresOcana commented Oct 29, 2019

Last issue. Please also articulate how you tested this since there is no test coverage

True: all these features are being tested by live calibration with a real camera.
I would encourage you or anybody else to very it too by calibrating a camera.

@DavidTorresOcana
Copy link
Contributor Author

Commit bc4f2e3 introduces fisheye calibration flags as input arguments.
The proposed input arguments are:

Options:
  -h, --help            show this help message and exit
  -c CAMERA_NAME, --camera_name=CAMERA_NAME
                        name of the camera to appear in the calibration file

  Chessboard Options:
    You must specify one or more chessboards as pairs of --size and
    --square options.

    -p PATTERN, --pattern=PATTERN
                        calibration pattern to detect - 'chessboard',
                        'circles', 'acircles'
    -s SIZE, --size=SIZE
                        chessboard size as NxM, counting interior corners
                        (e.g. a standard chessboard is 7x7)
    -q SQUARE, --square=SQUARE
                        chessboard square size in meters

  ROS Communication Options:
    --approximate=APPROXIMATE
                        allow specified slop (in seconds) when pairing images
                        from unsynchronized stereo cameras
    --no-service-check  disable check for set_camera_info services at startup
    --queue-size=QUEUE_SIZE
                        image queue size (default 1, set to 0 for unlimited)

  Calibration Optimizer Options:
    --pinhole-fix-principal-point
                        for pinhole, fix the principal point at the image
                        center
    --pinhole-fix-aspect-ratio
                        for pinhole, enforce focal lengths (fx, fy) are equal
    --pinhole-zero-tangent-dist
                        for pinhole, set tangential distortion coefficients
                        (p1, p2) to zero
    --pinhole-k-coefficients=NUM_COEFFS
                        for pinhole, number of radial distortion coefficients
                        to use (up to 6, default 2)
    --fisheye-recompute-extrinsicsts
                        for fisheye, extrinsic will be recomputed after each
                        iteration of intrinsic optimization
    --fisheye-fix-skew  for fisheye, skew coefficient (alpha) is set to zero
                        and stay zero
    --fisheye-fix-principal-point
                        for fisheye,fix the principal point at the image
                        center
    --fisheye-k-coefficients=NUM_COEFFS
                        for fisheye, number of radial distortion coefficients
                        to use fixing to zero the rest (up to 4, default 4)
    --fisheye-check-conditions
                        for fisheye, the functions will check validity of
                        condition number
    --disable_calib_cb_fast_check
                        uses the CALIB_CB_FAST_CHECK flag for
                        findChessboardCorners
    --max-chessboard-speed=MAX_CHESSBOARD_SPEED
                        Do not use samples where the calibration pattern is
                        moving faster                      than this speed in
                        px/frame. Set to eg. 0.5 for rolling shutter cameras. 

Copy link
Member

@SteveMacenski SteveMacenski left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK if tested on hardware I'm OK with that.

You broke backwards compatibility with the flag updates, we need another solution to that. I think just no qualifiers is fine since that's what OpenCV does anyhow and fisheye is specified

camera_calibration/nodes/cameracalibrator.py Outdated Show resolved Hide resolved
Rolling back changes to previous commit on camera calibrator flags to enable backwards compatibility
Copy link
Member

@SteveMacenski SteveMacenski left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@JWhitleyAStuff take a look

Copy link
Collaborator

@JWhitleyWork JWhitleyWork left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

See comments.

camera_calibration/src/camera_calibration/calibrator.py Outdated Show resolved Hide resolved
camera_calibration/src/camera_calibration/calibrator.py Outdated Show resolved Hide resolved
@JWhitleyWork JWhitleyWork merged commit 1cdc128 into ros-perception:melodic Nov 7, 2019
wep21 pushed a commit to wep21/image_pipeline that referenced this pull request Oct 17, 2021
* Add Fisheye calibration tool

* Add calibration for fisheye cameras
Fix ros-perception#146

* Correct typo

* Restore camera_calib files permisions

* Upgrades to calibrator tool for multi model calibration

* Solve fisheye balance selection TODO:
For some reason estimateNewCameraMatrixForUndistortRectify is not producing the expected result, hence a workaround was implemented

* Add fisheye calibration flags as user arguments

* Add undistortion of points for fisheye

* cam_calib: rolling back flags
Rolling back changes to previous commit on camera calibrator flags to enable backwards compatibility

* cam_calib: Style formating
JWhitleyWork pushed a commit that referenced this pull request Nov 11, 2021
* Add Fisheye calibration tool

* Add calibration for fisheye cameras
Fix #146

* Correct typo

* Restore camera_calib files permisions

* Upgrades to calibrator tool for multi model calibration

* Solve fisheye balance selection TODO:
For some reason estimateNewCameraMatrixForUndistortRectify is not producing the expected result, hence a workaround was implemented

* Add fisheye calibration flags as user arguments

* Add undistortion of points for fisheye

* cam_calib: rolling back flags
Rolling back changes to previous commit on camera calibrator flags to enable backwards compatibility

* cam_calib: Style formating
JWhitleyWork pushed a commit that referenced this pull request Apr 14, 2022
* Add Fisheye calibration tool

* Add calibration for fisheye cameras
Fix #146

* Correct typo

* Restore camera_calib files permisions

* Upgrades to calibrator tool for multi model calibration

* Solve fisheye balance selection TODO:
For some reason estimateNewCameraMatrixForUndistortRectify is not producing the expected result, hence a workaround was implemented

* Add fisheye calibration flags as user arguments

* Add undistortion of points for fisheye

* cam_calib: rolling back flags
Rolling back changes to previous commit on camera calibrator flags to enable backwards compatibility

* cam_calib: Style formating
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

support fisheye calibration using opencv 3.0
4 participants