Namespaces | Functions
footprint.cpp File Reference
#include <costmap_2d/costmap_math.h>
#include <boost/tokenizer.hpp>
#include <boost/foreach.hpp>
#include <boost/algorithm/string.hpp>
#include <costmap_2d/footprint.h>
#include <costmap_2d/array_parser.h>
#include <geometry_msgs/Point32.h>
Include dependency graph for footprint.cpp:

Go to the source code of this file.

Namespaces

namespace  costmap_2d

Functions

void costmap_2d::calculateMinAndMaxDistances (const std::vector< geometry_msgs::Point > &footprint, double &min_dist, double &max_dist)
 Calculate the extreme distances for the footprint.
double costmap_2d::getNumberFromXMLRPC (XmlRpc::XmlRpcValue &value, const std::string &full_param_name)
std::vector< geometry_msgs::Pointcostmap_2d::makeFootprintFromParams (ros::NodeHandle &nh)
 Read the ros-params "footprint" and/or "robot_radius" from the given NodeHandle using searchParam() to go up the tree.
std::vector< geometry_msgs::Pointcostmap_2d::makeFootprintFromRadius (double radius)
 Create a circular footprint from a given radius.
bool costmap_2d::makeFootprintFromString (const std::string &footprint_string, std::vector< geometry_msgs::Point > &footprint)
 Make the footprint from the given string.
std::vector< geometry_msgs::Pointcostmap_2d::makeFootprintFromXMLRPC (XmlRpc::XmlRpcValue &footprint_xmlrpc, const std::string &full_param_name)
 Create the footprint from the given XmlRpcValue.
void costmap_2d::padFootprint (std::vector< geometry_msgs::Point > &footprint, double padding)
 Adds the specified amount of padding to the footprint (in place)
geometry_msgs::Point costmap_2d::toPoint (geometry_msgs::Point32 pt)
 Convert Point32 to Point.
geometry_msgs::Point32 costmap_2d::toPoint32 (geometry_msgs::Point pt)
 Convert Point to Point32.
std::vector< geometry_msgs::Pointcostmap_2d::toPointVector (geometry_msgs::Polygon polygon)
 Convert Polygon msg to vector of Points.
geometry_msgs::Polygon costmap_2d::toPolygon (std::vector< geometry_msgs::Point > pts)
 Convert vector of Points to Polygon msg.
void costmap_2d::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)
void costmap_2d::transformFootprint (double x, double y, double theta, const std::vector< geometry_msgs::Point > &footprint_spec, geometry_msgs::PolygonStamped &oriented_footprint)
 Given a pose and base footprint, build the oriented footprint of the robot (PolygonStamped)
void costmap_2d::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 dynamic_reconfigure will see the new value.


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:46:15