apriltag_detector.h
Go to the documentation of this file.
00001 #ifndef APRILTAG_DETECTOR_H
00002 #define APRILTAG_DETECTOR_H
00003 
00004 #include <ros/ros.h>
00005 #include <image_transport/image_transport.h>
00006 
00007 #include <AprilTags/TagDetector.h>
00008 #include <tf/transform_broadcaster.h>
00009 
00010 namespace apriltags_ros{
00011 
00012 
00013 class AprilTagDescription{
00014  public:
00015   AprilTagDescription(int id, double size, std::string &frame_name):id_(id), size_(size), frame_name_(frame_name){}
00016   double size(){return size_;}
00017   int id(){return id_;} 
00018   std::string& frame_name(){return frame_name_;} 
00019  private:
00020   int id_;
00021   double size_;
00022   std::string frame_name_;
00023 };
00024 
00025 
00026 class AprilTagDetector{
00027  public:
00028   AprilTagDetector(ros::NodeHandle& nh, ros::NodeHandle& pnh);
00029   ~AprilTagDetector();
00030  private:
00031   void imageCb(const sensor_msgs::ImageConstPtr& msg,const sensor_msgs::CameraInfoConstPtr& cam_info);
00032   std::map<int, AprilTagDescription> parse_tag_descriptions(XmlRpc::XmlRpcValue& april_tag_descriptions);
00033 
00034  private:
00035   std::map<int, AprilTagDescription> descriptions_;
00036   std::string sensor_frame_id_;
00037   image_transport::ImageTransport it_;
00038   image_transport::CameraSubscriber image_sub_;
00039   image_transport::Publisher image_pub_;
00040   ros::Publisher detections_pub_;
00041   ros::Publisher pose_pub_;
00042   tf::TransformBroadcaster tf_pub_;
00043   boost::shared_ptr<AprilTags::TagDetector> tag_detector_;
00044 };
00045 
00046 
00047 
00048 }
00049 
00050 
00051 #endif


apriltags_ros
Author(s): Mitchell Wills
autogenerated on Thu Aug 27 2015 12:23:32