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 | FootprintLayer |
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) |
double | getNumberFromXMLRPC (XmlRpc::XmlRpcValue &value, const std::string &full_param_name) |
void | move_parameter (ros::NodeHandle &old_h, ros::NodeHandle &new_h, std::string name, bool should_delete=true) |
bool | operator< (const CellData &a, const CellData &b) |
Provide an ordering between CellData objects in the priority queue. | |
std::vector< std::vector< float > > | parseVVF (const std::string &input, std::string &error_return) |
Parse a vector of vectors of floats from a string. | |
double | sign (double x) |
geometry_msgs::Point | toPoint (geometry_msgs::Point32 pt) |
geometry_msgs::Point32 | toPoint32 (geometry_msgs::Point pt) |
std::vector< geometry_msgs::Point > | toPointVector (geometry_msgs::Polygon polygon) |
geometry_msgs::Polygon | toPolygon (std::vector< geometry_msgs::Point > pts) |
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 | ||
) |
Definition at line 40 of file footprint.cpp.
double costmap_2d::getNumberFromXMLRPC | ( | XmlRpc::XmlRpcValue & | value, |
const std::string & | full_param_name | ||
) |
Definition at line 436 of file costmap_2d_ros.cpp.
void costmap_2d::move_parameter | ( | ros::NodeHandle & | old_h, |
ros::NodeHandle & | new_h, | ||
std::string | name, | ||
bool | should_delete = true |
||
) |
Definition at line 52 of file costmap_2d_ros.cpp.
bool costmap_2d::operator< | ( | const CellData & | a, |
const CellData & | b | ||
) | [inline] |
Provide an ordering between CellData objects in the priority queue.
Definition at line 81 of file inflation_layer.h.
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.
double costmap_2d::sign | ( | double | x | ) |
Definition at line 486 of file costmap_2d_ros.cpp.
geometry_msgs::Point costmap_2d::toPoint | ( | geometry_msgs::Point32 | pt | ) |
Definition at line 77 of file footprint.cpp.
geometry_msgs::Point32 costmap_2d::toPoint32 | ( | geometry_msgs::Point | pt | ) |
Definition at line 68 of file footprint.cpp.
std::vector< geometry_msgs::Point > costmap_2d::toPointVector | ( | geometry_msgs::Polygon | polygon | ) |
Definition at line 95 of file footprint.cpp.
geometry_msgs::Polygon costmap_2d::toPolygon | ( | std::vector< geometry_msgs::Point > | pts | ) |
Definition at line 86 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.