Skip to content

Commit

Permalink
Handle hamming distance param
Browse files Browse the repository at this point in the history
  • Loading branch information
davidirobinson committed Jun 22, 2022
1 parent 5e94306 commit b283515
Show file tree
Hide file tree
Showing 4 changed files with 4 additions and 2 deletions.
1 change: 1 addition & 0 deletions multisense_ros/cfg/multisense.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -348,6 +348,7 @@ for feature_name, feature in SupportedFeatures.__members__.items():
gen.const("tagStandard52h13", str_t, "tagStandard52h13", "tagStandard52h13")],
"Available apriltag families")
gen.add("apriltag_family", str_t, 0, "Apriltag family to detect", "tagStandard52h13", edit_method=apriltag_family_enum)
gen.add("apriltag_max_hamming", int_t, 0, "The maximum hamming correction that will be applied while detecting codes (value of 1 causes the detector to pause for a while)", 0, 0, 1)
gen.add("apriltag_quad_detection_blur_sigma", double_t, 0, "Sigma of the Gaussian blur applied to the image before quad_detection, specified in full resolution pixels. Kernel size = 4*sigma, rounded up to the next odd number. (<0.5 results in no blur)", 0.75, 0.0, 5.0)
gen.add("apriltag_quad_detection_decimate", double_t, 0, "Amount to decimate image before detecting quads. Values < 1.0. (0.5 decimation reduces height/width by half)", 1.0, 0.0, 1.0)
gen.add("apriltag_min_border_width", int_t, 0, "Minimum border width that can be considered a valid tag. Used to filter contours based on area and perimeter. Units are in undecimated image pixels.", 5, 0, 10)
Expand Down
2 changes: 1 addition & 1 deletion multisense_ros/msg/AprilTagDetection.msg
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# The family of the tag
uint64 family
string family

# The ID of the tag
uint32 id
Expand Down
1 change: 1 addition & 0 deletions multisense_ros/src/reconfigure.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -878,6 +878,7 @@ template<class T> void Reconfigure::configureApriltagParams(const T& dyn)
crl::multisense::system::ApriltagParams params;

params.family = dyn.apriltag_family;
params.max_hamming = dyn.apriltag_max_hamming;
params.quad_detection_blur_sigma = dyn.apriltag_quad_detection_blur_sigma;
params.quad_detection_decimate = dyn.apriltag_quad_detection_decimate;
params.min_border_width = dyn.apriltag_min_border_width;
Expand Down

0 comments on commit b283515

Please sign in to comment.