|
void | costmap_2d::calculateMinAndMaxDistances (const std::vector< geometry_msgs::Point > &footprint, double &min_dist, double &max_dist) |
| Calculate the extreme distances for the footprint. More...
|
|
std::vector< geometry_msgs::Point > | costmap_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. More...
|
|
std::vector< geometry_msgs::Point > | costmap_2d::makeFootprintFromRadius (double radius) |
| Create a circular footprint from a given radius. More...
|
|
bool | costmap_2d::makeFootprintFromString (const std::string &footprint_string, std::vector< geometry_msgs::Point > &footprint) |
| Make the footprint from the given string. More...
|
|
std::vector< geometry_msgs::Point > | costmap_2d::makeFootprintFromXMLRPC (XmlRpc::XmlRpcValue &footprint_xmlrpc, const std::string &full_param_name) |
| Create the footprint from the given XmlRpcValue. More...
|
|
void | costmap_2d::padFootprint (std::vector< geometry_msgs::Point > &footprint, double padding) |
| Adds the specified amount of padding to the footprint (in place) More...
|
|
geometry_msgs::Point | costmap_2d::toPoint (geometry_msgs::Point32 pt) |
| Convert Point32 to Point. More...
|
|
geometry_msgs::Point32 | costmap_2d::toPoint32 (geometry_msgs::Point pt) |
| Convert Point to Point32. More...
|
|
std::vector< geometry_msgs::Point > | costmap_2d::toPointVector (geometry_msgs::Polygon polygon) |
| Convert Polygon msg to vector of Points. More...
|
|
geometry_msgs::Polygon | costmap_2d::toPolygon (std::vector< geometry_msgs::Point > pts) |
| Convert vector of Points to Polygon msg. More...
|
|
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) More...
|
|
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) More...
|
|
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. More...
|
|