Go to the documentation of this file.00001
00002
00003 #include <ros/ros.h>
00004
00005 #include <opencv/cv.h>
00006 #include <opencv/highgui.h>
00007 #include <sensor_msgs/Image.h>
00008 #include <cv_bridge/CvBridge.h>
00009 #include <image_transport/image_transport.h>
00010
00011
00012 #include <face_contour_detector/GetFilters.h>
00013 #include <face_contour_detector/ApplyFilters.h>
00014
00015
00016 #include <face_contour_detector/filters/List.h>
00017 #include <face_contour_detector/filters/Canny.h>
00018 #include <face_contour_detector/filters/ColorGraphs.h>
00019 #include <face_contour_detector/filters/DeleteShortLines.h>
00020 #include <face_contour_detector/filters/EdgeConnectorGraphBased.h>
00021 #include <face_contour_detector/filters/GaussianBlur.h>
00022 #include <face_contour_detector/filters/RosServices.h>
00023
00024
00025 #include <vector>
00026
00027
00029 int main(int argc, char* argv[]) {
00030
00031 ros::init(argc, argv, "filter_services");
00032 ros::NodeHandle n;
00033
00034 face_contour_detector::filters::RosServices services;
00035 services.AddFilter("GaussianBlur", new face_contour_detector::filters::GaussianBlur());
00036 services.AddFilter("Canny", new face_contour_detector::filters::Canny());
00037 services.AddFilter("EdgeConnector", new face_contour_detector::filters::EdgeConnectorGraphBased());
00038 services.AddFilter("DeleteShortLines", new face_contour_detector::filters::DeleteShortLines());
00039
00040 ros::ServiceServer getService = n.advertiseService("get_filters", &face_contour_detector::filters::RosServices::HandleGetRequest, &services);
00041 ros::ServiceServer applyService = n.advertiseService("apply_filters", &face_contour_detector::filters::RosServices::HandleApplyRequest, &services);
00042 ROS_INFO("filter services ready");
00043
00044 ros::spin();
00045
00046 return 0;
00047
00048 }