|
void | synchronize () |
|
| WavefrontMapAccessor (MapGrid *map, double outer_radius) |
|
virtual | ~WavefrontMapAccessor () |
|
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 () |
|