Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
footprint.hpp
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  * David V. Lu!!
37  *********************************************************************/
38 #ifndef NAV2_COSTMAP_2D__FOOTPRINT_HPP_
39 #define NAV2_COSTMAP_2D__FOOTPRINT_HPP_
40 
41 #include <string>
42 #include <vector>
43 
44 #include "rclcpp/rclcpp.hpp"
45 #include "geometry_msgs/msg/polygon.hpp"
46 #include "geometry_msgs/msg/polygon_stamped.hpp"
47 #include "geometry_msgs/msg/point.hpp"
48 #include "geometry_msgs/msg/point32.hpp"
49 #include "nav2_util/lifecycle_node.hpp"
50 
51 namespace nav2_costmap_2d
52 {
53 
62  const std::vector<geometry_msgs::msg::Point> & footprint,
63  double & min_dist, double & max_dist);
64 
68 geometry_msgs::msg::Point toPoint(geometry_msgs::msg::Point32 pt);
69 
73 geometry_msgs::msg::Point32 toPoint32(geometry_msgs::msg::Point pt);
74 
78 geometry_msgs::msg::Polygon toPolygon(std::vector<geometry_msgs::msg::Point> pts);
79 
83 std::vector<geometry_msgs::msg::Point> toPointVector(
84  geometry_msgs::msg::Polygon::SharedPtr polygon);
85 
95  double x, double y, double theta,
96  const std::vector<geometry_msgs::msg::Point> & footprint_spec,
97  std::vector<geometry_msgs::msg::Point> & oriented_footprint);
98 
107 void transformFootprint(
108  double x, double y, double theta,
109  const std::vector<geometry_msgs::msg::Point> & footprint_spec,
110  geometry_msgs::msg::PolygonStamped & oriented_footprint);
111 
115 void padFootprint(std::vector<geometry_msgs::msg::Point> & footprint, double padding);
116 
120 std::vector<geometry_msgs::msg::Point> makeFootprintFromRadius(double radius);
121 
129  const std::string & footprint_string,
130  std::vector<geometry_msgs::msg::Point> & footprint);
131 
132 } // end namespace nav2_costmap_2d
133 
134 #endif // NAV2_COSTMAP_2D__FOOTPRINT_HPP_
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
geometry_msgs::msg::Point toPoint(geometry_msgs::msg::Point32 pt)
Convert Point32 to Point.
Definition: footprint.cpp:82