29 #include "nav2_costmap_2d/footprint.hpp"
36 #include "geometry_msgs/msg/point32.hpp"
37 #include "nav2_costmap_2d/array_parser.hpp"
38 #include "nav2_costmap_2d/costmap_math.hpp"
44 const std::vector<geometry_msgs::msg::Point> & footprint,
45 double & min_dist,
double & max_dist)
47 min_dist = std::numeric_limits<double>::max();
50 if (footprint.size() <= 2) {
54 for (
unsigned int i = 0; i < footprint.size() - 1; ++i) {
56 double vertex_dist = distance(0.0, 0.0, footprint[i].x, footprint[i].y);
57 double edge_dist = distanceToLine(
58 0.0, 0.0, footprint[i].x, footprint[i].y,
59 footprint[i + 1].x, footprint[i + 1].y);
60 min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
61 max_dist = std::max(max_dist, std::max(vertex_dist, edge_dist));
65 double vertex_dist = distance(0.0, 0.0, footprint.back().x, footprint.back().y);
66 double edge_dist = distanceToLine(
67 0.0, 0.0, footprint.back().x, footprint.back().y,
68 footprint.front().x, footprint.front().y);
69 min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
70 max_dist = std::max(max_dist, std::max(vertex_dist, edge_dist));
73 geometry_msgs::msg::Point32
toPoint32(geometry_msgs::msg::Point pt)
75 geometry_msgs::msg::Point32 point32;
82 geometry_msgs::msg::Point
toPoint(geometry_msgs::msg::Point32 pt)
84 geometry_msgs::msg::Point point;
91 geometry_msgs::msg::Polygon
toPolygon(std::vector<geometry_msgs::msg::Point> pts)
93 geometry_msgs::msg::Polygon polygon;
94 for (
unsigned int i = 0; i < pts.size(); i++) {
95 polygon.points.push_back(
toPoint32(pts[i]));
100 std::vector<geometry_msgs::msg::Point>
toPointVector(geometry_msgs::msg::Polygon::SharedPtr polygon)
102 std::vector<geometry_msgs::msg::Point> pts;
103 for (
unsigned int i = 0; i < polygon->points.size(); i++) {
104 pts.push_back(
toPoint(polygon->points[i]));
110 double x,
double y,
double theta,
111 const std::vector<geometry_msgs::msg::Point> & footprint_spec,
112 std::vector<geometry_msgs::msg::Point> & oriented_footprint)
115 oriented_footprint.resize(footprint_spec.size());
116 double cos_th = cos(theta);
117 double sin_th = sin(theta);
118 for (
unsigned int i = 0; i < footprint_spec.size(); ++i) {
119 double new_x = x + (footprint_spec[i].x * cos_th - footprint_spec[i].y * sin_th);
120 double new_y = y + (footprint_spec[i].x * sin_th + footprint_spec[i].y * cos_th);
121 geometry_msgs::msg::Point & new_pt = oriented_footprint[i];
128 double x,
double y,
double theta,
129 const std::vector<geometry_msgs::msg::Point> & footprint_spec,
130 geometry_msgs::msg::PolygonStamped & oriented_footprint)
133 oriented_footprint.polygon.points.clear();
134 double cos_th = cos(theta);
135 double sin_th = sin(theta);
136 for (
unsigned int i = 0; i < footprint_spec.size(); ++i) {
137 geometry_msgs::msg::Point32 new_pt;
138 new_pt.x = x + (footprint_spec[i].x * cos_th - footprint_spec[i].y * sin_th);
139 new_pt.y = y + (footprint_spec[i].x * sin_th + footprint_spec[i].y * cos_th);
140 oriented_footprint.polygon.points.push_back(new_pt);
144 void padFootprint(std::vector<geometry_msgs::msg::Point> & footprint,
double padding)
147 for (
unsigned int i = 0; i < footprint.size(); i++) {
148 geometry_msgs::msg::Point & pt = footprint[i];
149 pt.x += sign0(pt.x) * padding;
150 pt.y += sign0(pt.y) * padding;
157 std::vector<geometry_msgs::msg::Point> points;
161 geometry_msgs::msg::Point pt;
162 for (
int i = 0; i < N; ++i) {
163 double angle = i * 2 * M_PI / N;
164 pt.x = cos(angle) * radius;
165 pt.y = sin(angle) * radius;
167 points.push_back(pt);
175 const std::string & footprint_string,
176 std::vector<geometry_msgs::msg::Point> & footprint)
179 std::vector<std::vector<float>> vvf =
parseVVF(footprint_string, error);
184 "nav2_costmap_2d"),
"Error parsing footprint parameter: '%s'", error.c_str());
187 "nav2_costmap_2d"),
" Footprint string was '%s'.", footprint_string.c_str());
192 if (vvf.size() < 3) {
196 "You must specify at least three points for the robot footprint, reverting to previous footprint.");
199 footprint.reserve(vvf.size());
200 for (
unsigned int i = 0; i < vvf.size(); i++) {
201 if (vvf[i].size() == 2) {
202 geometry_msgs::msg::Point point;
206 footprint.push_back(point);
211 "Points in the footprint specification must be pairs of numbers. Found a point with %d numbers.",
212 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.
void calculateMinAndMaxDistances(const std::vector< geometry_msgs::msg::Point > &footprint, double &min_dist, double &max_dist)
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.
std::vector< std::vector< float > > parseVVF(const std::string &input, std::string &error_return)
Parse a vector of vectors of floats from a string.
geometry_msgs::msg::Point toPoint(geometry_msgs::msg::Point32 pt)
Convert Point32 to Point.