$search
00001 #ifndef CHECKERBOARD_POSE_ESTIMATION_ROS_DETECTOR_H 00002 #define CHECKERBOARD_POSE_ESTIMATION_ROS_DETECTOR_H 00003 00004 #include <ros/ros.h> 00005 #include <image_transport/image_transport.h> 00006 #include <cv_bridge/CvBridge.h> 00007 #include <tf/tf.h> 00008 #include <tf/transform_broadcaster.h> 00009 #include <checkerboard_pose_estimation/detector.h> 00010 #include <checkerboard_pose_estimation/estimator.h> 00011 00012 namespace checkerboard_pose_estimation { 00013 00014 class RosDetector 00015 { 00016 public: 00017 RosDetector(const std::string& name = ros::this_node::getName()); 00018 00019 bool initFromParameters(const ros::NodeHandle& nh = ros::NodeHandle("~")); 00020 00021 Detector& getDetector() { return detector_; } 00022 const Detector& getDetector() const { return detector_; } 00023 00024 visual_pose_estimation::PoseEstimator& getPoseEstimator() { return pose_estimator_; } 00025 const visual_pose_estimation::PoseEstimator& getPoseEstimator() const { return pose_estimator_; } 00026 00027 // detected object = checkerboard, target = plug 00028 bool detectObject(const sensor_msgs::ImageConstPtr& image_msg, const sensor_msgs::CameraInfoConstPtr& info_msg, 00029 const tf::Stamped<tf::Pose>& target_prior, const tf::Transformer& transformer, 00030 tf::Stamped<tf::Pose>& target_pose); 00031 00032 void publishDisplayImage(const cv::Mat& source, const std::vector<cv::Point2f>& corners, bool success); 00033 00034 protected: 00035 ros::NodeHandle nh_; 00036 image_transport::ImageTransport it_; 00037 std::string name_; 00038 00039 // Publications 00040 tf::TransformBroadcaster tf_broadcaster_; 00041 image_transport::Publisher display_pub_; 00042 sensor_msgs::Image display_img_; 00043 cv::Mat display_img_cv_; 00044 ros::Publisher marker_pub_; 00045 00046 // Message processing 00047 sensor_msgs::CvBridge img_bridge_; 00048 image_geometry::PinholeCameraModel cam_model_; 00049 Detector detector_; 00050 visual_pose_estimation::PoseEstimator pose_estimator_; 00052 tf::Transform target_in_detected_object_; 00053 tf::Stamped<tf::Pose> target_prior_; 00054 }; 00055 00056 } //namespace checkerboard_pose_estimation 00057 00058 #endif