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 aruco detector parameter file #228

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
53 changes: 53 additions & 0 deletions aruco_pose/launch/aruco_detector_config.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
# Detector parameters for aruco_detect nodelet
# Constant for adaptive thresholding before finding contours
adaptiveThreshConstant: 7.0
# 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
# Maximum number of iterations for stop criteria of the corner refinement process
cornerRefinementMaxIterations: 30
# Corner refinement method:
# 0 - no refinement;
# 1 - do subpixel refinement;
# 2 - use contour-points (OpenCV 3.3+);
# 3 - use the AprilTag2 approach (OpenCV 3.3+).
cornerRefinementMethod: 2
# Minimum error for the stop criteria of the corner refinement process
cornerRefinementMinAccuracy: 0.1
# Window size for the corner refinement process (in pixels)
cornerRefinementWinSize: 5
# (OpenCV 3.4.7+) check if there is a white marker
detectInvertedMarker: false
# Error correction rate respect to the maximum error correction capability for each dictionary
errorCorrectionRate: 0.6
# Minimum distance between corners for detected markers relative to its perimeter
minCornerDistanceRate: 0.05
# Number of bits of the marker border, i.e. marker border width
markerBorderBits: 1
# Maximum number of accepted erroneous bits in the border (i.e. number of allowed white bits in the border)
maxErroneousBitsInBorderRate: 0.35
# Minimum distance of any corner to the image border for detected markers (in pixels)
minDistanceToBorder: 3
# minimum mean distance beetween two marker corners to be considered similar, so that the smaller one is removed. The rate is relative to the smaller perimeter of the two markers
minMarkerDistanceRate: 0.05
# Determine minimum perimeter for marker contour to be detected. This is defined as a rate respect to the maximum dimension of the input image
# Smallest detectable marker from 4x4 dicts would have a perimeter of 24 pixels ((4 inner pixels + 2 border pixels) * 4 sides)
# Set this to at least 0.0375 for 640x480 images, 0.075 for 320x240 images
minMarkerPerimeterRate: 0.075
# 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
# 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
# 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. perpectiveRemovePixelPerCell
perspectiveRemoveIgnoredMarginPerCell: 0.13
# Number of bits (per dimension) for each cell of the marker when removing the perspective
perspectiveRemovePixelPerCell: 4
# Minimum accuracy during the polygonal approximation process to determine which contours are squares
polygonalApproxAccuracyRate: 0.03
# Detection of quads can be done on a lower-resolution image, improving speed at a cost of pose accuracy and a slight decrease in detection rate. Decoding the binary payload is still done at full resolution
aprilTagQuadDecimate: 0.0
# What Gaussian blur should be applied to the segmented image (used for quad detection?) Parameter is the standard deviation in pixels. Very noisy images benefit from non-zero values
aprilTagQuadSigma: 0.0
1 change: 1 addition & 0 deletions aruco_pose/launch/sample.launch
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
<remap from="image_raw" to="main_camera/image_raw"/>
<remap from="camera_info" to="main_camera/camera_info"/>
<param name="length" value="0.33"/>
<rosparam command="load" file="$(dirname)/aruco_detector_config.yaml"/>
</node>

<!-- aruco map -->
Expand Down
4 changes: 3 additions & 1 deletion clover/launch/aruco.launch
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,13 @@
<remap from="image_raw" to="main_camera/image_raw"/>
<remap from="camera_info" to="main_camera/camera_info"/>
<remap from="map_markers" to="aruco_map/markers" if="$(arg aruco_map)"/>
<param name="cornerRefinementMethod" value="2"/>
<param name="estimate_poses" value="true"/>
<param name="send_tf" value="true"/>
<param name="known_tilt" value="map"/>
<param name="length" value="0.33"/>
<!-- aruco detector parameters -->
<param name="cornerRefinementMethod" value="2"/> <!-- contour refinement -->
<param name="minMarkerPerimeterRate" value="0.075"/> <!-- 0.075 for 320x240, 0.0375 for 640x480 -->
</node>

<!-- aruco_map: estimate aruco map pose -->
Expand Down