#include <proxemic_layer.h>
 | 
| virtual void  | onInitialize () | 
|   | 
|   | ProxemicLayer () | 
|   | 
| virtual void  | updateBoundsFromPeople (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) | 
|   | 
| bool  | isDiscretized () | 
|   | 
|   | SocialLayer () | 
|   | 
| virtual void  | updateBounds (double origin_x, double origin_y, double origin_yaw, double *min_x, double *min_y, double *max_x, double *max_y) | 
|   | 
| virtual void  | activate () | 
|   | 
| virtual void  | deactivate () | 
|   | 
| 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  | matchSize () | 
|   | 
| virtual void  | onFootprintChanged () | 
|   | 
| virtual void  | reset () | 
|   | 
| virtual  | ~Layer () | 
|   | 
 | 
| void  | configure (ProxemicLayerConfig &config, uint32_t level) | 
|   | 
| void  | peopleCallback (const people_msgs::People &people) | 
|   | 
Definition at line 14 of file proxemic_layer.h.
 
  
  
      
        
          | social_navigation_layers::ProxemicLayer::ProxemicLayer  | 
          ( | 
           | ) | 
           | 
         
       
   | 
  
inline   | 
  
 
 
  
  
      
        
          | void social_navigation_layers::ProxemicLayer::configure  | 
          ( | 
          ProxemicLayerConfig &  | 
          config,  | 
         
        
           | 
           | 
          uint32_t  | 
          level  | 
         
        
           | 
          ) | 
           |  | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | void social_navigation_layers::ProxemicLayer::onInitialize  | 
          ( | 
           | ) | 
           | 
         
       
   | 
  
virtual   | 
  
 
 
  
  
      
        
          | void social_navigation_layers::ProxemicLayer::updateBoundsFromPeople  | 
          ( | 
          double *  | 
          min_x,  | 
         
        
           | 
           | 
          double *  | 
          min_y,  | 
         
        
           | 
           | 
          double *  | 
          max_x,  | 
         
        
           | 
           | 
          double *  | 
          max_y  | 
         
        
           | 
          ) | 
           |  | 
         
       
   | 
  
virtual   | 
  
 
 
  
  
      
        
          | void social_navigation_layers::ProxemicLayer::updateCosts  | 
          ( | 
          costmap_2d::Costmap2D &  | 
          master_grid,  | 
         
        
           | 
           | 
          int  | 
          min_i,  | 
         
        
           | 
           | 
          int  | 
          min_j,  | 
         
        
           | 
           | 
          int  | 
          max_i,  | 
         
        
           | 
           | 
          int  | 
          max_j  | 
         
        
           | 
          ) | 
           |  | 
         
       
   | 
  
virtual   | 
  
 
 
  
  
      
        
          | double social_navigation_layers::ProxemicLayer::amplitude_ | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | double social_navigation_layers::ProxemicLayer::covar_ | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | double social_navigation_layers::ProxemicLayer::cutoff_ | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | dynamic_reconfigure::Server<ProxemicLayerConfig>::CallbackType social_navigation_layers::ProxemicLayer::f_ | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | double social_navigation_layers::ProxemicLayer::factor_ | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | dynamic_reconfigure::Server<ProxemicLayerConfig>* social_navigation_layers::ProxemicLayer::server_ | 
         
       
   | 
  
protected   | 
  
 
 
The documentation for this class was generated from the following files: