00001 // -*- coding: utf-8 -*- 00002 #include <opencv2/imgproc/imgproc.hpp> 00003 #include <sensor_msgs/PointCloud.h> 00004 #include <sensor_msgs/Image.h> 00005 00006 #include <list> 00007 #include <boost/shared_ptr.hpp> 00008 00009 #include <opencv_fitting/Poses2D.h> 00010 00012 class DetectEllipseNode 00013 { 00014 public: 00015 virtual ~DetectEllipseNode() {} 00016 00017 virtual void DetectEllipses(const sensor_msgs::ImageConstPtr& msg, 00018 opencv_fitting::Poses2D& ellipses) = 0; 00019 virtual void DetectCircles(const sensor_msgs::ImageConstPtr& msg, 00020 sensor_msgs::PointCloud& points) = 0; 00021 }; 00022 00023 typedef boost::shared_ptr<DetectEllipseNode> DetectEllipseNodePtr; 00024 00026 double fitEllipse( const cv::Mat& points, cv::RotatedRect& ellipse ); 00027 00029 void fitEllipseFromImage(cv::Mat& image, std::list<cv::RotatedRect>& ellipses); 00030 00032 DetectEllipseNodePtr CreateDetectEllipseNode();