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

Tag family parameter #8

Merged
merged 1 commit into from
Jul 6, 2016
Merged
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
7 changes: 5 additions & 2 deletions apriltags_ros/launch/example.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,13 @@
<!-- Remap topic required by the node to custom topics -->
<remap from="image_rect" to="image_rect" />
<remap from="camera_info" to="camera_info" />

<!-- Optional: Subscribe to the compressed stream-->
<param name="image_transport" type="str" value="compressed" />


<!-- Select the tag family: 16h5, 25h7, 25h9, 36h9, or 36h11(default) -->
<param name="tag_family" type="str" value="36h11" />

<!-- Describe the tags -->
<rosparam param="tag_descriptions">[
{id: 0, size: 0.163513},
Expand Down
27 changes: 25 additions & 2 deletions apriltags_ros/src/apriltag_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,31 @@ AprilTagDetector::AprilTagDetector(ros::NodeHandle& nh, ros::NodeHandle& pnh): i
sensor_frame_id_ = "";
}

AprilTags::TagCodes tag_codes = AprilTags::tagCodes36h11;
tag_detector_= boost::shared_ptr<AprilTags::TagDetector>(new AprilTags::TagDetector(tag_codes));
std::string tag_family;
pnh.param<std::string>("tag_family", tag_family, "36h11");

const AprilTags::TagCodes* tag_codes;
if(tag_family == "16h5"){
tag_codes = &AprilTags::tagCodes16h5;
}
else if(tag_family == "25h7"){
tag_codes = &AprilTags::tagCodes25h7;
}
else if(tag_family == "25h9"){
tag_codes = &AprilTags::tagCodes25h9;
}
else if(tag_family == "36h9"){
tag_codes = &AprilTags::tagCodes36h9;
}
else if(tag_family == "36h11"){
tag_codes = &AprilTags::tagCodes36h11;
}
else{
ROS_WARN("Invalid tag family specified; defaulting to 36h11");
tag_codes = &AprilTags::tagCodes36h11;
}

tag_detector_= boost::shared_ptr<AprilTags::TagDetector>(new AprilTags::TagDetector(*tag_codes));
image_sub_ = it_.subscribeCamera("image_rect", 1, &AprilTagDetector::imageCb, this);
image_pub_ = it_.advertise("tag_detections_image", 1);
detections_pub_ = nh.advertise<AprilTagDetectionArray>("tag_detections", 1);
Expand Down