#include <HectorMapTools.h>
|  | 
| int | bresenham2D (unsigned int abs_da, unsigned int abs_db, int error_b, int offset_a, int offset_b, unsigned int offset, unsigned int max_length) | 
|  | 
| float | checkOccupancyBresenhami (const Eigen::Vector2i &beginMap, const Eigen::Vector2i &endMap, Eigen::Vector2i *hitCoords=0, unsigned int max_length=UINT_MAX) | 
|  | 
|  | DistanceMeasurementProvider () | 
|  | 
| float | getDist (const Eigen::Vector2f &begin_world, const Eigen::Vector2f &end_world, Eigen::Vector2f *hitCoords=0) | 
|  | 
| void | setMap (const nav_msgs::OccupancyGridConstPtr map) | 
|  | 
Definition at line 118 of file HectorMapTools.h.
 
◆ DistanceMeasurementProvider()
  
  | 
        
          | HectorMapTools::DistanceMeasurementProvider::DistanceMeasurementProvider | ( |  | ) |  |  | inline | 
 
 
◆ bresenham2D()
  
  | 
        
          | int HectorMapTools::DistanceMeasurementProvider::bresenham2D | ( | unsigned int | abs_da, |  
          |  |  | unsigned int | abs_db, |  
          |  |  | int | error_b, |  
          |  |  | int | offset_a, |  
          |  |  | int | offset_b, |  
          |  |  | unsigned int | offset, |  
          |  |  | unsigned int | max_length |  
          |  | ) |  |  |  | inline | 
 
 
◆ checkOccupancyBresenhami()
  
  | 
        
          | float HectorMapTools::DistanceMeasurementProvider::checkOccupancyBresenhami | ( | const Eigen::Vector2i & | beginMap, |  
          |  |  | const Eigen::Vector2i & | endMap, |  
          |  |  | Eigen::Vector2i * | hitCoords = 0, |  
          |  |  | unsigned int | max_length = UINT_MAX |  
          |  | ) |  |  |  | inline | 
 
 
◆ getDist()
  
  | 
        
          | float HectorMapTools::DistanceMeasurementProvider::getDist | ( | const Eigen::Vector2f & | begin_world, |  
          |  |  | const Eigen::Vector2f & | end_world, |  
          |  |  | Eigen::Vector2f * | hitCoords = 0 |  
          |  | ) |  |  |  | inline | 
 
 
◆ setMap()
  
  | 
        
          | void HectorMapTools::DistanceMeasurementProvider::setMap | ( | const nav_msgs::OccupancyGridConstPtr | map | ) |  |  | inline | 
 
 
◆ map_ptr_
  
  | 
        
          | nav_msgs::OccupancyGridConstPtr HectorMapTools::DistanceMeasurementProvider::map_ptr_ |  | protected | 
 
 
◆ world_map_transformer_
The documentation for this class was generated from the following file: