| Classes | |
| class | CellData | 
| Storage for cell information used during obstacle inflation.  More... | |
| class | Costmap2D | 
| A 2D costmap provides a mapping between points in the world and their associated "costs".  More... | |
| class | Costmap2DPublisher | 
| A tool to periodically publish visualization data from a Costmap2D.  More... | |
| class | Costmap2DROS | 
| A ROS wrapper for a 2D Costmap. Handles subscribing to topics that provide observations about obstacles in either the form of PointCloud or LaserScan messages.  More... | |
| class | CostmapLayer | 
| class | CostmapTester | 
| class | InflationLayer | 
| class | Layer | 
| class | LayeredCostmap | 
| Instantiates different layer plugins and aggregates them into one score.  More... | |
| struct | MapLocation | 
| class | Observation | 
| Stores an observation in terms of a point cloud and the origin of the source.  More... | |
| class | ObservationBuffer | 
| Takes in point clouds from sensors, transforms them to the desired frame, and stores them.  More... | |
| class | ObstacleLayer | 
| class | StaticLayer | 
| class | VoxelLayer | 
| Functions | |
| void | calculateMinAndMaxDistances (const std::vector< geometry_msgs::Point > &footprint, double &min_dist, double &max_dist) | 
| Calculate the extreme distances for the footprint. | |
| double | getNumberFromXMLRPC (XmlRpc::XmlRpcValue &value, const std::string &full_param_name) | 
| std::vector< geometry_msgs::Point > | 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::Point > | makeFootprintFromRadius (double radius) | 
| Create a circular footprint from a given radius. | |
| bool | makeFootprintFromString (const std::string &footprint_string, std::vector< geometry_msgs::Point > &footprint) | 
| Make the footprint from the given string. | |
| std::vector< geometry_msgs::Point > | makeFootprintFromXMLRPC (XmlRpc::XmlRpcValue &footprint_xmlrpc, const std::string &full_param_name) | 
| Create the footprint from the given XmlRpcValue. | |
| void | move_parameter (ros::NodeHandle &old_h, ros::NodeHandle &new_h, std::string name, bool should_delete=true) | 
| void | padFootprint (std::vector< geometry_msgs::Point > &footprint, double padding) | 
| Adds the specified amount of padding to the footprint (in place) | |
| 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::Point | toPoint (geometry_msgs::Point32 pt) | 
| Convert Point32 to Point. | |
| geometry_msgs::Point32 | toPoint32 (geometry_msgs::Point pt) | 
| Convert Point to Point32. | |
| std::vector< geometry_msgs::Point > | toPointVector (geometry_msgs::Polygon polygon) | 
| Convert Polygon msg to vector of Points. | |
| geometry_msgs::Polygon | toPolygon (std::vector< geometry_msgs::Point > pts) | 
| Convert vector of Points to Polygon msg. | |
| 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) | |
| void | 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 | 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. | |
| Variables | |
| static const unsigned char | FREE_SPACE = 0 | 
| static const unsigned char | INSCRIBED_INFLATED_OBSTACLE = 253 | 
| static const unsigned char | LETHAL_OBSTACLE = 254 | 
| static const unsigned char | NO_INFORMATION = 255 | 
Provides a mapping for often used cost values
| void costmap_2d::calculateMinAndMaxDistances | ( | const std::vector< geometry_msgs::Point > & | footprint, | 
| double & | min_dist, | ||
| double & | max_dist | ||
| ) | 
Calculate the extreme distances for the footprint.
| footprint | The footprint to examine | 
| min_dist | Output parameter of the minimum distance | 
| max_dist | Output parameter of the maximum distance | 
Definition at line 41 of file footprint.cpp.
| double costmap_2d::getNumberFromXMLRPC | ( | XmlRpc::XmlRpcValue & | value, | 
| const std::string & | full_param_name | ||
| ) | 
Definition at line 269 of file footprint.cpp.
| 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.
Definition at line 212 of file footprint.cpp.
| std::vector< geometry_msgs::Point > costmap_2d::makeFootprintFromRadius | ( | double | radius | ) | 
Create a circular footprint from a given radius.
Definition at line 150 of file footprint.cpp.
| bool costmap_2d::makeFootprintFromString | ( | const std::string & | footprint_string, | 
| std::vector< geometry_msgs::Point > & | footprint | ||
| ) | 
Make the footprint from the given string.
Format should be bracketed array of arrays of floats, like so: [[1.0, 2.2], [3.3, 4.2], ...]
Definition at line 170 of file footprint.cpp.
| 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.
| footprint_xmlrpc | should be an array of arrays, where the top-level array should have 3 or more elements, and the sub-arrays should all have exactly 2 elements (x and y coordinates). | 
| full_param_name | this is the full name of the rosparam from which the footprint_xmlrpc value came. It is used only for reporting errors. | 
Definition at line 283 of file footprint.cpp.
| void costmap_2d::move_parameter | ( | ros::NodeHandle & | old_h, | 
| ros::NodeHandle & | new_h, | ||
| std::string | name, | ||
| bool | should_delete = true | ||
| ) | 
Definition at line 51 of file costmap_2d_ros.cpp.
| void costmap_2d::padFootprint | ( | std::vector< geometry_msgs::Point > & | footprint, | 
| double | padding | ||
| ) | 
Adds the specified amount of padding to the footprint (in place)
Definition at line 138 of file footprint.cpp.
| std::vector< std::vector< float > > costmap_2d::parseVVF | ( | const std::string & | input, | 
| std::string & | error_return | ||
| ) | 
Parse a vector of vectors of floats from a string.
Parse a vector of vector of floats from a string.
| error_return | If no error, error_return is set to "". If error, error_return will describe the error. Syntax is [[1.0, 2.0], [3.3, 4.4, 5.5], ...] | 
On error, error_return is set and the return value could be anything, like part of a successful parse.
| input | |
| error_return | Syntax is [[1.0, 2.0], [3.3, 4.4, 5.5], ...] | 
Definition at line 44 of file array_parser.cpp.
| geometry_msgs::Point costmap_2d::toPoint | ( | geometry_msgs::Point32 | pt | ) | 
Convert Point32 to Point.
Definition at line 78 of file footprint.cpp.
| geometry_msgs::Point32 costmap_2d::toPoint32 | ( | geometry_msgs::Point | pt | ) | 
Convert Point to Point32.
Definition at line 69 of file footprint.cpp.
| std::vector< geometry_msgs::Point > costmap_2d::toPointVector | ( | geometry_msgs::Polygon | polygon | ) | 
Convert Polygon msg to vector of Points.
Definition at line 96 of file footprint.cpp.
| geometry_msgs::Polygon costmap_2d::toPolygon | ( | std::vector< geometry_msgs::Point > | pts | ) | 
Convert vector of Points to Polygon msg.
Definition at line 87 of file footprint.cpp.
| 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)
| x | The x position of the robot | 
| y | The y position of the robot | 
| theta | The orientation of the robot | 
| footprint_spec | Basic shape of the footprint | 
| oriented_footprint | Will be filled with the points in the oriented footprint of the robot | 
Definition at line 106 of file footprint.cpp.
| 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)
| x | The x position of the robot | 
| y | The y position of the robot | 
| theta | The orientation of the robot | 
| footprint_spec | Basic shape of the footprint | 
| oriented_footprint | Will be filled with the points in the oriented footprint of the robot | 
Definition at line 122 of file footprint.cpp.
| 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.
Definition at line 248 of file footprint.cpp.
| const unsigned char costmap_2d::FREE_SPACE = 0  [static] | 
Definition at line 45 of file cost_values.h.
| const unsigned char costmap_2d::INSCRIBED_INFLATED_OBSTACLE = 253  [static] | 
Definition at line 44 of file cost_values.h.
| const unsigned char costmap_2d::LETHAL_OBSTACLE = 254  [static] | 
Definition at line 43 of file cost_values.h.
| const unsigned char costmap_2d::NO_INFORMATION = 255  [static] | 
Definition at line 42 of file cost_values.h.