map_ray_caster.h
Go to the documentation of this file.
00001 #ifndef MAP_RAY_CASTER_MAP_RAY_CASTER_H
00002 #define MAP_RAY_CASTER_MAP_RAY_CASTER_H
00003 
00004 #include <math.h> /* for lround, std::lround not in C++99. */
00005 #include <cmath>
00006 #include <map>
00007 #include <vector>
00008 
00009 #include <angles/angles.h>
00010 #include <nav_msgs/OccupancyGrid.h>
00011 #include <sensor_msgs/LaserScan.h>
00012 
00013 #include <lama_msgs/PlaceProfile.h>
00014 
00015 #include <map_ray_caster/ray_caster_utils.h>
00016 
00017 namespace map_ray_caster
00018 {
00019 
00020 typedef std::map<double, std::vector<size_t> > RayLookup;
00021 
00022 class MapRayCaster
00023 {
00024   public :
00025 
00026     MapRayCaster(const int occupied_threshold = 60);
00027 
00028     void laserScanCast(const nav_msgs::OccupancyGrid& map, sensor_msgs::LaserScan& scan);
00029 
00030     const std::vector<size_t>& getRayCastToMapBorder(const double angle, const size_t nrow, const size_t ncol, const double tolerance = 0);
00031 
00032     size_t lookupSize() const {return raycast_lookup_.size();}
00033 
00034   private :
00035 
00036     RayLookup::const_iterator angleLookup(const double angle, const double tolerance);
00037 
00038     int occupied_threshold_;
00039     size_t ncol_; 
00040     size_t nrow_; 
00041     RayLookup raycast_lookup_;
00042 };
00043 
00044 } // namespace map_ray_caster
00045 
00046 #endif // MAP_RAY_CASTER_MAP_RAY_CASTER_H


map_ray_caster
Author(s): Gaƫl Ecorchard
autogenerated on Thu Jun 6 2019 22:02:02