Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
footprint.cpp
1 /*
2  * Copyright (c) 2013, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 #include "nav2_costmap_2d/footprint.hpp"
30 
31 #include <algorithm>
32 #include <limits>
33 #include <string>
34 #include <vector>
35 
36 #include "geometry_msgs/msg/point32.hpp"
37 #include "nav2_costmap_2d/array_parser.hpp"
38 #include "nav2_costmap_2d/costmap_math.hpp"
39 
40 namespace nav2_costmap_2d
41 {
42 
44  const std::vector<geometry_msgs::msg::Point> & footprint,
45  double & min_dist, double & max_dist)
46 {
47  min_dist = std::numeric_limits<double>::max();
48  max_dist = 0.0;
49 
50  if (footprint.size() <= 2) {
51  return;
52  }
53 
54  for (unsigned int i = 0; i < footprint.size() - 1; ++i) {
55  // check the distance from the robot center point to the first vertex
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));
62  }
63 
64  // we also need to do the last vertex and the first vertex
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));
71 }
72 
73 geometry_msgs::msg::Point32 toPoint32(geometry_msgs::msg::Point pt)
74 {
75  geometry_msgs::msg::Point32 point32;
76  point32.x = pt.x;
77  point32.y = pt.y;
78  point32.z = pt.z;
79  return point32;
80 }
81 
82 geometry_msgs::msg::Point toPoint(geometry_msgs::msg::Point32 pt)
83 {
84  geometry_msgs::msg::Point point;
85  point.x = pt.x;
86  point.y = pt.y;
87  point.z = pt.z;
88  return point;
89 }
90 
91 geometry_msgs::msg::Polygon toPolygon(std::vector<geometry_msgs::msg::Point> pts)
92 {
93  geometry_msgs::msg::Polygon polygon;
94  for (unsigned int i = 0; i < pts.size(); i++) {
95  polygon.points.push_back(toPoint32(pts[i]));
96  }
97  return polygon;
98 }
99 
100 std::vector<geometry_msgs::msg::Point> toPointVector(geometry_msgs::msg::Polygon::SharedPtr polygon)
101 {
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]));
105  }
106  return pts;
107 }
108 
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)
113 {
114  // build the oriented footprint at a given location
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];
122  new_pt.x = new_x;
123  new_pt.y = new_y;
124  }
125 }
126 
128  double x, double y, double theta,
129  const std::vector<geometry_msgs::msg::Point> & footprint_spec,
130  geometry_msgs::msg::PolygonStamped & oriented_footprint)
131 {
132  // build the oriented footprint at a given location
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);
141  }
142 }
143 
144 void padFootprint(std::vector<geometry_msgs::msg::Point> & footprint, double padding)
145 {
146  // pad footprint in place
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;
151  }
152 }
153 
154 
155 std::vector<geometry_msgs::msg::Point> makeFootprintFromRadius(double radius)
156 {
157  std::vector<geometry_msgs::msg::Point> points;
158 
159  // Loop over 16 angles around a circle making a point each time
160  int N = 16;
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;
166 
167  points.push_back(pt);
168  }
169 
170  return points;
171 }
172 
173 
175  const std::string & footprint_string,
176  std::vector<geometry_msgs::msg::Point> & footprint)
177 {
178  std::string error;
179  std::vector<std::vector<float>> vvf = parseVVF(footprint_string, error);
180 
181  if (error != "") {
182  RCLCPP_ERROR(
183  rclcpp::get_logger(
184  "nav2_costmap_2d"), "Error parsing footprint parameter: '%s'", error.c_str());
185  RCLCPP_ERROR(
186  rclcpp::get_logger(
187  "nav2_costmap_2d"), " Footprint string was '%s'.", footprint_string.c_str());
188  return false;
189  }
190 
191  // convert vvf into points.
192  if (vvf.size() < 3) {
193  RCLCPP_ERROR(
194  rclcpp::get_logger(
195  "nav2_costmap_2d"),
196  "You must specify at least three points for the robot footprint, reverting to previous footprint."); //NOLINT
197  return false;
198  }
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;
203  point.x = vvf[i][0];
204  point.y = vvf[i][1];
205  point.z = 0;
206  footprint.push_back(point);
207  } else {
208  RCLCPP_ERROR(
209  rclcpp::get_logger(
210  "nav2_costmap_2d"),
211  "Points in the footprint specification must be pairs of numbers. Found a point with %d numbers.", //NOLINT
212  static_cast<int>(vvf[i].size()));
213  return false;
214  }
215  }
216 
217  return true;
218 }
219 
220 } // end namespace nav2_costmap_2d
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)
Definition: footprint.cpp:109
bool makeFootprintFromString(const std::string &footprint_string, std::vector< geometry_msgs::msg::Point > &footprint)
Make the footprint from the given string.
Definition: footprint.cpp:174
void calculateMinAndMaxDistances(const std::vector< geometry_msgs::msg::Point > &footprint, double &min_dist, double &max_dist)
Calculate the extreme distances for the footprint.
Definition: footprint.cpp:43
void padFootprint(std::vector< geometry_msgs::msg::Point > &footprint, double padding)
Adds the specified amount of padding to the footprint (in place)
Definition: footprint.cpp:144
std::vector< geometry_msgs::msg::Point > makeFootprintFromRadius(double radius)
Create a circular footprint from a given radius.
Definition: footprint.cpp:155
std::vector< geometry_msgs::msg::Point > toPointVector(geometry_msgs::msg::Polygon::SharedPtr polygon)
Convert Polygon msg to vector of Points.
Definition: footprint.cpp:100
geometry_msgs::msg::Point32 toPoint32(geometry_msgs::msg::Point pt)
Convert Point to Point32.
Definition: footprint.cpp:73
geometry_msgs::msg::Polygon toPolygon(std::vector< geometry_msgs::msg::Point > pts)
Convert vector of Points to Polygon msg.
Definition: footprint.cpp:91
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.
Definition: footprint.cpp:82