Skip to content

Commit

Permalink
reverted ROS2 parameters refine and debug back to int and renamed ref…
Browse files Browse the repository at this point in the history
…ine to refine-edges
  • Loading branch information
Mihail Valchev committed Sep 27, 2022
1 parent aa4614d commit 127d864
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 5 deletions.
3 changes: 2 additions & 1 deletion cfg/tags_36h11.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -11,9 +11,10 @@ apriltag:
threads: 1 # number of threads
decimate: 1.0 # decimate resolution for quad detection
blur: 0.0 # sigma of Gaussian blur for quad detection
refine: true # snap to strong gradients
refine-edges: true # snap to strong gradients
sharpening: 0.25 # sharpening of decoded images
debug: false # write additional debugging images to current working directory
refine-pose: false # increase the accuracy of the extracted pose

# optional list of tags
tag:
Expand Down
3 changes: 2 additions & 1 deletion launch/tag_36h11_all.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,8 @@
"family": "36h11",
"size": 0.162,
"max_hamming": 0,
"z_up": True
"z_up": True,
"refine-pose": False # increase the accuracy of the extracted pose
}

def generate_launch_description():
Expand Down
6 changes: 3 additions & 3 deletions src/AprilTagNode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -176,9 +176,9 @@ AprilTagNode::AprilTagNode(const rclcpp::NodeOptions& options)
declare_parameter("detector.threads", td->nthreads, descr("number of threads"));
declare_parameter("detector.decimate", td->quad_decimate, descr("decimate resolution for quad detection"));
declare_parameter("detector.blur", td->quad_sigma, descr("sigma of Gaussian blur for quad detection"));
declare_parameter<bool>("detector.refine", td->refine_edges, descr("snap to strong gradients"));
declare_parameter<int>("detector.refine-edges", td->refine_edges, descr("snap to strong gradients"));
declare_parameter("detector.sharpening", td->decode_sharpening, descr("sharpening of decoded images"));
declare_parameter<bool>("detector.debug", td->debug, descr("write additional debugging images to working directory"));
declare_parameter<int>("detector.debug", td->debug, descr("write additional debugging images to working directory"));

declare_parameter<int>("max_hamming", 0, descr("reject detections with more corrected bits than allowed"));
declare_parameter("profile", false, descr("print profiling information to stdout"));
Expand Down Expand Up @@ -290,7 +290,7 @@ AprilTagNode::onParameter(const std::vector<rclcpp::Parameter>& parameters)
IF("detector.threads", td->nthreads)
IF("detector.decimate", td->quad_decimate)
IF("detector.blur", td->quad_sigma)
IF("detector.refine", td->refine_edges)
IF("detector.refine-edges", td->refine_edges)
IF("detector.sharpening", td->decode_sharpening)
IF("detector.debug", td->debug)
IF("max_hamming", max_hamming)
Expand Down

0 comments on commit 127d864

Please sign in to comment.