|
bool | isDiscretized () |
|
virtual void | matchSize () |
| Implement this to make this layer match the size of the parent costmap. More...
|
|
virtual void | onInitialize () |
| This is called at the end of initialize(). Override to implement subclass-specific initialization. More...
|
|
virtual void | reset () |
|
virtual void | updateBounds (double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y) |
| This is called by the LayeredCostmap to poll this plugin as to how much of the costmap it needs to update. Each layer can increase the size of this bounds. More...
|
|
void | updateOrigin (double new_origin_x, double new_origin_y) |
| Move the origin of the costmap to a new location.... keeping data when it can. More...
|
|
| VoxelLayer () |
|
virtual | ~VoxelLayer () |
|
virtual void | activate () |
| Restart publishers if they've been stopped. More...
|
|
void | addStaticObservation (costmap_2d::Observation &obs, bool marking, bool clearing) |
|
void | clearStaticObservations (bool marking, bool clearing) |
|
virtual void | deactivate () |
| Stop publishers. More...
|
|
void | laserScanCallback (const sensor_msgs::LaserScanConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer) |
| A callback to handle buffering LaserScan messages. More...
|
|
void | laserScanValidInfCallback (const sensor_msgs::LaserScanConstPtr &message, const boost::shared_ptr< ObservationBuffer > &buffer) |
| A callback to handle buffering LaserScan messages which need filtering to turn Inf values into range_max. More...
|
|
| ObstacleLayer () |
|
void | pointCloud2Callback (const sensor_msgs::PointCloud2ConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer) |
| A callback to handle buffering PointCloud2 messages. More...
|
|
void | pointCloudCallback (const sensor_msgs::PointCloudConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer) |
| A callback to handle buffering PointCloud messages. More...
|
|
virtual void | updateCosts (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) |
| Actually update the underlying costmap, only within the bounds calculated during UpdateBounds(). More...
|
|
virtual | ~ObstacleLayer () |
|
void | addExtraBounds (double mx0, double my0, double mx1, double my1) |
|
| CostmapLayer () |
|
bool | isDiscretized () |
|
const std::vector< geometry_msgs::Point > & | getFootprint () const |
| Convenience function for layered_costmap_->getFootprint(). More...
|
|
std::string | getName () const |
|
void | initialize (LayeredCostmap *parent, std::string name, tf::TransformListener *tf) |
|
bool | isCurrent () const |
| Check to make sure all the data in the layer is up to date. If the layer is not up to date, then it may be unsafe to plan using the data from this layer, and the planner may need to know. More...
|
|
| Layer () |
|
virtual void | onFootprintChanged () |
| LayeredCostmap calls this whenever the footprint there changes (via LayeredCostmap::setFootprint()). Override to be notified of changes to the robot's footprint. More...
|
|
virtual | ~Layer () |
|
unsigned int | cellDistance (double world_dist) |
| Given distance in the world... convert it to cells. More...
|
|
void | convexFillCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells) |
| Get the map cells that fill a convex polygon. More...
|
|
bool | copyCostmapWindow (const Costmap2D &map, double win_origin_x, double win_origin_y, double win_size_x, double win_size_y) |
| Turn this costmap into a copy of a window of a costmap passed in. More...
|
|
| Costmap2D (unsigned int cells_size_x, unsigned int cells_size_y, double resolution, double origin_x, double origin_y, unsigned char default_value=0) |
| Constructor for a costmap. More...
|
|
| Costmap2D (const Costmap2D &map) |
| Copy constructor for a costmap, creates a copy efficiently. More...
|
|
| Costmap2D () |
| Default constructor. More...
|
|
unsigned char * | getCharMap () const |
| Will return a pointer to the underlying unsigned char array used as the costmap. More...
|
|
unsigned char | getCost (unsigned int mx, unsigned int my) const |
| Get the cost of a cell in the costmap. More...
|
|
unsigned char | getDefaultValue () |
|
unsigned int | getIndex (unsigned int mx, unsigned int my) const |
| Given two map coordinates... compute the associated index. More...
|
|
mutex_t * | getMutex () |
|
double | getOriginX () const |
| Accessor for the x origin of the costmap. More...
|
|
double | getOriginY () const |
| Accessor for the y origin of the costmap. More...
|
|
double | getResolution () const |
| Accessor for the resolution of the costmap. More...
|
|
unsigned int | getSizeInCellsX () const |
| Accessor for the x size of the costmap in cells. More...
|
|
unsigned int | getSizeInCellsY () const |
| Accessor for the y size of the costmap in cells. More...
|
|
double | getSizeInMetersX () const |
| Accessor for the x size of the costmap in meters. More...
|
|
double | getSizeInMetersY () const |
| Accessor for the y size of the costmap in meters. More...
|
|
void | indexToCells (unsigned int index, unsigned int &mx, unsigned int &my) const |
| Given an index... compute the associated map coordinates. More...
|
|
void | mapToWorld (unsigned int mx, unsigned int my, double &wx, double &wy) const |
| Convert from map coordinates to world coordinates. More...
|
|
Costmap2D & | operator= (const Costmap2D &map) |
| Overloaded assignment operator. More...
|
|
void | polygonOutlineCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells) |
| Get the map cells that make up the outline of a polygon. More...
|
|
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) |
| Save the costmap out to a pgm file. More...
|
|
bool | setConvexPolygonCost (const std::vector< geometry_msgs::Point > &polygon, unsigned char cost_value) |
| Sets the cost of a convex polygon to a desired value. More...
|
|
void | setCost (unsigned int mx, unsigned int my, unsigned char cost) |
| Set the cost of a cell in the costmap. More...
|
|
void | setDefaultValue (unsigned char c) |
|
bool | worldToMap (double wx, double wy, unsigned int &mx, unsigned int &my) const |
| Convert from world coordinates to map coordinates. More...
|
|
void | worldToMapEnforceBounds (double wx, double wy, int &mx, int &my) const |
| Convert from world coordinates to map coordinates, constraining results to legal bounds. More...
|
|
void | worldToMapNoBounds (double wx, double wy, int &mx, int &my) const |
| Convert from world coordinates to map coordinates without checking for legal bounds. More...
|
|
virtual | ~Costmap2D () |
| Destructor. More...
|
|
|
virtual void | resetMaps () |
| Resets the costmap and static_map to be unknown space. More...
|
|
virtual void | setupDynamicReconfigure (ros::NodeHandle &nh) |
|
bool | getClearingObservations (std::vector< costmap_2d::Observation > &clearing_observations) const |
| Get the observations used to clear space. More...
|
|
bool | getMarkingObservations (std::vector< costmap_2d::Observation > &marking_observations) const |
| Get the observations used to mark space. More...
|
|
void | updateFootprint (double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y) |
|
void | updateRaytraceBounds (double ox, double oy, double wx, double wy, double range, double *min_x, double *min_y, double *max_x, double *max_y) |
|
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) |
|
template<typename data_type > |
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) |
| Copy a region of a source map into a destination map. More...
|
|
virtual void | deleteMaps () |
| Deletes the costmap, static_map, and markers data structures. More...
|
|
virtual void | initMaps (unsigned int size_x, unsigned int size_y) |
| Initializes the costmap, static_map, and markers data structures. More...
|
|
template<class ActionType > |
void | raytraceLine (ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int max_length=UINT_MAX) |
| Raytrace a line and apply some action at each step. More...
|
|
|
void | clearNonLethal (double wx, double wy, double w_size_x, double w_size_y, bool clear_no_info) |
|
double | dist (double x0, double y0, double z0, double x1, double y1, double z1) |
|
void | mapToWorld3D (unsigned int mx, unsigned int my, unsigned int mz, double &wx, double &wy, double &wz) |
|
virtual void | raytraceFreespace (const costmap_2d::Observation &clearing_observation, double *min_x, double *min_y, double *max_x, double *max_y) |
| Clear freespace based on one observation. More...
|
|
void | reconfigureCB (costmap_2d::VoxelPluginConfig &config, uint32_t level) |
|
bool | worldToMap3D (double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz) |
|
bool | worldToMap3DFloat (double wx, double wy, double wz, double &mx, double &my, double &mz) |
|
Definition at line 62 of file voxel_layer.h.