polygon.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2014-2017, the neonavigation authors
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 the copyright holder 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 #ifndef COSTMAP_CSPACE_POLYGON_H
00031 #define COSTMAP_CSPACE_POLYGON_H
00032 
00033 #include <ros/ros.h>
00034 #include <vector>
00035 
00036 #if ROS_DISTRO_indigo
00037 #include <XmlRpcException.h>
00038 #else
00039 #include <xmlrpcpp/XmlRpcException.h>
00040 #endif
00041 
00042 namespace costmap_cspace
00043 {
00044 class Vec
00045 {
00046 public:
00047   float c[2];
00048   float& operator[](const int& i)
00049   {
00050     ROS_ASSERT(i < 2);
00051     return c[i];
00052   }
00053   const float& operator[](const int& i) const
00054   {
00055     ROS_ASSERT(i < 2);
00056     return c[i];
00057   }
00058   Vec operator-(const Vec& a) const
00059   {
00060     Vec out = *this;
00061     out[0] -= a[0];
00062     out[1] -= a[1];
00063     return out;
00064   }
00065   float cross(const Vec& a) const
00066   {
00067     return (*this)[0] * a[1] - (*this)[1] * a[0];
00068   }
00069   float dot(const Vec& a) const
00070   {
00071     return (*this)[0] * a[0] + (*this)[1] * a[1];
00072   }
00073   float dist(const Vec& a) const
00074   {
00075     return hypotf((*this)[0] - a[0], (*this)[1] - a[1]);
00076   }
00077   float dist_line(const Vec& a, const Vec& b) const
00078   {
00079     return (b - a).cross((*this) - a) / b.dist(a);
00080   }
00081   float dist_linestrip(const Vec& a, const Vec& b) const
00082   {
00083     if ((b - a).dot((*this) - a) <= 0)
00084       return this->dist(a);
00085     if ((a - b).dot((*this) - b) <= 0)
00086       return this->dist(b);
00087     return fabs(this->dist_line(a, b));
00088   }
00089 };
00090 class Polygon
00091 {
00092 public:
00093   std::vector<Vec> v;
00094 
00095   Polygon()
00096   {
00097   }
00098   explicit Polygon(const XmlRpc::XmlRpcValue footprint_xml_const)
00099   {
00100     XmlRpc::XmlRpcValue footprint_xml = footprint_xml_const;
00101     if (footprint_xml.getType() != XmlRpc::XmlRpcValue::TypeArray || footprint_xml.size() < 3)
00102     {
00103       throw std::runtime_error("Invalid footprint xml.");
00104     }
00105 
00106     for (int i = 0; i < footprint_xml.size(); i++)
00107     {
00108       Vec p;
00109       try
00110       {
00111         p[0] = static_cast<double>(footprint_xml[i][0]);
00112         p[1] = static_cast<double>(footprint_xml[i][1]);
00113       }
00114       catch (XmlRpc::XmlRpcException& e)
00115       {
00116         throw std::runtime_error(("Invalid footprint xml." + e.getMessage()).c_str());
00117       }
00118 
00119       v.push_back(p);
00120     }
00121     v.push_back(v.front());
00122   }
00123   geometry_msgs::PolygonStamped toMsg() const
00124   {
00125     geometry_msgs::PolygonStamped msg;
00126 
00127     msg.polygon.points.clear();
00128     msg.header.frame_id = "base_link";
00129     for (const auto& p : v)
00130     {
00131       geometry_msgs::Point32 point;
00132       point.x = p[0];
00133       point.y = p[1];
00134       point.z = 0;
00135       msg.polygon.points.push_back(point);
00136     }
00137     msg.polygon.points.push_back(msg.polygon.points[0]);
00138 
00139     return msg;
00140   }
00141   float radius() const
00142   {
00143     float radius = 0;
00144     for (const auto& p : v)
00145     {
00146       const auto dist = hypotf(p[0], p[1]);
00147       if (dist > radius)
00148         radius = dist;
00149     }
00150     return radius;
00151   }
00152   void move(const float& x, const float& y, const float& yaw)
00153   {
00154     float cos_v = cosf(yaw);
00155     float sin_v = sinf(yaw);
00156     for (auto& p : v)
00157     {
00158       auto tmp = p;
00159       p[0] = cos_v * tmp[0] - sin_v * tmp[1] + x;
00160       p[1] = sin_v * tmp[0] + cos_v * tmp[1] + y;
00161     }
00162   }
00163   bool inside(const Vec& a) const
00164   {
00165     int cn = 0;
00166     for (size_t i = 0; i < v.size() - 1; i++)
00167     {
00168       auto& v1 = v[i];
00169       auto& v2 = v[i + 1];
00170       if ((v1[1] <= a[1] && a[1] < v2[1]) ||
00171           (v2[1] <= a[1] && a[1] < v1[1]))
00172       {
00173         float lx;
00174         lx = v1[0] + (v2[0] - v1[0]) * (a[1] - v1[1]) / (v2[1] - v1[1]);
00175         if (a[0] < lx)
00176           cn++;
00177       }
00178     }
00179     return ((cn & 1) == 1);
00180   }
00181   float dist(const Vec& a) const
00182   {
00183     float dist = FLT_MAX;
00184     for (size_t i = 0; i < v.size() - 1; i++)
00185     {
00186       auto& v1 = v[i];
00187       auto& v2 = v[i + 1];
00188       auto d = a.dist_linestrip(v1, v2);
00189       if (d < dist)
00190         dist = d;
00191     }
00192     return dist;
00193   }
00194 };
00195 }  // namespace costmap_cspace
00196 
00197 #endif  // COSTMAP_CSPACE_POLYGON_H


costmap_cspace
Author(s): Atsushi Watanabe
autogenerated on Sat Jun 22 2019 20:07:13