|
| BoundedExploreLayer () |
|
bool | isDiscretized () |
|
virtual void | matchSize () |
| Match dimensions and origin of parent costmap. More...
|
|
virtual void | onInitialize () |
| Loads default values and initialize exploration costmap. More...
|
|
virtual void | reset () |
| Reset exploration progress. More...
|
|
virtual void | updateBounds (double origin_x, double origin_y, double origin_yaw, double *polygon_min_x, double *polygon_min_y, double *polygon_max_x, double *polygon_max_y) |
| Calculate bounds of costmap window to update. More...
|
|
virtual void | updateCosts (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
| Update requested costmap window. More...
|
|
| ~BoundedExploreLayer () |
|
virtual void | activate () |
|
virtual void | deactivate () |
|
const std::vector< geometry_msgs::Point > & | getFootprint () const |
|
std::string | getName () const |
|
void | initialize (LayeredCostmap *parent, std::string name, tf::TransformListener *tf) |
|
bool | isCurrent () const |
|
| Layer () |
|
virtual void | onFootprintChanged () |
|
virtual | ~Layer () |
|
unsigned int | cellDistance (double world_dist) |
|
void | convexFillCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells) |
|
bool | copyCostmapWindow (const Costmap2D &map, double win_origin_x, double win_origin_y, double win_size_x, double win_size_y) |
|
| Costmap2D (unsigned int cells_size_x, unsigned int cells_size_y, double resolution, double origin_x, double origin_y, unsigned char default_value=0) |
|
| Costmap2D (const Costmap2D &map) |
|
| Costmap2D () |
|
unsigned char * | getCharMap () const |
|
unsigned char | getCost (unsigned int mx, unsigned int my) const |
|
unsigned char | getDefaultValue () |
|
unsigned int | getIndex (unsigned int mx, unsigned int my) const |
|
mutex_t * | getMutex () |
|
double | getOriginX () const |
|
double | getOriginY () const |
|
double | getResolution () const |
|
unsigned int | getSizeInCellsX () const |
|
unsigned int | getSizeInCellsY () const |
|
double | getSizeInMetersX () const |
|
double | getSizeInMetersY () const |
|
void | indexToCells (unsigned int index, unsigned int &mx, unsigned int &my) const |
|
void | mapToWorld (unsigned int mx, unsigned int my, double &wx, double &wy) const |
|
Costmap2D & | operator= (const Costmap2D &map) |
|
void | polygonOutlineCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells) |
|
void | resetMap (unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn) |
|
void | resizeMap (unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y) |
|
bool | saveMap (std::string file_name) |
|
bool | setConvexPolygonCost (const std::vector< geometry_msgs::Point > &polygon, unsigned char cost_value) |
|
void | setCost (unsigned int mx, unsigned int my, unsigned char cost) |
|
void | setDefaultValue (unsigned char c) |
|
virtual void | updateOrigin (double new_origin_x, double new_origin_y) |
|
bool | worldToMap (double wx, double wy, unsigned int &mx, unsigned int &my) const |
|
void | worldToMapEnforceBounds (double wx, double wy, int &mx, int &my) const |
|
void | worldToMapNoBounds (double wx, double wy, int &mx, int &my) const |
|
virtual | ~Costmap2D () |
|
|
bool | getNextFrontier (geometry_msgs::PoseStamped start_pose, geometry_msgs::PoseStamped &next_frontier) |
| Search the costmap for next reachable frontier to explore. More...
|
|
bool | getNextFrontierService (frontier_exploration::GetNextFrontier::Request &req, frontier_exploration::GetNextFrontier::Response &res) |
| ROS Service wrapper for getNextFrontier. More...
|
|
bool | updateBoundaryPolygon (geometry_msgs::PolygonStamped polygon_stamped) |
| Load polygon boundary to draw on map with each update. More...
|
|
bool | updateBoundaryPolygonService (frontier_exploration::UpdateBoundaryPolygon::Request &req, frontier_exploration::UpdateBoundaryPolygon::Response &res) |
| ROS Service wrapper for updateBoundaryPolygon. More...
|
|
void | 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) |
|
virtual void | deleteMaps () |
|
virtual void | initMaps (unsigned int size_x, unsigned int size_y) |
|
void | raytraceLine (ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int max_length=UINT_MAX) |
|
virtual void | resetMaps () |
|
costmap_2d layer plugin that holds the state for a bounded frontier exploration task. Manages the boundary polygon, superimposes the polygon on the overall exploration costmap, and processes costmap to find next frontier to explore.
Definition at line 22 of file bounded_explore_layer.h.