Public Member Functions | Private Attributes | List of all members
base_local_planner::WavefrontMapAccessor Class Reference

#include <wavefront_map_accessor.h>

Inheritance diagram for base_local_planner::WavefrontMapAccessor:
Inheritance graph
[legend]

Public Member Functions

void synchronize ()
 
 WavefrontMapAccessor (MapGrid *map, double outer_radius)
 
virtual ~WavefrontMapAccessor ()
 
- Public Member Functions inherited from costmap_2d::Costmap2D
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_tgetMutex ()
 
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
 
Costmap2Doperator= (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 ()
 

Private Attributes

MapGridmap_
 
double outer_radius_
 

Additional Inherited Members

- Public Types inherited from costmap_2d::Costmap2D
typedef boost::recursive_mutex mutex_t
 
- Protected Member Functions inherited from costmap_2d::Costmap2D
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 ()
 
- Protected Attributes inherited from costmap_2d::Costmap2D
unsigned char * costmap_
 
unsigned char default_value_
 
double origin_x_
 
double origin_y_
 
double resolution_
 
unsigned int size_x_
 
unsigned int size_y_
 

Detailed Description

Map_grids rely on costmaps to identify obstacles. We need a costmap that we can easily manipulate for unit tests. This class has a grid map where we can set grid cell state, and a synchronize method to make the costmap match.

Definition at line 17 of file wavefront_map_accessor.h.

Constructor & Destructor Documentation

base_local_planner::WavefrontMapAccessor::WavefrontMapAccessor ( MapGrid map,
double  outer_radius 
)
inline

Definition at line 19 of file wavefront_map_accessor.h.

virtual base_local_planner::WavefrontMapAccessor::~WavefrontMapAccessor ( )
inlinevirtual

Definition at line 25 of file wavefront_map_accessor.h.

Member Function Documentation

void base_local_planner::WavefrontMapAccessor::synchronize ( )
inline

Definition at line 27 of file wavefront_map_accessor.h.

Member Data Documentation

MapGrid* base_local_planner::WavefrontMapAccessor::map_
private

Definition at line 42 of file wavefront_map_accessor.h.

double base_local_planner::WavefrontMapAccessor::outer_radius_
private

Definition at line 43 of file wavefront_map_accessor.h.


The documentation for this class was generated from the following file:


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Thu Jan 21 2021 04:05:50