31 #include <boost/tokenizer.hpp>
32 #include <boost/foreach.hpp>
33 #include <boost/algorithm/string.hpp>
36 #include<geometry_msgs/Point32.h>
43 min_dist = std::numeric_limits<double>::max();
46 if (footprint.size() <= 2)
51 for (
unsigned int i = 0; i < footprint.size() - 1; ++i)
54 double vertex_dist =
distance(0.0, 0.0, footprint[i].x, footprint[i].y);
55 double edge_dist =
distanceToLine(0.0, 0.0, footprint[i].x, footprint[i].y,
56 footprint[i + 1].x, footprint[i + 1].y);
57 min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
58 max_dist = std::max(max_dist, std::max(vertex_dist, edge_dist));
62 double vertex_dist =
distance(0.0, 0.0, footprint.back().x, footprint.back().y);
63 double edge_dist =
distanceToLine(0.0, 0.0, footprint.back().x, footprint.back().y,
64 footprint.front().x, footprint.front().y);
65 min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
66 max_dist = std::max(max_dist, std::max(vertex_dist, edge_dist));
69 geometry_msgs::Point32
toPoint32(geometry_msgs::Point pt)
71 geometry_msgs::Point32 point32;
78 geometry_msgs::Point
toPoint(geometry_msgs::Point32 pt)
80 geometry_msgs::Point point;
87 geometry_msgs::Polygon
toPolygon(std::vector<geometry_msgs::Point> pts)
89 geometry_msgs::Polygon polygon;
90 for (
int i = 0; i < pts.size(); i++){
91 polygon.points.push_back(
toPoint32(pts[i]));
96 std::vector<geometry_msgs::Point>
toPointVector(geometry_msgs::Polygon polygon)
98 std::vector<geometry_msgs::Point> pts;
99 for (
int i = 0; i < polygon.points.size(); i++)
101 pts.push_back(
toPoint(polygon.points[i]));
106 void transformFootprint(
double x,
double y,
double theta,
const std::vector<geometry_msgs::Point>& footprint_spec,
107 std::vector<geometry_msgs::Point>& oriented_footprint)
110 oriented_footprint.clear();
111 double cos_th = cos(theta);
112 double sin_th = sin(theta);
113 for (
unsigned int i = 0; i < footprint_spec.size(); ++i)
115 geometry_msgs::Point new_pt;
116 new_pt.x = x + (footprint_spec[i].x * cos_th - footprint_spec[i].y * sin_th);
117 new_pt.y = y + (footprint_spec[i].x * sin_th + footprint_spec[i].y * cos_th);
118 oriented_footprint.push_back(new_pt);
122 void transformFootprint(
double x,
double y,
double theta,
const std::vector<geometry_msgs::Point>& footprint_spec,
123 geometry_msgs::PolygonStamped& oriented_footprint)
126 oriented_footprint.polygon.points.clear();
127 double cos_th = cos(theta);
128 double sin_th = sin(theta);
129 for (
unsigned int i = 0; i < footprint_spec.size(); ++i)
131 geometry_msgs::Point32 new_pt;
132 new_pt.x = x + (footprint_spec[i].x * cos_th - footprint_spec[i].y * sin_th);
133 new_pt.y = y + (footprint_spec[i].x * sin_th + footprint_spec[i].y * cos_th);
134 oriented_footprint.polygon.points.push_back(new_pt);
138 void padFootprint(std::vector<geometry_msgs::Point>& footprint,
double padding)
141 for (
unsigned int i = 0; i < footprint.size(); i++)
143 geometry_msgs::Point& pt = footprint[ i ];
144 pt.x +=
sign0(pt.x) * padding;
145 pt.y +=
sign0(pt.y) * padding;
152 std::vector<geometry_msgs::Point> points;
156 geometry_msgs::Point pt;
157 for (
int i = 0; i < N; ++i)
159 double angle = i * 2 * M_PI / N;
160 pt.x = cos(
angle) * radius;
161 pt.y = sin(
angle) * radius;
163 points.push_back(pt);
173 std::vector<std::vector<float> > vvf =
parseVVF(footprint_string, error);
177 ROS_ERROR(
"Error parsing footprint parameter: '%s'", error.c_str());
178 ROS_ERROR(
" Footprint string was '%s'.", footprint_string.c_str());
185 ROS_ERROR(
"You must specify at least three points for the robot footprint, reverting to previous footprint.");
188 footprint.reserve(vvf.size());
189 for (
unsigned int i = 0; i < vvf.size(); i++)
191 if (vvf[ i ].size() == 2)
193 geometry_msgs::Point point;
194 point.x = vvf[ i ][ 0 ];
195 point.y = vvf[ i ][ 1 ];
197 footprint.push_back(point);
201 ROS_ERROR(
"Points in the footprint specification must be pairs of numbers. Found a point with %d numbers.",
202 int(vvf[ i ].size()));
214 std::string full_param_name;
215 std::string full_radius_param_name;
216 std::vector<geometry_msgs::Point> points;
221 nh.
getParam(full_param_name, footprint_xmlrpc);
223 footprint_xmlrpc !=
"" && footprint_xmlrpc !=
"[]")
239 if (nh.
searchParam(
"robot_radius", full_radius_param_name))
242 nh.
param(full_radius_param_name, robot_radius, 1.234);
244 nh.
setParam(
"robot_radius", robot_radius);
254 std::ostringstream oss;
256 for (
unsigned int i = 0; i < footprint.size(); i++)
258 geometry_msgs::Point p = footprint[ i ];
261 oss <<
"[[" << p.x <<
"," << p.y <<
"]";
266 oss <<
",[" << p.x <<
"," << p.y <<
"]";
270 nh.
setParam(
"footprint", oss.str().c_str());
279 std::string& value_string = value;
280 ROS_FATAL(
"Values in the footprint specification (param %s) must be numbers. Found value %s.",
281 full_param_name.c_str(), value_string.c_str());
282 throw std::runtime_error(
"Values in the footprint specification must be numbers");
288 const std::string& full_param_name)
292 footprint_xmlrpc.
size() < 3)
294 ROS_FATAL(
"The footprint must be specified as list of lists on the parameter server, %s was specified as %s",
295 full_param_name.c_str(), std::string(footprint_xmlrpc).c_str());
296 throw std::runtime_error(
"The footprint must be specified as list of lists on the parameter server with at least "
297 "3 points eg: [[x1, y1], [x2, y2], ..., [xn, yn]]");
300 std::vector<geometry_msgs::Point> footprint;
301 geometry_msgs::Point pt;
303 for (
int i = 0; i < footprint_xmlrpc.
size(); ++i)
310 ROS_FATAL(
"The footprint (parameter %s) must be specified as list of lists on the parameter server eg: "
311 "[[x1, y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form.",
312 full_param_name.c_str());
313 throw std::runtime_error(
"The footprint must be specified as list of lists on the parameter server eg: "
314 "[[x1, y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form");
317 pt.x = getNumberFromXMLRPC(point[ 0 ], full_param_name);
318 pt.y = getNumberFromXMLRPC(point[ 1 ], full_param_name);
320 footprint.push_back(pt);