Skip to content

Commit

Permalink
Merge branch 'melodic' into image_proc_fisheye
Browse files Browse the repository at this point in the history
  • Loading branch information
DavidTorresOcana committed Aug 2, 2020
2 parents 0acfe95 + 71900fa commit fd76f52
Show file tree
Hide file tree
Showing 36 changed files with 860 additions and 490 deletions.
66 changes: 0 additions & 66 deletions .circleci/config.yml

This file was deleted.

38 changes: 38 additions & 0 deletions .github/workflows/basic-build-ci.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
name: Basic Build Workflow

on:
- pull_request
- push

jobs:
build-melodic:
runs-on: ubuntu-latest
strategy:
fail-fast: false
container:
image: ros:melodic-perception
steps:
- name: Checkout repo
uses: actions/checkout@v2
- name: Create Workspace
run: |
mkdir src_tmp
mv `find -maxdepth 1 -not -name . -not -name src_tmp` src_tmp/
mv src_tmp/ src/
cd src
bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \
catkin_init_workspace'
- name: Install Prerequisites
run: |
bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \
apt-get update && rosdep update; \
rosdep install --from-paths src --ignore-src -y'
- name: Build Workspace
run: |
bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \
catkin_make'
- name: Run Tests
run: |
bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \
catkin_make run_tests; \
catkin_test_results --verbose'
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
image_pipeline
==============

