/* * ROS wrapper for the ASIFT_matcher object. * Track an object described in the references in a RGBD stream and publish it's center. * @author : antoine.harle@etu.upmc.Fr * @see : ASIFT_matcher.cpp/.hpp, asift_match.launch */ #ifndef ROSMATCHER_HPP #define ROSMATCHER_HPP #include #include #include #include #include #include #include #include #include #include #include #include #include "ASIFT_matcher.hpp" typedef message_filters::sync_policies::ApproximateTime MySyncPolicy; enum MATCHER_STATUS{ MATCHER_STATUS_IDLE=0, MATCHER_STATUS_PROCESSING, MATCHER_STATUS_WAITING_INIT}; class ROS_matcher { protected: ros::NodeHandle _nh; //Publisher ROS ros::Publisher _center_pub; //Subscriber ROS // message_filters::Subscriber* info_sub; message_filters::Subscriber* _image_sub; message_filters::Subscriber* _pointcloud_sub; message_filters::Synchronizer* Timesync; //Matcher int _num_tilt, _filter_coeff; //Parameters of the ASIFT_matcher ASIFT_matcher matcher; //Matcher MATCHER_STATUS _status; //Matcher status std::string tracked_object; //Name of the tracked object. public: ROS_matcher(); ~ROS_matcher(); void cameraCallback(const sensor_msgs::Image::ConstPtr& image_msg, const sensor_msgs::PointCloud2::ConstPtr& pointcloud_msg); }; #endif