, including all inherited members.
cached_costs_ | costmap_2d::Costmap2D | [protected] |
cached_distances_ | costmap_2d::Costmap2D | [protected] |
cell_circumscribed_radius_ | costmap_2d::Costmap2D | [protected] |
cell_inflation_radius_ | costmap_2d::Costmap2D | [protected] |
cell_inscribed_radius_ | costmap_2d::Costmap2D | [protected] |
cellDistance(double world_dist) | costmap_2d::Costmap2D | [protected] |
circumscribed_cost_lb_ | costmap_2d::Costmap2D | [protected] |
circumscribed_radius_ | costmap_2d::Costmap2D | [protected] |
clearNonLethal(double wx, double wy, double w_size_x, double w_size_y, bool clear_no_info=false) | costmap_2d::VoxelCostmap2D | [virtual] |
computeCost(double distance) const | costmap_2d::Costmap2D | [inline] |
convexFillCells(const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells) | costmap_2d::Costmap2D | |
copyCostmapWindow(const Costmap2D &map, double win_origin_x, double win_origin_y, double win_size_x, double win_size_y) | costmap_2d::Costmap2D | |
copyKernels(const Costmap2D &map, unsigned int cell_inflation_radius) | costmap_2d::Costmap2D | [protected] |
copyMapRegion(data_type *source_map, unsigned int sm_lower_left_x, unsigned int sm_lower_left_y, unsigned int sm_size_x, data_type *dest_map, unsigned int dm_lower_left_x, unsigned int dm_lower_left_y, unsigned int dm_size_x, unsigned int region_size_x, unsigned int region_size_y) | costmap_2d::Costmap2D | [inline, protected] |
Costmap2D(unsigned int cells_size_x, unsigned int cells_size_y, double resolution, double origin_x, double origin_y, double inscribed_radius=0.0, double circumscribed_radius=0.0, double inflation_radius=0.0, double max_obstacle_range=0.0, double max_obstacle_height=0.0, double max_raytrace_range=0.0, double weight=25.0, const std::vector< unsigned char > &static_data=std::vector< unsigned char >(0), unsigned char lethal_threshold=0, bool track_unknown_space=false, unsigned char unknown_cost_value=0) | costmap_2d::Costmap2D | |
Costmap2D(const Costmap2D &map) | costmap_2d::Costmap2D | |
Costmap2D() | costmap_2d::Costmap2D | |
costmap_ | costmap_2d::Costmap2D | [protected] |
deleteKernels() | costmap_2d::Costmap2D | [protected] |
deleteMaps() | costmap_2d::Costmap2D | [protected, virtual] |
dist(double x0, double y0, double z0, double x1, double y1, double z1) | costmap_2d::VoxelCostmap2D | [inline, private] |
enqueue(unsigned int index, unsigned int mx, unsigned int my, unsigned int src_x, unsigned int src_y, std::priority_queue< CellData > &inflation_queue) | costmap_2d::Costmap2D | [inline, protected] |
finishConfiguration(costmap_2d::Costmap2DConfig &config) | costmap_2d::VoxelCostmap2D | [private, virtual] |
getCharMap() const | costmap_2d::Costmap2D | |
getCircumscribedCost() const | costmap_2d::Costmap2D | [inline] |
getCircumscribedRadius() const | costmap_2d::Costmap2D | [inline] |
getCost(unsigned int mx, unsigned int my) const | costmap_2d::Costmap2D | |
getIndex(unsigned int mx, unsigned int my) const | costmap_2d::Costmap2D | [inline] |
getInflationRadius() const | costmap_2d::Costmap2D | [inline] |
getInscribedRadius() const | costmap_2d::Costmap2D | [inline] |
getOriginX() const | costmap_2d::Costmap2D | |
getOriginY() const | costmap_2d::Costmap2D | |
getPoints(pcl::PointCloud< pcl::PointXYZ > &cloud) | costmap_2d::VoxelCostmap2D | |
getResolution() const | costmap_2d::Costmap2D | |
getSizeInCellsX() const | costmap_2d::Costmap2D | |
getSizeInCellsY() const | costmap_2d::Costmap2D | |
getSizeInMetersX() const | costmap_2d::Costmap2D | |
getSizeInMetersY() const | costmap_2d::Costmap2D | |
getVoxelGridMessage(VoxelGrid &grid) | costmap_2d::VoxelCostmap2D | |
indexToCells(unsigned int index, unsigned int &mx, unsigned int &my) const | costmap_2d::Costmap2D | [inline] |
inflation_queue_ | costmap_2d::Costmap2D | [protected] |
inflation_radius_ | costmap_2d::Costmap2D | [protected] |
initMaps(unsigned int size_x, unsigned int size_y) | costmap_2d::VoxelCostmap2D | [protected, virtual] |
inscribed_radius_ | costmap_2d::Costmap2D | [protected] |
isCircumscribedCell(unsigned int x, unsigned int y) const | costmap_2d::Costmap2D | |
lethal_threshold_ | costmap_2d::Costmap2D | [protected] |
mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const | costmap_2d::Costmap2D | |
mapToWorld3D(const unsigned int mx, const unsigned int my, const unsigned int mz, const double origin_x, const double origin_y, const double origin_z, const double x_resolution, const double y_resolution, const double z_resolution, double &wx, double &wy, double &wz) | costmap_2d::VoxelCostmap2D | [inline, static] |
mapToWorld3D(unsigned int mx, unsigned int my, unsigned int mz, double &wx, double &wy, double &wz) | costmap_2d::VoxelCostmap2D | [inline, private] |
mark_threshold_ | costmap_2d::VoxelCostmap2D | [protected] |
markers_ | costmap_2d::Costmap2D | [protected] |
max_obstacle_height_ | costmap_2d::Costmap2D | [protected] |
max_obstacle_range_ | costmap_2d::Costmap2D | [protected] |
max_raytrace_range_ | costmap_2d::Costmap2D | [protected] |
operator=(const Costmap2D &map) | costmap_2d::Costmap2D | |
origin_x_ | costmap_2d::Costmap2D | [protected] |
origin_y_ | costmap_2d::Costmap2D | [protected] |
origin_z_ | costmap_2d::VoxelCostmap2D | [protected] |
polygonOutlineCells(const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells) | costmap_2d::Costmap2D | |
raytraceFreespace(const Observation &clearing_observation) | costmap_2d::VoxelCostmap2D | [private, virtual] |
reconfigure(costmap_2d::Costmap2DConfig &config, const costmap_2d::Costmap2DConfig &last_config) | costmap_2d::Costmap2D | |
reinflateWindow(double wx, double wy, double w_size_x, double w_size_y, bool clear=true) | costmap_2d::Costmap2D | |
replaceFullMap(double win_origin_x, double win_origin_y, unsigned int data_size_x, unsigned int data_size_y, const std::vector< unsigned char > &static_data) | costmap_2d::Costmap2D | |
replaceStaticMapWindow(double win_origin_x, double win_origin_y, unsigned int data_size_x, unsigned int data_size_y, const std::vector< unsigned char > &static_data) | costmap_2d::Costmap2D | [protected] |
resetMapOutsideWindow(double wx, double wy, double w_size_x, double w_size_y) | costmap_2d::VoxelCostmap2D | [virtual] |
resetMaps() | costmap_2d::VoxelCostmap2D | [protected, virtual] |
reshapeStaticMap(double win_origin_x, double win_origin_y, unsigned int data_size_x, unsigned int data_size_y, const std::vector< unsigned char > &static_data) | costmap_2d::Costmap2D | [protected] |
resolution_ | costmap_2d::Costmap2D | [protected] |
saveMap(std::string file_name) | costmap_2d::Costmap2D | |
saveRawMap(std::string file_name) | costmap_2d::Costmap2D | |
setConvexPolygonCost(const std::vector< geometry_msgs::Point > &polygon, unsigned char cost_value) | costmap_2d::Costmap2D | |
setCost(unsigned int mx, unsigned int my, unsigned char cost) | costmap_2d::Costmap2D | |
size_x_ | costmap_2d::Costmap2D | [protected] |
size_y_ | costmap_2d::Costmap2D | [protected] |
size_z_ | costmap_2d::VoxelCostmap2D | [protected] |
static_map_ | costmap_2d::Costmap2D | [protected] |
track_unknown_space_ | costmap_2d::Costmap2D | [protected] |
unknown_cost_value_ | costmap_2d::Costmap2D | [protected] |
unknown_threshold_ | costmap_2d::VoxelCostmap2D | [protected] |
updateObstacles(const std::vector< Observation > &observations, std::priority_queue< CellData > &inflation_queue) | costmap_2d::VoxelCostmap2D | [private, virtual] |
updateOrigin(double new_origin_x, double new_origin_y) | costmap_2d::VoxelCostmap2D | [virtual] |
updateStaticMapWindow(double win_origin_x, double win_origin_y, unsigned int data_size_x, unsigned int data_size_y, const std::vector< unsigned char > &static_data) | costmap_2d::Costmap2D | |
updateWorld(double robot_x, double robot_y, const std::vector< Observation > &observations, const std::vector< Observation > &clearing_observations) | costmap_2d::Costmap2D | |
voxel_grid_ | costmap_2d::VoxelCostmap2D | [protected] |
VoxelCostmap2D(unsigned int cells_size_x, unsigned int cells_size_y, unsigned int cells_size_z, double xy_resolution, double z_resolution, double origin_x, double origin_y, double origin_z=0.0, double inscribed_radius=0.0, double circumscribed_radius=0.0, double inflation_radius=0.0, double obstacle_range=0.0, double raytrace_range=0.0, double weight=25.0, const std::vector< unsigned char > &static_data=std::vector< unsigned char >(0), unsigned char lethal_threshold=0, unsigned int unknown_threshold=0, unsigned int mark_threshold=0, unsigned char unknown_cost_value=0) | costmap_2d::VoxelCostmap2D | |
VoxelCostmap2D(costmap_2d::Costmap2D &costmap, double z_resolution, unsigned int cells_size_z, double origin_z=0.0, unsigned int mark_threshold=0, unsigned int unknown_threshold=0) | costmap_2d::VoxelCostmap2D | |
weight_ | costmap_2d::Costmap2D | [protected] |
worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const | costmap_2d::Costmap2D | |
worldToMap3D(double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz) | costmap_2d::VoxelCostmap2D | [inline, private] |
worldToMap3DFloat(double wx, double wy, double wz, double &mx, double &my, double &mz) | costmap_2d::VoxelCostmap2D | [inline, private] |
worldToMapNoBounds(double wx, double wy, int &mx, int &my) const | costmap_2d::Costmap2D | |
xy_resolution_ | costmap_2d::VoxelCostmap2D | [protected] |
z_resolution_ | costmap_2d::VoxelCostmap2D | [protected] |
~Costmap2D() | costmap_2d::Costmap2D | [virtual] |
~VoxelCostmap2D() | costmap_2d::VoxelCostmap2D | |