|
| virtual void | activate () |
| |
| virtual void | deactivate () |
| |
| virtual void | matchSize () |
| |
| virtual void | onInitialize () |
| |
| virtual void | reset () |
| |
| | StaticLayer () |
| |
| virtual void | updateBounds (double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y) |
| |
| virtual void | updateCosts (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
| |
| virtual | ~StaticLayer () |
| |
| void | addExtraBounds (double mx0, double my0, double mx1, double my1) |
| |
| | CostmapLayer () |
| |
| bool | isDiscretized () |
| |
| 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 () |
| |
|
| typedef boost::recursive_mutex | mutex_t |
| |
| void | touch (double x, double y, double *min_x, double *min_y, double *max_x, double *max_y) |
| |
| void | updateWithAddition (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
| |
| void | updateWithMax (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
| |
| void | updateWithOverwrite (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
| |
| void | updateWithTrueOverwrite (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
| |
| void | useExtraBounds (double *min_x, double *min_y, double *max_x, double *max_y) |
| |
| 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 () |
| |
| bool | has_extra_bounds_ |
| |
| bool | current_ |
| |
| bool | enabled_ |
| |
| LayeredCostmap * | layered_costmap_ |
| |
| std::string | name_ |
| |
| tf::TransformListener * | tf_ |
| |
| unsigned char * | costmap_ |
| |
| unsigned char | default_value_ |
| |
| double | origin_x_ |
| |
| double | origin_y_ |
| |
| double | resolution_ |
| |
| unsigned int | size_x_ |
| |
| unsigned int | size_y_ |
| |
Definition at line 53 of file static_layer.h.