[![CircleCI](https://circleci.com/gh/ros-perception/image_pipeline.svg?style=svg)](https://circleci.com/gh/ros-perception/image_pipeline)
[![](https://github.com/ros-perception/image_pipeline/workflows/Basic%20Build%20Workflow/badge.svg?branch=melodic)](https://github.com/ros-perception/image_pipeline/actions)

This package fills the gap between getting raw images from a camera driver and higher-level vision processing.

Expand Down
36 changes: 36 additions & 0 deletions camera_calibration/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,3 +1,39 @@
1.15.0 (2020-05-18)
-------------------
* Fix import path on camera_calibrator.py (`#509 <https://github.com/ros-perception/image_pipeline/issues/509>`_)
* Fixes `#501 <https://github.com/ros-perception/image_pipeline/issues/501>`_: self.size is set before dumping calibration parameters in calibrator.py do_calibration(self, dump) (`#502 <https://github.com/ros-perception/image_pipeline/issues/502>`_)
Not sure how this one made it through. Thanks for the fix!
* Contributors: Gonçalo Camelo Neves Pereira, Stewart Jamieson

1.14.0 (2020-01-12)
-------------------
* Add Fisheye calibration tool (`#440 <https://github.com/ros-perception/image_pipeline/issues/440>`_)
* Add Fisheye calibration tool
* Restore camera_calib files permisions
* Upgrades to calibrator tool for multi model calibration
* Solve fisheye balance selection
* Add fisheye calibration flags as user arguments
* Add undistortion of points for fisheye
* cam_calib: Style formating
* camera_calibration: Improve YAML formatting, make config dumping methods static (`#438 <https://github.com/ros-perception/image_pipeline/issues/438>`_)
* Add `from __future_\_ import print_function`
* Improve YAML formatting, make some methods static
* Improves matrix formatting in YAML.
* Reduced decimal figures for camera and projection matrix values from 8 to 5.
* Making the methods static allows them to be used from elsewhere as well to dump calibration info.
* camera_calibration: Fix all-zero distortion coeffs returned for a rational_polynomial model (`#433 <https://github.com/ros-perception/image_pipeline/issues/433>`_)
* Fix empty distortion coeffs returned for a rational_polynomial model
* Remove the redundant distCoeffs parameter from cv2.calibrateCamera()
* Set the shape of distortion_coefficients correctly in YAML output
* Merge pull request `#437 <https://github.com/ros-perception/image_pipeline/issues/437>`_ from valgur/enable-calibration-with-empty-queue
camera_calibration: Make sure 'calibrate' button works even if not receiving images anymore
* Make sure 'calibrate' button works even if not receiving images anymore
* Merge pull request `#432 <https://github.com/ros-perception/image_pipeline/issues/432>`_ from valgur/melodic
camera_calibration: Fix excessive CPU usage due to queue synchronization
* Replace deque with a modified Queue, add --queue-size param
Base fork on upstream melodic instead of indigo
* Contributors: David Torres Ocaña, Joshua Whitley, Martin Valgur, Tim Übelhör

1.13.0 (2019-06-12)
-------------------
* Merge pull request `#356 <https://github.com/ros-perception/image_pipeline/issues/356>`_ from sevangelatos/feature/calibrator_rolling_shutter
Expand Down
93 changes: 83 additions & 10 deletions camera_calibration/nodes/cameracalibrator.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,22 @@
from camera_calibration.calibrator import ChessboardInfo, Patterns
from message_filters import ApproximateTimeSynchronizer

def optionsValidCharuco(options, parser):
"""
Validates the provided options when the pattern type is 'charuco'
"""
if options.pattern != 'charuco': return False

n_boards = len(options.size)
if (n_boards != len(options.square) or n_boards != len(options.charuco_marker_size) or n_boards !=
len(options.aruco_dict)):
parser.error("When using ChArUco boards, --size, --square, --charuco_marker_size, and --aruco_dict " +
"must be specified for each board")
return False

# TODO: check for fisheye and stereo (not implemented with ChArUco)
return True


def main():
from optparse import OptionParser, OptionGroup
Expand All @@ -53,13 +69,22 @@ def main():
"You must specify one or more chessboards as pairs of --size and --square options.")
group.add_option("-p", "--pattern",
type="string", default="chessboard",
help="calibration pattern to detect - 'chessboard', 'circles', 'acircles'")
help="calibration pattern to detect - 'chessboard', 'circles', 'acircles', 'charuco'\n" +
" if 'charuco' is used, a --charuco_marker_size and --aruco_dict argument must be supplied\n" +
" with each --size and --square argument")
group.add_option("-s", "--size",
action="append", default=[],
help="chessboard size as NxM, counting interior corners (e.g. a standard chessboard is 7x7)")
group.add_option("-q", "--square",
action="append", default=[],
help="chessboard square size in meters")
group.add_option("-m", "--charuco_marker_size",
action="append", default=[],
help="ArUco marker size (meters); only valid with `-p charuco`")
group.add_option("-d", "--aruco_dict",
action="append", default=[],
help="ArUco marker dictionary; only valid with `-p charuco`; one of 'aruco_orig', '4x4_250', " +
"'5x5_250', '6x6_250', '7x7_250'")
parser.add_option_group(group)
group = OptionGroup(parser, "ROS Communication Options")
group.add_option("--approximate",
Expand All @@ -75,41 +100,67 @@ def main():
group = OptionGroup(parser, "Calibration Optimizer Options")
group.add_option("--fix-principal-point",
action="store_true", default=False,
help="fix the principal point at the image center")
help="for pinhole, fix the principal point at the image center")
group.add_option("--fix-aspect-ratio",
action="store_true", default=False,
help="enforce focal lengths (fx, fy) are equal")
help="for pinhole, enforce focal lengths (fx, fy) are equal")
group.add_option("--zero-tangent-dist",
action="store_true", default=False,
help="set tangential distortion coefficients (p1, p2) to zero")
help="for pinhole, set tangential distortion coefficients (p1, p2) to zero")
group.add_option("-k", "--k-coefficients",
type="int", default=2, metavar="NUM_COEFFS",
help="number of radial distortion coefficients to use (up to 6, default %default)")
help="for pinhole, number of radial distortion coefficients to use (up to 6, default %default)")

group.add_option("--fisheye-recompute-extrinsicsts",
action="store_true", default=False,
help="for fisheye, extrinsic will be recomputed after each iteration of intrinsic optimization")
group.add_option("--fisheye-fix-skew",
action="store_true", default=False,
help="for fisheye, skew coefficient (alpha) is set to zero and stay zero")
group.add_option("--fisheye-fix-principal-point",
action="store_true", default=False,
help="for fisheye,fix the principal point at the image center")
group.add_option("--fisheye-k-coefficients",
type="int", default=4, metavar="NUM_COEFFS",
help="for fisheye, number of radial distortion coefficients to use fixing to zero the rest (up to 4, default %default)")

group.add_option("--fisheye-check-conditions",
action="store_true", default=False,
help="for fisheye, the functions will check validity of condition number")

