snake_geometry.cpp 7.69 KB
Newer Older
1 2 3 4 5 6 7 8
#include "snake_geometry.h"
#include <mapbox/polylabel.hpp>
#include <mapbox/geometry.hpp>

#include <boost/geometry.hpp>
#include <boost/geometry/geometries/polygon.hpp>
#include <boost/geometry/geometries/adapted/boost_tuple.hpp>

Valentin Platzgummer's avatar
Valentin Platzgummer committed
9 10 11 12

#include <GeographicLib/Geocentric.hpp>
#include <GeographicLib/LocalCartesian.hpp>

13
using namespace mapbox;
Valentin Platzgummer's avatar
Valentin Platzgummer committed
14 15
using namespace snake_geometry;
using namespace std;
16 17 18 19 20 21

BOOST_GEOMETRY_REGISTER_BOOST_TUPLE_CS(cs::cartesian)


namespace snake_geometry {

Valentin Platzgummer's avatar
Valentin Platzgummer committed
22
Point3D toENU(const GeoPoint3D &WGS84Reference, const GeoPoint3D &WGS84Position)
23
{
Valentin Platzgummer's avatar
Valentin Platzgummer committed
24 25
    GeographicLib::Geocentric earth(GeographicLib::Constants::WGS84_a(), GeographicLib::Constants::WGS84_f());
    GeographicLib::LocalCartesian proj(WGS84Reference[0], WGS84Reference[1], WGS84Reference[2], earth);
26

Valentin Platzgummer's avatar
Valentin Platzgummer committed
27 28
    Point3D ENUPosition;
    proj.Forward(WGS84Position[0], WGS84Position[1], WGS84Position[2], ENUPosition[0], ENUPosition[1], ENUPosition[2]);
29 30 31
    return ENUPosition;
}

Valentin Platzgummer's avatar
Valentin Platzgummer committed
32
GeoPoint3D fromENU(const Point3D &WGS84Reference, const Point3D &CartesianPosition)
33
{
Valentin Platzgummer's avatar
Valentin Platzgummer committed
34 35
    GeographicLib::Geocentric earth(GeographicLib::Constants::WGS84_a(), GeographicLib::Constants::WGS84_f());
    GeographicLib::LocalCartesian proj(WGS84Reference[0], WGS84Reference[1], WGS84Reference[2], earth);
36

Valentin Platzgummer's avatar
Valentin Platzgummer committed
37 38 39
    GeoPoint3D GeoPosition;
    proj.Reverse(CartesianPosition[0], CartesianPosition[1], CartesianPosition[2], GeoPosition[0], GeoPosition[1], GeoPosition[2]);
    return GeoPosition;
40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116
}

Point2D polygonCenter(const Point2DList &polygon)
{
   geometry::polygon<double> p;
   geometry::linear_ring<double> lr1;
   for (size_t i = 0; i < polygon.size(); ++i) {
       geometry::point<double> vertex(polygon[i][0], polygon[i][1]);
       lr1.push_back(vertex);
   }
   p.push_back(lr1);
   geometry::point<double> center = polylabel(p);

   return Point2D{center.x, center.y};
}

min_bbox_rt minimalBoundingBox(const Point2DList &polygon)
{
    /*
    Find the minimum-area bounding box of a set of 2D points

    The input is a 2D convex hull, in an Nx2 numpy array of x-y co-ordinates.
    The first and last points points must be the same, making a closed polygon.
    This program finds the rotation angles of each edge of the convex polygon,
    then tests the area of a bounding box aligned with the unique angles in
    90 degrees of the 1st Quadrant.
    Returns the

    Tested with Python 2.6.5 on Ubuntu 10.04.4 (original version)
    Results verified using Matlab

    Copyright (c) 2013, David Butterworth, University of Queensland
    All rights reserved.

    Redistribution and use in source and binary forms, with or without
    modification, are permitted provided that the following conditions are met:

        * Redistributions of source code must retain the above copyright
          notice, this list of conditions and the following disclaimer.
        * Redistributions in binary form must reproduce the above copyright
          notice, this list of conditions and the following disclaimer in the
          documentation and/or other materials provided with the distribution.
        * Neither the name of the Willow Garage, Inc. nor the names of its
          contributors may be used to endorse or promote products derived from
          this software without specific prior written permission.

    THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
    AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
    IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
    ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
    LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
    CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
    SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
    INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
    CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
    ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
    POSSIBILITY OF SUCH DAMAGE.
    */

    typedef boost::tuple<double, double> point_t;
    typedef boost::geometry::model::polygon<point_t> poly_t;
    namespace trans = boost::geometry::strategy::transform;

    poly_t poly;
    for (auto vertex : polygon)
        poly.outer().push_back(point_t{vertex[0], vertex[1]});

    poly_t convex_hull;
    boost::geometry::convex_hull(poly, convex_hull);

    //hull_points_2d = array(convex_polygon[0])
    //# print "Input convex hull points: "
    //# print hull_points_2d

    //# Compute edges (x2-x1,y2-y1)
    std::vector<point_t> edges;
    auto convex_hull_outer = convex_hull.outer();
Valentin Platzgummer's avatar
Valentin Platzgummer committed
117
    for (size_t i=0; i < convex_hull_outer.size()-1; ++i) {
118 119 120 121 122 123 124 125 126 127 128 129 130 131 132
        point_t p1      = convex_hull_outer.at(i);
        point_t p2      = convex_hull_outer.at(i+1);
        double edge_x   = p2.get<0>() - p1.get<0>();
        double edge_y   = p2.get<1>() - p1.get<1>();
        edges.push_back(point_t{edge_x, edge_y});
    }
    // print "Edges: \n", edges

    // Calculate edge angles   atan2(y/x)
    std::set<double> edge_angles;
    for (auto vertex : edges)
        edge_angles.insert(std::fmod(atan2(vertex.get<1>(), vertex.get<0>()), M_PI / 2)); // want strictly positive answers
    //# print "Unique edge angles: \n", edge_angles


Valentin Platzgummer's avatar
Valentin Platzgummer committed
133
    min_bbox_rt min_bbox{0, 0, 0, {Point2D{0,0}}};
134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149
    double min_area = std::numeric_limits<double>::infinity();
    // Test each angle to find bounding box with smallest area
    // print "Testing", len(edge_angles), "possible rotations for bounding box... \n"
    for (double angle : edge_angles){

        trans::rotate_transformer<boost::geometry::degree, double, 2, 2> rotate(angle*180/M_PI);
        poly_t hull_rotated;
        boost::geometry::transform(convex_hull, hull_rotated, rotate);

        boost::geometry::model::box<point_t> box;
        boost::geometry::envelope(hull_rotated, box);

        //# print "Rotated hull points are \n", rot_points
        point_t min_corner = box.min_corner();
        point_t max_corner = box.max_corner();
        double min_x = min_corner.get<0>();
Valentin Platzgummer's avatar
Valentin Platzgummer committed
150 151
        double max_x = max_corner.get<0>();
        double min_y = min_corner.get<1>();
152 153 154 155 156 157 158 159 160 161 162 163 164 165 166
        double max_y = max_corner.get<1>();
        //# print "Min x:", min_x, " Max x: ", max_x, "   Min y:", min_y, " Max y: ", max_y

        // Calculate height/width/area of this bounding rectangle
        double width    = max_x - min_x;
        double height   = max_y - min_y;
        double area     = width * height;
        // print "Potential bounding box ", i, ":  width: ", width, " height: ", height, "  area: ", area

        // Store the smallest rect found first (a simple convex hull might have 2 answers with same area)
        if (area < min_area){
            min_bbox.angle  = angle;
            min_bbox.width  = width;
            min_bbox.height = height;

Valentin Platzgummer's avatar
Valentin Platzgummer committed
167 168 169 170
            min_bbox.corners = std::array<Point2D, 4>{Point2D{min_x, min_y},
                                                      Point2D{max_x, min_y},
                                                      Point2D{max_x, max_y},
                                                      Point2D{min_x, max_y}};
171 172 173
        }
    }

Valentin Platzgummer's avatar
Valentin Platzgummer committed
174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189

    // Transform corners of minimal bounding box.
    poly_t boost_polygon;
    for (auto vertex : min_bbox.corners){
        boost_polygon.outer().push_back(point_t{vertex[0], vertex[1]});
    }
    trans::rotate_transformer<boost::geometry::degree, double, 2, 2> rotate(-min_bbox.angle*180/M_PI);
    poly_t rotated_polygon;
    boost::geometry::transform(boost_polygon, rotated_polygon, rotate);

    for (size_t i = 0; i < 4; ++i){
        point_t boost_vertex{rotated_polygon.outer()[i]};
        min_bbox.corners[i] = Point2D{boost_vertex.get<0>(), boost_vertex.get<1>()};
    }


190 191
    return min_bbox;
}
Valentin Platzgummer's avatar
Valentin Platzgummer committed
192 193

} // end namespace snake_geometry