Skip to content

Commit fd76f52

Browse files
Merge branch 'melodic' into image_proc_fisheye
2 parents 0acfe95 + 71900fa commit fd76f52

36 files changed

+860
-490
lines changed

.circleci/config.yml

Lines changed: 0 additions & 66 deletions
This file was deleted.

.github/workflows/basic-build-ci.yaml

Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,38 @@
1+
name: Basic Build Workflow
2+
3+
on:
4+
- pull_request
5+
- push
6+
7+
jobs:
8+
build-melodic:
9+
runs-on: ubuntu-latest
10+
strategy:
11+
fail-fast: false
12+
container:
13+
image: ros:melodic-perception
14+
steps:
15+
- name: Checkout repo
16+
uses: actions/checkout@v2
17+
- name: Create Workspace
18+
run: |
19+
mkdir src_tmp
20+
mv `find -maxdepth 1 -not -name . -not -name src_tmp` src_tmp/
21+
mv src_tmp/ src/
22+
cd src
23+
bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \
24+
catkin_init_workspace'
25+
- name: Install Prerequisites
26+
run: |
27+
bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \
28+
apt-get update && rosdep update; \
29+
rosdep install --from-paths src --ignore-src -y'
30+
- name: Build Workspace
31+
run: |
32+
bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \
33+
catkin_make'
34+
- name: Run Tests
35+
run: |
36+
bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \
37+
catkin_make run_tests; \
38+
catkin_test_results --verbose'

README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
image_pipeline
22
==============
33

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

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

camera_calibration/CHANGELOG.rst

Lines changed: 36 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,39 @@
1+
1.15.0 (2020-05-18)
2+
-------------------
3+
* Fix import path on camera_calibrator.py (`#509 <https://github.com/ros-perception/image_pipeline/issues/509>`_)
4+
* 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>`_)
5+
Not sure how this one made it through. Thanks for the fix!
6+
* Contributors: Gonçalo Camelo Neves Pereira, Stewart Jamieson
7+
8+
1.14.0 (2020-01-12)
9+
-------------------
10+
* Add Fisheye calibration tool (`#440 <https://github.com/ros-perception/image_pipeline/issues/440>`_)
11+
* Add Fisheye calibration tool
12+
* Restore camera_calib files permisions
13+
* Upgrades to calibrator tool for multi model calibration
14+
* Solve fisheye balance selection
15+
* Add fisheye calibration flags as user arguments
16+
* Add undistortion of points for fisheye
17+
* cam_calib: Style formating
18+
* camera_calibration: Improve YAML formatting, make config dumping methods static (`#438 <https://github.com/ros-perception/image_pipeline/issues/438>`_)
19+
* Add `from __future_\_ import print_function`
20+
* Improve YAML formatting, make some methods static
21+
* Improves matrix formatting in YAML.
22+
* Reduced decimal figures for camera and projection matrix values from 8 to 5.
23+
* Making the methods static allows them to be used from elsewhere as well to dump calibration info.
24+
* camera_calibration: Fix all-zero distortion coeffs returned for a rational_polynomial model (`#433 <https://github.com/ros-perception/image_pipeline/issues/433>`_)
25+
* Fix empty distortion coeffs returned for a rational_polynomial model
26+
* Remove the redundant distCoeffs parameter from cv2.calibrateCamera()
27+
* Set the shape of distortion_coefficients correctly in YAML output
28+
* Merge pull request `#437 <https://github.com/ros-perception/image_pipeline/issues/437>`_ from valgur/enable-calibration-with-empty-queue
29+
camera_calibration: Make sure 'calibrate' button works even if not receiving images anymore
30+
* Make sure 'calibrate' button works even if not receiving images anymore
31+
* Merge pull request `#432 <https://github.com/ros-perception/image_pipeline/issues/432>`_ from valgur/melodic
32+
camera_calibration: Fix excessive CPU usage due to queue synchronization
33+
* Replace deque with a modified Queue, add --queue-size param
34+
Base fork on upstream melodic instead of indigo
35+
* Contributors: David Torres Ocaña, Joshua Whitley, Martin Valgur, Tim Übelhör
36+
137
1.13.0 (2019-06-12)
238
-------------------
339
* Merge pull request `#356 <https://github.com/ros-perception/image_pipeline/issues/356>`_ from sevangelatos/feature/calibrator_rolling_shutter

camera_calibration/nodes/cameracalibrator.py

