| 
|   | PassingLayer () | 
|   | 
| virtual void  | updateBounds (double origin_x, double origin_y, double origin_z, 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) | 
|   | 
| virtual void  | onInitialize () | 
|   | 
|   | ProxemicLayer () | 
|   | 
| virtual void  | updateBoundsFromPeople (double *min_x, double *min_y, double *max_x, double *max_y) | 
|   | 
| bool  | isDiscretized () | 
|   | 
|   | SocialLayer () | 
|   | 
| 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 () | 
|   | 
Definition at line 13 of file passing_layer.cpp.
 
  
  
      
        
          | social_navigation_layers::PassingLayer::PassingLayer  | 
          ( | 
           | ) | 
           | 
         
       
   | 
  
inline   | 
  
 
 
  
  
      
        
          | virtual void social_navigation_layers::PassingLayer::updateBounds  | 
          ( | 
          double  | 
          origin_x,  | 
         
        
           | 
           | 
          double  | 
          origin_y,  | 
         
        
           | 
           | 
          double  | 
          origin_z,  | 
         
        
           | 
           | 
          double *  | 
          min_x,  | 
         
        
           | 
           | 
          double *  | 
          min_y,  | 
         
        
           | 
           | 
          double *  | 
          max_x,  | 
         
        
           | 
           | 
          double *  | 
          max_y  | 
         
        
           | 
          ) | 
           |  | 
         
       
   | 
  
inlinevirtual   | 
  
 
 
  
  
      
        
          | virtual void social_navigation_layers::PassingLayer::updateCosts  | 
          ( | 
          costmap_2d::Costmap2D &  | 
          master_grid,  | 
         
        
           | 
           | 
          int  | 
          min_i,  | 
         
        
           | 
           | 
          int  | 
          min_j,  | 
         
        
           | 
           | 
          int  | 
          max_i,  | 
         
        
           | 
           | 
          int  | 
          max_j  | 
         
        
           | 
          ) | 
           |  | 
         
       
   | 
  
inlinevirtual   | 
  
 
 
The documentation for this class was generated from the following file: