Skip to content

Commit

Permalink
Add missing detection parameters (#38)
Browse files Browse the repository at this point in the history
* Populate default aruco parameter values from OpenCV library

* Add detectInvertedMarker parameter

* Add descriptions to aruco parameters in yaml file

* Add option to generate inverted markers

* Add Aruco3 detection parameters
  • Loading branch information
bjsowa committed May 7, 2024
1 parent 9cbdaa7 commit 026af15
Show file tree
Hide file tree
Showing 4 changed files with 174 additions and 20 deletions.
61 changes: 61 additions & 0 deletions aruco_opencv/config/aruco_tracker.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -17,23 +17,84 @@
# Dynamically reconfigurable Detector parameters
# https://docs.opencv.org/4.2.0/d5/dae/tutorial_aruco_detection.html
aruco:
# minimum window size for adaptive thresholding before finding contours
adaptiveThreshWinSizeMin: 3

# maximum window size for adaptive thresholding before finding contours
adaptiveThreshWinSizeMax: 23

# increments from adaptiveThreshWinSizeMin to adaptiveThreshWinSizeMax during the thresholding
adaptiveThreshWinSizeStep: 10

# constant for adaptive thresholding before finding contours
adaptiveThreshConstant: 7.0

# determine minimum perimeter for marker contour to be detected.
# This is defined as a rate respect to the maximum dimension of the input image
minMarkerPerimeterRate: 0.03

# determine maximum perimeter for marker contour to be detected.
# This is defined as a rate respect to the maximum dimension of the input image
maxMarkerPerimeterRate: 4.0

# minimum accuracy during the polygonal approximation process to determine which contours are squares.
polygonalApproxAccuracyRate: 0.03

# minimum distance between corners for detected markers relative to its perimeter
minCornerDistanceRate: 0.05

# minimum distance of any corner to the image border for detected markers
minDistanceToBorder: 3

# minimum average distance between the corners of the two markers to be grouped (default 0.125).
# The rate is relative to the smaller perimeter of the two markers.
# Two markers are grouped if average distance between the corners of the two markers is less than
# min(MarkerPerimeter1, MarkerPerimeter2)*minMarkerDistanceRate.
minMarkerDistanceRate: 0.05

# number of bits of the marker border, i.e. marker border width
markerBorderBits: 1

# number of bits (per dimension) for each cell of the marker when removing the perspective
perspectiveRemovePixelPerCell: 4

# width of the margin of pixels on each cell not considered for the determination of the cell bit.
# Represents the rate respect to the total size of the cell, i.e. perspectiveRemovePixelPerCell
perspectiveRemoveIgnoredMarginPerCell: 0.13

# maximum number of accepted erroneous bits in the border (i.e. number of allowed white bits in the border).
# Represented as a rate respect to the total number of bits per marker
maxErroneousBitsInBorderRate: 0.35

# minimun standard deviation in pixels values during the decodification step to apply Otsu
# thresholding (otherwise, all the bits are set to 0 or 1 depending on mean higher than 128 or not)
minOtsuStdDev: 5.0

# error correction rate respect to the maximun error correction capability for each dictionary
errorCorrectionRate: 0.6

cornerRefinementMethod: 2 # 0 - None, 1 - Subpix, 2 - Contour

# maximum window size for the corner refinement process (in pixels)
cornerRefinementWinSize: 5

# maximum number of iterations for stop criteria of the corner refinement process
cornerRefinementMaxIterations: 30

# minimum error for the stop cristeria of the corner refinement process
cornerRefinementMinAccuracy: 0.1

# to check if there is a white marker
detectInvertedMarker: false

# (required OpenCV 4.6.0+) enable the new and faster Aruco detection strategy.
# Proposed in the paper:
# Romero-Ramirez et al: Speeded up detection of squared fiducial markers (2018)
# https://www.researchgate.net/publication/325787310_Speeded_Up_Detection_of_Squared_Fiducial_Markers
useAruco3Detection: false

# (required OpenCV 4.6.0+) minimum side length of a marker in the canonical image. Latter is the binarized image in which contours are searched
minSideLengthCanonicalImg: 32

# (required OpenCV 4.6.0+) range [0,1], eq (2) from paper. The parameter tau_i has a direct influence on the processing speed.
minMarkerLengthRatioOriginalImg: 0.0
114 changes: 94 additions & 20 deletions aruco_opencv/include/aruco_opencv/parameters.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,26 +87,71 @@ inline void declare_param_double_range(
template<class NodeT>
inline void declare_aruco_parameters(NodeT && node)
{
declare_param_int_range(node, "aruco.adaptiveThreshWinSizeMin", 3, 3, 100);
declare_param_int_range(node, "aruco.adaptiveThreshWinSizeMax", 23, 3, 100);
declare_param_int_range(node, "aruco.adaptiveThreshWinSizeStep", 10, 1, 100);
declare_param_double_range(node, "aruco.adaptiveThreshConstant", 7.0, 0.0, 100.0);
declare_param_double_range(node, "aruco.minMarkerPerimeterRate", 0.03, 0.0, 4.0);
declare_param_double_range(node, "aruco.maxMarkerPerimeterRate", 4.0, 0.0, 4.0);
declare_param_double_range(node, "aruco.polygonalApproxAccuracyRate", 0.03, 0.0, 0.3);
declare_param_double_range(node, "aruco.minCornerDistanceRate", 0.05, 0.0, 0.25);
declare_param_int_range(node, "aruco.minDistanceToBorder", 3, 0, 100);
declare_param_double_range(node, "aruco.minMarkerDistanceRate", 0.05, 0.0, 0.25);
declare_param_int_range(node, "aruco.markerBorderBits", 1, 1, 3);
declare_param_int_range(node, "aruco.perspectiveRemovePixelPerCell", 4, 1, 20);
declare_param_double_range(node, "aruco.perspectiveRemoveIgnoredMarginPerCell", 0.13, 0.0, 0.5);
declare_param_double_range(node, "aruco.maxErroneousBitsInBorderRate", 0.35, 0.0, 1.0);
declare_param_double_range(node, "aruco.minOtsuStdDev", 5.0, 0.0, 30.0);
declare_param_double_range(node, "aruco.errorCorrectionRate", 0.6, 0.0, 1.0);
declare_param_int_range(node, "aruco.cornerRefinementMethod", 2, 0, 2);
declare_param_int_range(node, "aruco.cornerRefinementWinSize", 5, 2, 10);
declare_param_int_range(node, "aruco.cornerRefinementMaxIterations", 30, 1, 100);
declare_param_double_range(node, "aruco.cornerRefinementMinAccuracy", 0.1, 0.01, 1.0);
#if CV_VERSION_MAJOR > 4 || CV_VERSION_MAJOR == 4 && CV_VERSION_MINOR >= 7
auto default_parameters = cv::makePtr<cv::aruco::DetectorParameters>();
#else
auto default_parameters = cv::aruco::DetectorParameters::create();
#endif

declare_param_int_range(node,
"aruco.adaptiveThreshWinSizeMin", default_parameters->adaptiveThreshWinSizeMin, 3, 100);
declare_param_int_range(node,
"aruco.adaptiveThreshWinSizeMax", default_parameters->adaptiveThreshWinSizeMax, 3, 100);
declare_param_int_range(node,
"aruco.adaptiveThreshWinSizeStep", default_parameters->adaptiveThreshWinSizeStep, 1, 100);
declare_param_double_range(node,
"aruco.adaptiveThreshConstant", default_parameters->adaptiveThreshConstant, 0.0, 100.0);
declare_param_double_range(node,
"aruco.minMarkerPerimeterRate", default_parameters->minMarkerPerimeterRate, 0.0, 4.0);
declare_param_double_range(node,
"aruco.maxMarkerPerimeterRate", default_parameters->maxMarkerPerimeterRate, 0.0, 4.0);
declare_param_double_range(node,
"aruco.polygonalApproxAccuracyRate",
default_parameters->polygonalApproxAccuracyRate, 0.0, 0.3);
declare_param_double_range(node,
"aruco.minCornerDistanceRate", default_parameters->minCornerDistanceRate, 0.0, 0.25);
declare_param_int_range(node,
"aruco.minDistanceToBorder", default_parameters->minDistanceToBorder, 0, 100);
declare_param_double_range(node,
"aruco.minMarkerDistanceRate", default_parameters->minMarkerDistanceRate, 0.0, 0.25);
declare_param_int_range(node,
"aruco.markerBorderBits", default_parameters->markerBorderBits, 1, 3);
declare_param_int_range(node,
"aruco.perspectiveRemovePixelPerCell",
default_parameters->perspectiveRemovePixelPerCell, 1, 20);
declare_param_double_range(node,
"aruco.perspectiveRemoveIgnoredMarginPerCell",
default_parameters->perspectiveRemoveIgnoredMarginPerCell, 0.0, 0.5);
declare_param_double_range(node,
"aruco.maxErroneousBitsInBorderRate",
default_parameters->maxErroneousBitsInBorderRate, 0.0, 1.0);
declare_param_double_range(node,
"aruco.minOtsuStdDev", default_parameters->minOtsuStdDev, 0.0, 30.0);
declare_param_double_range(node,
"aruco.errorCorrectionRate", default_parameters->errorCorrectionRate, 0.0, 1.0);
declare_param_int_range(node,
"aruco.cornerRefinementMethod", default_parameters->cornerRefinementMethod, 0, 2);
declare_param_int_range(node,
"aruco.cornerRefinementWinSize", default_parameters->cornerRefinementWinSize, 2, 10);
declare_param_int_range(node,
"aruco.cornerRefinementMaxIterations",
default_parameters->cornerRefinementMaxIterations, 1, 100);
declare_param_double_range(node,
"aruco.cornerRefinementMinAccuracy",
default_parameters->cornerRefinementMinAccuracy, 0.01, 1.0);
declare_param(node,
"aruco.detectInvertedMarker", default_parameters->detectInvertedMarker, true);

#if CV_VERSION_MAJOR > 4 || CV_VERSION_MAJOR == 4 && CV_VERSION_MINOR >= 6
declare_param(node,
"aruco.useAruco3Detection", default_parameters->useAruco3Detection, true);
declare_param_int_range(node,
"aruco.minSideLengthCanonicalImg",
default_parameters->minSideLengthCanonicalImg, 1, 100);
declare_param_double_range(node,
"aruco.minMarkerLengthRatioOriginalImg",
default_parameters->minMarkerLengthRatioOriginalImg, 0.0, 1.0);
#endif
}

template<class NodeT>
Expand Down Expand Up @@ -164,6 +209,17 @@ void retrieve_aruco_parameters(
"aruco.cornerRefinementMaxIterations", detector_parameters->cornerRefinementMaxIterations);
node.get_parameter(
"aruco.cornerRefinementMinAccuracy", detector_parameters->cornerRefinementMinAccuracy);
node.get_parameter(
"aruco.detectInvertedMarker", detector_parameters->detectInvertedMarker);

#if CV_VERSION_MAJOR > 4 || CV_VERSION_MAJOR == 4 && CV_VERSION_MINOR >= 6
node.get_parameter(
"aruco.useAruco3Detection", detector_parameters->useAruco3Detection);
node.get_parameter(
"aruco.minSideLengthCanonicalImg", detector_parameters->minSideLengthCanonicalImg);
node.get_parameter(
"aruco.minMarkerLengthRatioOriginalImg", detector_parameters->minMarkerLengthRatioOriginalImg);
#endif

if (log_values) {
RCLCPP_INFO_STREAM(
Expand Down Expand Up @@ -229,6 +285,24 @@ void retrieve_aruco_parameters(
RCLCPP_INFO_STREAM(
node.get_logger(),
" * cornerRefinementMinAccuracy: " << detector_parameters->cornerRefinementMinAccuracy);
RCLCPP_INFO_STREAM(
node.get_logger(),
" * detectInvertedMarker: " <<
(detector_parameters->detectInvertedMarker ? "TRUE" : "FALSE"));

#if CV_VERSION_MAJOR > 4 || CV_VERSION_MAJOR == 4 && CV_VERSION_MINOR >= 6
RCLCPP_INFO_STREAM(
node.get_logger(),
" * useAruco3Detection: " <<
(detector_parameters->useAruco3Detection ? "TRUE" : "FALSE"));
RCLCPP_INFO_STREAM(
node.get_logger(),
" * minSideLengthCanonicalImg: " << detector_parameters->minSideLengthCanonicalImg);
RCLCPP_INFO_STREAM(
node.get_logger(),
" * minMarkerLengthRatioOriginalImg: " <<
detector_parameters->minMarkerLengthRatioOriginalImg);
#endif
}
}

Expand Down
10 changes: 10 additions & 0 deletions aruco_opencv/scripts/create_board
Original file line number Diff line number Diff line change
Expand Up @@ -100,6 +100,12 @@ def parse_args() -> argparse.Namespace:
default=2,
help="Number of markers in the Y direction",
)
parser.add_argument(
"-i",
"--inverted",
action='store_true',
help="Whether the board should be inverted (white board)",
)
parser.add_argument(
"id", type=int, nargs="+", help="ID of the first marker in the board"
)
Expand Down Expand Up @@ -143,6 +149,7 @@ def main():
f"Output image size: {args.size:.3f} x {output_y_size:.3f} m - {output_x_pixels} x {output_y_pixels} pixels"
)
print(f"Output DPI: {dpi:.3f}")
print(f"Inverted: {"TRUE" if args.inverted else "FALSE"}")

images = []
for marker_id in args.id:
Expand All @@ -166,6 +173,9 @@ def main():
args.border_bits,
)

if args.inverted:
marker = ~marker

img = cv2.imencode(".png", marker)[1].tobytes()
images.append(img)

Expand Down
9 changes: 9 additions & 0 deletions aruco_opencv/scripts/create_marker
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,12 @@ def parse_args() -> argparse.Namespace:
default=0.10,
help="Output marker size (with margins) in meters",
)
parser.add_argument(
"-i",
"--inverted",
action='store_true',
help="Whether the marker should be inverted (white marker)",
)
parser.add_argument("id", type=int, nargs="+", help="ID of the marker to generate")
return parser.parse_args()

Expand All @@ -101,6 +107,7 @@ def main():
)
print(f"Output image side size: {args.size:.3f} m - {output_side_pixels} pixels")
print(f"Output DPI: {dpi:.3f}")
print(f"Inverted: {"TRUE" if args.inverted else "FALSE"}")

images = []
for marker_id in args.id:
Expand All @@ -111,6 +118,8 @@ def main():
)
if args.margin_pixels > 0:
marker = np.pad(marker, args.margin_pixels, constant_values=255)
if args.inverted:
marker = ~marker
img = cv2.imencode(".png", marker)[1].tobytes()
images.append(img)

Expand Down

0 comments on commit 026af15

Please sign in to comment.