intersect_polygons.cpp
Go to the documentation of this file.
00001 /* 
00002  * Copyright (c) 2009, U.
00003  * All rights reserved.
00004  * 
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  * 
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  * 
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
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 // Procedure declarations 
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 // Procedures 
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   // Local iconic variables 
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   // Local iconic variables 
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 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


intersect_polys
Author(s): Ulrich F Klank
autogenerated on Thu May 23 2013 13:56:58