footprint.h
Go to the documentation of this file.
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 COSTMAP_2D_FOOTPRINT_H
39 #define COSTMAP_2D_FOOTPRINT_H
40 
41 #include <ros/ros.h>
42 #include <geometry_msgs/Polygon.h>
43 #include <geometry_msgs/PolygonStamped.h>
44 #include <geometry_msgs/Point.h>
45 #include <geometry_msgs/Point32.h>
46 
47 namespace costmap_2d
48 {
49 
57 void calculateMinAndMaxDistances(const std::vector<geometry_msgs::Point>& footprint,
58  double& min_dist, double& max_dist);
59 
63 geometry_msgs::Point toPoint(geometry_msgs::Point32 pt);
64 
68 geometry_msgs::Point32 toPoint32(geometry_msgs::Point pt);
69 
73 geometry_msgs::Polygon toPolygon(std::vector<geometry_msgs::Point> pts);
74 
78 std::vector<geometry_msgs::Point> toPointVector(geometry_msgs::Polygon polygon);
79 
88 void transformFootprint(double x, double y, double theta, const std::vector<geometry_msgs::Point>& footprint_spec,
89  std::vector<geometry_msgs::Point>& oriented_footprint);
90 
99 void transformFootprint(double x, double y, double theta, const std::vector<geometry_msgs::Point>& footprint_spec,
100  geometry_msgs::PolygonStamped & oriented_footprint);
101 
105 void padFootprint(std::vector<geometry_msgs::Point>& footprint, double padding);
106 
110 std::vector<geometry_msgs::Point> makeFootprintFromRadius(double radius);
111 
118 bool makeFootprintFromString(const std::string& footprint_string, std::vector<geometry_msgs::Point>& footprint);
119 
124 std::vector<geometry_msgs::Point> makeFootprintFromParams(ros::NodeHandle& nh);
125 
137 std::vector<geometry_msgs::Point> makeFootprintFromXMLRPC(XmlRpc::XmlRpcValue& footprint_xmlrpc,
138  const std::string& full_param_name);
139 
143 void writeFootprintToParam(ros::NodeHandle& nh, const std::vector<geometry_msgs::Point>& footprint);
144 
145 } // end namespace costmap_2d
146 
147 #endif // COSTMAP_2D_FOOTPRINT_H
costmap_2d::padFootprint
void padFootprint(std::vector< geometry_msgs::Point > &footprint, double padding)
Adds the specified amount of padding to the footprint (in place)
Definition: footprint.cpp:138
costmap_2d::toPointVector
std::vector< geometry_msgs::Point > toPointVector(geometry_msgs::Polygon polygon)
Convert Polygon msg to vector of Points.
Definition: footprint.cpp:96
ros.h
costmap_2d::transformFootprint
void transformFootprint(double x, double y, double theta, const std::vector< geometry_msgs::Point > &footprint_spec, std::vector< geometry_msgs::Point > &oriented_footprint)
Given a pose and base footprint, build the oriented footprint of the robot (list of Points)
Definition: footprint.cpp:106
costmap_2d::makeFootprintFromParams
std::vector< geometry_msgs::Point > makeFootprintFromParams(ros::NodeHandle &nh)
Read the ros-params "footprint" and/or "robot_radius" from the given NodeHandle using searchParam() t...
Definition: footprint.cpp:212
costmap_2d::makeFootprintFromXMLRPC
std::vector< geometry_msgs::Point > makeFootprintFromXMLRPC(XmlRpc::XmlRpcValue &footprint_xmlrpc, const std::string &full_param_name)
Create the footprint from the given XmlRpcValue.
costmap_2d::calculateMinAndMaxDistances
void calculateMinAndMaxDistances(const std::vector< geometry_msgs::Point > &footprint, double &min_dist, double &max_dist)
Calculate the extreme distances for the footprint.
Definition: footprint.cpp:41
costmap_2d::writeFootprintToParam
void writeFootprintToParam(ros::NodeHandle &nh, const std::vector< geometry_msgs::Point > &footprint)
Write the current unpadded_footprint_ to the "footprint" parameter of the given NodeHandle so that dy...
Definition: footprint.cpp:252
costmap_2d::makeFootprintFromString
bool makeFootprintFromString(const std::string &footprint_string, std::vector< geometry_msgs::Point > &footprint)
Make the footprint from the given string.
Definition: footprint.cpp:170
costmap_2d::makeFootprintFromRadius
std::vector< geometry_msgs::Point > makeFootprintFromRadius(double radius)
Create a circular footprint from a given radius.
Definition: footprint.cpp:150
costmap_2d::toPoint32
geometry_msgs::Point32 toPoint32(geometry_msgs::Point pt)
Convert Point to Point32.
Definition: footprint.cpp:69
costmap_2d::toPoint
geometry_msgs::Point toPoint(geometry_msgs::Point32 pt)
Convert Point32 to Point.
Definition: footprint.cpp:78
costmap_2d
Definition: array_parser.h:37
XmlRpc::XmlRpcValue
ros::NodeHandle
costmap_2d::toPolygon
geometry_msgs::Polygon toPolygon(std::vector< geometry_msgs::Point > pts)
Convert vector of Points to Polygon msg.
Definition: footprint.cpp:87


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17