29 #include "nav2_costmap_2d/footprint.hpp"
36 #include "geometry_msgs/msg/point32.hpp"
37 #include "nav2_util/array_parser.hpp"
38 #include "nav2_costmap_2d/costmap_math.hpp"
44 const std::vector<geometry_msgs::msg::Point> & footprint)
46 double min_dist = std::numeric_limits<double>::max();
47 double max_dist = 0.0;
49 if (footprint.size() <= 2) {
50 return std::pair<double, double>(min_dist, max_dist);
53 for (
unsigned int i = 0; i < footprint.size() - 1; ++i) {
55 double vertex_dist = distance(0.0, 0.0, footprint[i].x, footprint[i].y);
56 double edge_dist = distanceToLine(
57 0.0, 0.0, footprint[i].x, footprint[i].y,
58 footprint[i + 1].x, footprint[i + 1].y);
59 min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
60 max_dist = std::max(max_dist, std::max(vertex_dist, edge_dist));
64 double vertex_dist = distance(0.0, 0.0, footprint.back().x, footprint.back().y);
65 double edge_dist = distanceToLine(
66 0.0, 0.0, footprint.back().x, footprint.back().y,
67 footprint.front().x, footprint.front().y);
68 min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
69 max_dist = std::max(max_dist, std::max(vertex_dist, edge_dist));
71 return std::pair<double, double>(min_dist, max_dist);
74 geometry_msgs::msg::Point32
toPoint32(geometry_msgs::msg::Point pt)
76 geometry_msgs::msg::Point32 point32;
83 geometry_msgs::msg::Point
toPoint(geometry_msgs::msg::Point32 pt)
85 geometry_msgs::msg::Point point;
92 geometry_msgs::msg::Polygon
toPolygon(std::vector<geometry_msgs::msg::Point> pts)
94 geometry_msgs::msg::Polygon polygon;
95 for (
unsigned int i = 0; i < pts.size(); i++) {
96 polygon.points.push_back(
toPoint32(pts[i]));
101 std::vector<geometry_msgs::msg::Point>
toPointVector(geometry_msgs::msg::Polygon::SharedPtr polygon)
103 std::vector<geometry_msgs::msg::Point> pts;
104 for (
unsigned int i = 0; i < polygon->points.size(); i++) {
105 pts.push_back(
toPoint(polygon->points[i]));
111 double x,
double y,
double theta,
112 const std::vector<geometry_msgs::msg::Point> & footprint_spec,
113 std::vector<geometry_msgs::msg::Point> & oriented_footprint)
116 oriented_footprint.resize(footprint_spec.size());
117 double cos_th = cos(theta);
118 double sin_th = sin(theta);
119 for (
unsigned int i = 0; i < footprint_spec.size(); ++i) {
120 double new_x = x + (footprint_spec[i].x * cos_th - footprint_spec[i].y * sin_th);
121 double new_y = y + (footprint_spec[i].x * sin_th + footprint_spec[i].y * cos_th);
122 geometry_msgs::msg::Point & new_pt = oriented_footprint[i];
129 double x,
double y,
double theta,
130 const std::vector<geometry_msgs::msg::Point> & footprint_spec,
131 geometry_msgs::msg::PolygonStamped & oriented_footprint)
134 oriented_footprint.polygon.points.clear();
135 double cos_th = cos(theta);
136 double sin_th = sin(theta);
137 for (
unsigned int i = 0; i < footprint_spec.size(); ++i) {
138 geometry_msgs::msg::Point32 new_pt;
139 new_pt.x = x + (footprint_spec[i].x * cos_th - footprint_spec[i].y * sin_th);
140 new_pt.y = y + (footprint_spec[i].x * sin_th + footprint_spec[i].y * cos_th);
141 oriented_footprint.polygon.points.push_back(new_pt);
145 void padFootprint(std::vector<geometry_msgs::msg::Point> & footprint,
double padding)
148 for (
unsigned int i = 0; i < footprint.size(); i++) {
149 geometry_msgs::msg::Point & pt = footprint[i];
150 pt.x += sign0(pt.x) * padding;
151 pt.y += sign0(pt.y) * padding;
158 std::vector<geometry_msgs::msg::Point> points;
162 geometry_msgs::msg::Point pt;
163 for (
int i = 0; i < N; ++i) {
164 double angle = i * 2 * M_PI / N;
165 pt.x = cos(angle) * radius;
166 pt.y = sin(angle) * radius;
168 points.push_back(pt);
176 const std::string & footprint_string,
177 std::vector<geometry_msgs::msg::Point> & footprint)
180 std::vector<std::vector<float>> vvf = nav2_util::parseVVF(footprint_string, error);
185 "nav2_costmap_2d"),
"Error parsing footprint parameter: '%s'", error.c_str());
188 "nav2_costmap_2d"),
" Footprint string was '%s'.", footprint_string.c_str());
193 if (vvf.size() < 3) {
197 "You must specify at least three points for the robot footprint,"
198 " reverting to previous footprint.");
201 footprint.reserve(vvf.size());
202 for (
unsigned int i = 0; i < vvf.size(); i++) {
203 if (vvf[i].size() == 2) {
204 geometry_msgs::msg::Point point;
208 footprint.push_back(point);
213 "Points in the footprint specification must be pairs of numbers."
214 " Found a point with %d numbers.",
215 static_cast<int>(vvf[i].size()));
void transformFootprint(double x, double y, double theta, const std::vector< geometry_msgs::msg::Point > &footprint_spec, std::vector< geometry_msgs::msg::Point > &oriented_footprint)
Given a pose and base footprint, build the oriented footprint of the robot (list of Points)
bool makeFootprintFromString(const std::string &footprint_string, std::vector< geometry_msgs::msg::Point > &footprint)
Make the footprint from the given string.
std::pair< double, double > calculateMinAndMaxDistances(const std::vector< geometry_msgs::msg::Point > &footprint)
Calculate the extreme distances for the footprint.
void padFootprint(std::vector< geometry_msgs::msg::Point > &footprint, double padding)
Adds the specified amount of padding to the footprint (in place)
std::vector< geometry_msgs::msg::Point > makeFootprintFromRadius(double radius)
Create a circular footprint from a given radius.
std::vector< geometry_msgs::msg::Point > toPointVector(geometry_msgs::msg::Polygon::SharedPtr polygon)
Convert Polygon msg to vector of Points.
geometry_msgs::msg::Point32 toPoint32(geometry_msgs::msg::Point pt)
Convert Point to Point32.
geometry_msgs::msg::Polygon toPolygon(std::vector< geometry_msgs::msg::Point > pts)
Convert vector of Points to Polygon msg.
geometry_msgs::msg::Point toPoint(geometry_msgs::msg::Point32 pt)
Convert Point32 to Point.