00001 #include <face_contour_detector/filters/EdgeConnector.h> 00002 #include <string> 00003 #include <ros/ros.h> 00004 #include <face_contour_detector/EdgeConnector.h> 00005 #include <cv_bridge/CvBridge.h> 00006 00007 namespace face_contour_detector { 00008 namespace filters { 00009 00010 EdgeConnector::EdgeConnector(ros::NodeHandle& node) { 00011 ResetParameters(); 00012 m_client = node.serviceClient<face_contour_detector::EdgeConnector>("connect_edges"); 00013 00014 } 00015 00016 std::vector<Parameter> EdgeConnector::GetParameters() { 00017 std::vector<Parameter> re; 00018 std::string name("searchRadius"); 00019 re.push_back(Parameter(name, &m_searchRadius)); 00020 return re; 00021 } 00022 00023 void EdgeConnector::Apply(const cv::Mat& input, cv::Mat& result) { 00024 face_contour_detector::EdgeConnector srv; 00025 IplImage ipl = input; 00026 srv.request.input_image = *m_cvBridge.cvToImgMsg(&ipl, "mono8"); 00027 srv.request.search_radius = m_searchRadius; 00028 00029 if (m_client.call(srv)) { 00030 if (m_cvBridge.fromImage(srv.response.output_image, "mono8")) { 00031 result = cv::Mat(m_cvBridge.toIpl(), true); 00032 } 00033 00034 std::cout<<result.type()<<std::endl; 00035 } else { 00036 ROS_ERROR("Failed to call service contour_detector"); 00037 result = input; 00038 } 00039 } 00040 00041 void EdgeConnector::ResetParameters() { 00042 m_searchRadius = 2; 00043 } 00044 00045 const std::string& EdgeConnector::GetFilterName() { 00046 return m_filterName; 00047 } 00048 00049 //static 00050 std::string EdgeConnector::m_filterName = std::string("EdgeConnector"); 00051 } //namespace filters 00052 } //namespace face_contour_detector