group.add_option("--disable_calib_cb_fast_check", action='store_true', default=False,
help="uses the CALIB_CB_FAST_CHECK flag for findChessboardCorners")
group.add_option("--max-chessboard-speed", type="float", default=-1.0,
help="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.")

parser.add_option_group(group)

options, args = parser.parse_args()

if len(options.size) != len(options.square):
if (len(options.size) != len(options.square)):
parser.error("Number of size and square inputs must be the same!")

if not options.square:
options.square.append("0.108")
options.size.append("8x6")

boards = []
for (sz, sq) in zip(options.size, options.square):
size = tuple([int(c) for c in sz.split('x')])
boards.append(ChessboardInfo(size[0], size[1], float(sq)))
if options.pattern == "charuco" and optionsValidCharuco(options, parser):
for (sz, sq, ms, ad) in zip(options.size, options.square, options.charuco_marker_size, options.aruco_dict):
size = tuple([int(c) for c in sz.split('x')])
boards.append(ChessboardInfo('charuco', size[0], size[1], float(sq), float(ms), ad))
else:
for (sz, sq) in zip(options.size, options.square):
size = tuple([int(c) for c in sz.split('x')])
boards.append(ChessboardInfo(options.pattern, size[0], size[1], float(sq)))

if options.approximate == 0.0:
sync = message_filters.TimeSynchronizer
else:
sync = functools.partial(ApproximateTimeSynchronizer, slop=options.approximate)

# Pinhole opencv calibration options parsing
num_ks = options.k_coefficients

calib_flags = 0
Expand All @@ -134,11 +185,33 @@ def main():
if (num_ks < 1):
calib_flags |= cv2.CALIB_FIX_K1

# Opencv calibration flags parsing:
num_ks = options.fisheye_k_coefficients
fisheye_calib_flags = 0
if options.fisheye_fix_principal_point:
fisheye_calib_flags |= cv2.fisheye.CALIB_FIX_PRINCIPAL_POINT
if options.fisheye_fix_skew:
fisheye_calib_flags |= cv2.fisheye.CALIB_FIX_SKEW
if options.fisheye_recompute_extrinsicsts:
fisheye_calib_flags |= cv2.fisheye.CALIB_RECOMPUTE_EXTRINSIC
if options.fisheye_check_conditions:
fisheye_calib_flags |= cv2.fisheye.CALIB_CHECK_COND
if (num_ks < 4):
fisheye_calib_flags |= cv2.fisheye.CALIB_FIX_K4
if (num_ks < 3):
fisheye_calib_flags |= cv2.fisheye.CALIB_FIX_K3
if (num_ks < 2):
fisheye_calib_flags |= cv2.fisheye.CALIB_FIX_K2
if (num_ks < 1):
fisheye_calib_flags |= cv2.fisheye.CALIB_FIX_K1

pattern = Patterns.Chessboard
if options.pattern == 'circles':
pattern = Patterns.Circles
elif options.pattern == 'acircles':
pattern = Patterns.ACircles
elif options.pattern == 'charuco':
pattern = Patterns.ChArUco
elif options.pattern != 'chessboard':
print('Unrecognized pattern %s, defaulting to chessboard' % options.pattern)

Expand All @@ -148,7 +221,7 @@ def main():
checkerboard_flags = cv2.CALIB_CB_FAST_CHECK

rospy.init_node('cameracalibrator')
node = OpenCVCalibrationNode(boards, options.service_check, sync, calib_flags, pattern, options.camera_name,
node = OpenCVCalibrationNode(boards, options.service_check, sync, calib_flags, fisheye_calib_flags, pattern, options.camera_name,
checkerboard_flags=checkerboard_flags, max_chessboard_speed=options.max_chessboard_speed,
queue_size=options.queue_size)
rospy.spin()
Expand Down
2 changes: 1 addition & 1 deletion camera_calibration/package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package>
<name>camera_calibration</name>
<version>1.13.0</version>
<version>1.15.0</version>
<description>
camera_calibration allows easy calibration of monocular or stereo
cameras using a checkerboard calibration target.
Expand Down
Loading

0 comments on commit fd76f52

Please sign in to comment.