Go to the documentation of this file.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 #include<costmap_2d/costmap_math.h>
00031 #include <boost/tokenizer.hpp>
00032 #include <boost/foreach.hpp>
00033 #include <boost/algorithm/string.hpp>
00034 #include <costmap_2d/footprint.h>
00035 #include<geometry_msgs/Point32.h>
00036
00037 namespace costmap_2d
00038 {
00039
00040 void calculateMinAndMaxDistances(const std::vector<geometry_msgs::Point>& footprint, double& min_dist, double& max_dist)
00041 {
00042 min_dist = std::numeric_limits<double>::max();
00043 max_dist = 0.0;
00044
00045 if (footprint.size() <= 2)
00046 {
00047 return;
00048 }
00049
00050 for (unsigned int i = 0; i < footprint.size() - 1; ++i)
00051 {
00052
00053 double vertex_dist = distance(0.0, 0.0, footprint[i].x, footprint[i].y);
00054 double edge_dist = distanceToLine(0.0, 0.0, footprint[i].x, footprint[i].y,
00055 footprint[i + 1].x, footprint[i + 1].y);
00056 min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
00057 max_dist = std::max(max_dist, std::max(vertex_dist, edge_dist));
00058 }
00059
00060
00061 double vertex_dist = distance(0.0, 0.0, footprint.back().x, footprint.back().y);
00062 double edge_dist = distanceToLine(0.0, 0.0, footprint.back().x, footprint.back().y,
00063 footprint.front().x, footprint.front().y);
00064 min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
00065 max_dist = std::max(max_dist, std::max(vertex_dist, edge_dist));
00066 }
00067
00068 geometry_msgs::Point32 toPoint32(geometry_msgs::Point pt)
00069 {
00070 geometry_msgs::Point32 point32;
00071 point32.x = pt.x;
00072 point32.y = pt.y;
00073 point32.z = pt.z;
00074 return point32;
00075 }
00076
00077 geometry_msgs::Point toPoint(geometry_msgs::Point32 pt)
00078 {
00079 geometry_msgs::Point point;
00080 point.x = pt.x;
00081 point.y = pt.y;
00082 point.z = pt.z;
00083 return point;
00084 }
00085
00086 geometry_msgs::Polygon toPolygon(std::vector<geometry_msgs::Point> pts)
00087 {
00088 geometry_msgs::Polygon polygon;
00089 for(int i=0;i<pts.size();i++){
00090 polygon.points.push_back( toPoint32(pts[i]) );
00091 }
00092 return polygon;
00093 }
00094
00095 std::vector<geometry_msgs::Point> toPointVector(geometry_msgs::Polygon polygon)
00096 {
00097 std::vector<geometry_msgs::Point> pts;
00098 for(int i=0;i<polygon.points.size();i++)
00099 {
00100 pts.push_back( toPoint(polygon.points[i] ) );
00101 }
00102 return pts;
00103 }
00104
00105 }
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Thu Aug 27 2015 14:06:55