00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #include "cpp/HalconCpp.h"
00035 #include "ros/ros.h"
00036 #include "vision_srvs/clip_polygon.h"
00037
00038
00039
00040 void intersect_poly (Halcon::HTuple X1, Halcon::HTuple Y1, Halcon::HTuple X2, Halcon::HTuple Y2,
00041 Halcon::HTuple *XOut, Halcon::HTuple *YOut);
00042 void merge_polys (Halcon::HTuple X1, Halcon::HTuple Y1, Halcon::HTuple X2, Halcon::HTuple Y2,
00043 Halcon::HTuple *XOut, Halcon::HTuple *YOut);
00044
00045 void intersect_poly (Halcon::HTuple X1, Halcon::HTuple Y1, Halcon::HTuple X2, Halcon::HTuple Y2,
00046 Halcon::HTuple *XOut, Halcon::HTuple *YOut)
00047 {
00048 using namespace Halcon;
00049
00050
00051 Hobject Contour, Contour2, ContoursIntersection;
00052
00053 gen_contour_polygon_xld(&Contour, X1, Y1);
00054 gen_contour_polygon_xld(&Contour2, X2, Y2);
00055 intersection_closed_contours_xld(Contour, Contour2, &ContoursIntersection);
00056 get_contour_xld(ContoursIntersection, &(*XOut), &(*YOut));
00057 return;
00058 }
00059
00060 void merge_polys (Halcon::HTuple X1, Halcon::HTuple Y1, Halcon::HTuple X2, Halcon::HTuple Y2,
00061 Halcon::HTuple *XOut, Halcon::HTuple *YOut)
00062 {
00063 using namespace Halcon;
00064
00065
00066 Hobject Contour, Contour2, ContoursIntersection;
00067
00068 gen_contour_polygon_xld(&Contour, X1, Y1);
00069 gen_contour_polygon_xld(&Contour2, X2, Y2);
00070 union2_closed_contours_xld(Contour, Contour2, &ContoursIntersection);
00071 get_contour_xld(ContoursIntersection, &(*XOut), &(*YOut));
00072 return;
00073 }
00074
00075 bool srvcallback(vision_srvs::clip_polygon::Request& req, vision_srvs::clip_polygon::Response& resp)
00076 {
00077 Halcon::HTuple x1,x2,y1, y2, xout, yout;
00078 for(int i = 0; i < req.poly1.points.size(); i++)
00079 {
00080 x1 = x1.Append(req.poly1.points[i].x);
00081 y1 = y1.Append(req.poly1.points[i].y);
00082 }
00083 for(int j = 0; j < req.poly2.points.size(); j++)
00084 {
00085 x2 = x2.Append(req.poly2.points[j].x);
00086 y2 = y2.Append(req.poly2.points[j].y);
00087 }
00088
00089 if (req.operation == req.UNION)
00090 merge_polys (x1, y1, x2, y2, &xout, &yout);
00091 else if (req.operation == req.INTERSECTION)
00092 intersect_poly (x1,y1, x2, y2, &xout, &yout);
00093
00094 for(int j = 0; j < yout.Num(); j++)
00095 {
00096 geometry_msgs::Point32 p;
00097 p.x = xout[j].D();
00098 p.y = yout[j].D();
00099 resp.poly_clip.points.push_back(p);
00100 }
00101 return true;
00102 }
00103
00104 int main(int argc, char* argv [])
00105 {
00106 ros::init( argc, argv, "intersect_polygons");
00107 ros::NodeHandle nh;
00108 ros::ServiceServer srv = nh.advertiseService("/intersect_poly", srvcallback);
00109
00110 while(true)
00111 {
00112 ros::spin();
00113 sleep(0.1);
00114 }
00115 }