Skip to content

Commit

Permalink
Add configurable max_hamming_distance for the AprilTag Detector
Browse files Browse the repository at this point in the history
  • Loading branch information
Akshay Prasad committed Mar 31, 2021
1 parent ee868d3 commit 4793e17
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 2 deletions.
1 change: 1 addition & 0 deletions apriltag_ros/config/settings.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -7,5 +7,6 @@ tag_decimate: 1.0 # default: 1.0
tag_blur: 0.0 # default: 0.0
tag_refine_edges: 1 # default: 1
tag_debug: 0 # default: 0
max_hamming_dist: 2 # default: 2
# Other parameters
publish_tf: true # default: false
1 change: 1 addition & 0 deletions apriltag_ros/include/apriltag_ros/common_functions.h
Original file line number Diff line number Diff line change
Expand Up @@ -168,6 +168,7 @@ class TagDetector
double blur_;
int refine_edges_;
int debug_;
int max_hamming_distance_;

// AprilTag 2 objects
apriltag_family_t *tf_;
Expand Down
5 changes: 3 additions & 2 deletions apriltag_ros/src/common_functions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,8 @@ TagDetector::TagDetector(ros::NodeHandle pnh) :
blur_(getAprilTagOption<double>(pnh, "tag_blur", 0.0)),
refine_edges_(getAprilTagOption<int>(pnh, "tag_refine_edges", 1)),
debug_(getAprilTagOption<int>(pnh, "tag_debug", 0)),
publish_tf_(getAprilTagOption<bool>(pnh, "publish_tf", false))
publish_tf_(getAprilTagOption<bool>(pnh, "publish_tf", false)),
max_hamming_distance_(getAprilTagOption<int>(pnh, "max_hamming_dist", 2))
{
// Parse standalone tag descriptions specified by user (stored on ROS
// parameter server)
Expand Down Expand Up @@ -146,7 +147,7 @@ TagDetector::TagDetector(ros::NodeHandle pnh) :

// Create the AprilTag 2 detector
td_ = apriltag_detector_create();
apriltag_detector_add_family(td_, tf_);
apriltag_detector_add_family_bits(td_, tf_, max_hamming_distance_);
td_->quad_decimate = (float)decimate_;
td_->quad_sigma = (float)blur_;
td_->nthreads = threads_;
Expand Down

0 comments on commit 4793e17

Please sign in to comment.