Lines changed: 83 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,22 @@
4141
from camera_calibration.calibrator import ChessboardInfo, Patterns
4242
from message_filters import ApproximateTimeSynchronizer
4343

44+
def optionsValidCharuco(options, parser):
45+
"""
46+
Validates the provided options when the pattern type is 'charuco'
47+
"""
48+
if options.pattern != 'charuco': return False
49+
50+
n_boards = len(options.size)
51+
if (n_boards != len(options.square) or n_boards != len(options.charuco_marker_size) or n_boards !=
52+
len(options.aruco_dict)):
53+
parser.error("When using ChArUco boards, --size, --square, --charuco_marker_size, and --aruco_dict " +
54+
"must be specified for each board")
55+
return False
56+
57+
# TODO: check for fisheye and stereo (not implemented with ChArUco)
58+
return True
59+
4460

4561
def main():
4662
from optparse import OptionParser, OptionGroup
@@ -53,13 +69,22 @@ def main():
5369
"You must specify one or more chessboards as pairs of --size and --square options.")
5470
group.add_option("-p", "--pattern",
5571
type="string", default="chessboard",
56-
help="calibration pattern to detect - 'chessboard', 'circles', 'acircles'")
72+
help="calibration pattern to detect - 'chessboard', 'circles', 'acircles', 'charuco'\n" +
73+
" if 'charuco' is used, a --charuco_marker_size and --aruco_dict argument must be supplied\n" +
74+
" with each --size and --square argument")
5775
group.add_option("-s", "--size",
5876
action="append", default=[],
5977
help="chessboard size as NxM, counting interior corners (e.g. a standard chessboard is 7x7)")
6078
group.add_option("-q", "--square",
6179
action="append", default=[],
6280
help="chessboard square size in meters")
81+
group.add_option("-m", "--charuco_marker_size",
82+
action="append", default=[],
83+
help="ArUco marker size (meters); only valid with `-p charuco`")
84+
group.add_option("-d", "--aruco_dict",
85+
action="append", default=[],
86+
help="ArUco marker dictionary; only valid with `-p charuco`; one of 'aruco_orig', '4x4_250', " +
87+
"'5x5_250', '6x6_250', '7x7_250'")
6388
parser.add_option_group(group)
6489
group = OptionGroup(parser, "ROS Communication Options")
6590
group.add_option("--approximate",
@@ -75,41 +100,67 @@ def main():
75100
group = OptionGroup(parser, "Calibration Optimizer Options")
76101
group.add_option("--fix-principal-point",
77102
action="store_true", default=False,
78-
help="fix the principal point at the image center")
103+
help="for pinhole, fix the principal point at the image center")
79104
group.add_option("--fix-aspect-ratio",
80105
action="store_true", default=False,
81-
help="enforce focal lengths (fx, fy) are equal")
106+
help="for pinhole, enforce focal lengths (fx, fy) are equal")
82107
group.add_option("--zero-tangent-dist",
83108
action="store_true", default=False,
84-
help="set tangential distortion coefficients (p1, p2) to zero")
109+
help="for pinhole, set tangential distortion coefficients (p1, p2) to zero")
85110
group.add_option("-k", "--k-coefficients",
86111
type="int", default=2, metavar="NUM_COEFFS",
87-
help="number of radial distortion coefficients to use (up to 6, default %default)")
112+
help="for pinhole, number of radial distortion coefficients to use (up to 6, default %default)")
113+
114+
group.add_option("--fisheye-recompute-extrinsicsts",
115+
action="store_true", default=False,
116+
help="for fisheye, extrinsic will be recomputed after each iteration of intrinsic optimization")
117+
group.add_option("--fisheye-fix-skew",
118+
action="store_true", default=False,
119+
help="for fisheye, skew coefficient (alpha) is set to zero and stay zero")
120+
group.add_option("--fisheye-fix-principal-point",
121+
action="store_true", default=False,
122+
help="for fisheye,fix the principal point at the image center")
123+
group.add_option("--fisheye-k-coefficients",
124+
type="int", default=4, metavar="NUM_COEFFS",
125+
help="for fisheye, number of radial distortion coefficients to use fixing to zero the rest (up to 4, default %default)")
126+
127+
group.add_option("--fisheye-check-conditions",
128+
action="store_true", default=False,
129+
help="for fisheye, the functions will check validity of condition number")
130+
88131
group.add_option("--disable_calib_cb_fast_check", action='store_true', default=False,
89132
help="uses the CALIB_CB_FAST_CHECK flag for findChessboardCorners")
90133
group.add_option("--max-chessboard-speed", type="float", default=-1.0,
91134
help="Do not use samples where the calibration pattern is moving faster \
92135
than this speed in px/frame. Set to eg. 0.5 for rolling shutter cameras.")
136+
93137
parser.add_option_group(group)
138+
94139
options, args = parser.parse_args()
95140

96-
if len(options.size) != len(options.square):
141+
if (len(options.size) != len(options.square)):
97142
parser.error("Number of size and square inputs must be the same!")
98143

99144
if not options.square:
100145
options.square.append("0.108")
101146
options.size.append("8x6")
102147

103148
boards = []
104-
for (sz, sq) in zip(options.size, options.square):
105-
size = tuple([int(c) for c in sz.split('x')])
106-
boards.append(ChessboardInfo(size[0], size[1], float(sq)))
149+
if options.pattern == "charuco" and optionsValidCharuco(options, parser):
150+
for (sz, sq, ms, ad) in zip(options.size, options.square, options.charuco_marker_size, options.aruco_dict):
151+
size = tuple([int(c) for c in sz.split('x')])
152+
boards.append(ChessboardInfo('charuco', size[0], size[1], float(sq), float(ms), ad))
153+
else:
154+
for (sz, sq) in zip(options.size, options.square):
155+
size = tuple([int(c) for c in sz.split('x')])
156+
boards.append(ChessboardInfo(options.pattern, size[0], size[1], float(sq)))
107157

108158
if options.approximate == 0.0:
109159
sync = message_filters.TimeSynchronizer
110160
else:
111161
sync = functools.partial(ApproximateTimeSynchronizer, slop=options.approximate)
112162

163+
# Pinhole opencv calibration options parsing
113164
num_ks = options.k_coefficients
114165

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

188+
# Opencv calibration flags parsing:
189+
num_ks = options.fisheye_k_coefficients
190+
fisheye_calib_flags = 0
191+
if options.fisheye_fix_principal_point:
192+
fisheye_calib_flags |= cv2.fisheye.CALIB_FIX_PRINCIPAL_POINT
193+
if options.fisheye_fix_skew:
194+
fisheye_calib_flags |= cv2.fisheye.CALIB_FIX_SKEW
195+
if options.fisheye_recompute_extrinsicsts:
196+
fisheye_calib_flags |= cv2.fisheye.CALIB_RECOMPUTE_EXTRINSIC
197+
if options.fisheye_check_conditions:
198+
fisheye_calib_flags |= cv2.fisheye.CALIB_CHECK_COND
199+
if (num_ks < 4):
200+
fisheye_calib_flags |= cv2.fisheye.CALIB_FIX_K4
201+
if (num_ks < 3):
202+
fisheye_calib_flags |= cv2.fisheye.CALIB_FIX_K3
203+
if (num_ks < 2):
204+
fisheye_calib_flags |= cv2.fisheye.CALIB_FIX_K2
205+
if (num_ks < 1):
206+
fisheye_calib_flags |= cv2.fisheye.CALIB_FIX_K1
207+
137208
pattern = Patterns.Chessboard
138209
if options.pattern == 'circles':
139210
pattern = Patterns.Circles
140211
elif options.pattern == 'acircles':
141212
pattern = Patterns.ACircles
213+
elif options.pattern == 'charuco':
214+
pattern = Patterns.ChArUco
142215
elif options.pattern != 'chessboard':
143216
print('Unrecognized pattern %s, defaulting to chessboard' % options.pattern)
144217

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

150223
rospy.init_node('cameracalibrator')
151-
node = OpenCVCalibrationNode(boards, options.service_check, sync, calib_flags, pattern, options.camera_name,
224+
node = OpenCVCalibrationNode(boards, options.service_check, sync, calib_flags, fisheye_calib_flags, pattern, options.camera_name,
152225
checkerboard_flags=checkerboard_flags, max_chessboard_speed=options.max_chessboard_speed,
153226
queue_size=options.queue_size)
154227
rospy.spin()

camera_calibration/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
<package>
22
<name>camera_calibration</name>
3-
<version>1.13.0</version>
3+
<version>1.15.0</version>
44
<description>
55
camera_calibration allows easy calibration of monocular or stereo
66
cameras using a checkerboard calibration target.

0 commit comments

Comments
 (0)