proxemic_layer.h
Go to the documentation of this file.
00001 #ifndef PROXEMIC_LAYER_H_
00002 #define PROXEMIC_LAYER_H_
00003 #include <ros/ros.h>
00004 #include <social_navigation_layers/social_layer.h>
00005 #include <dynamic_reconfigure/server.h>
00006 #include <social_navigation_layers/ProxemicLayerConfig.h>
00007 
00008 double gaussian(double x, double y, double x0, double y0, double A, double varx, double vary, double skew);
00009 double get_radius(double cutoff, double A, double var);
00010 
00011 namespace social_navigation_layers
00012 {
00013   class ProxemicLayer : public SocialLayer
00014   {
00015     public:
00016       ProxemicLayer() { layered_costmap_ = NULL; }
00017 
00018       virtual void onInitialize();
00019       virtual void updateBoundsFromPeople(double* min_x, double* min_y, double* max_x, double* max_y);
00020       virtual void updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j);
00021 
00022     protected:
00023       void configure(ProxemicLayerConfig &config, uint32_t level);
00024       double cutoff_, amplitude_, covar_, factor_;
00025       dynamic_reconfigure::Server<ProxemicLayerConfig>* server_;
00026       dynamic_reconfigure::Server<ProxemicLayerConfig>::CallbackType f_;
00027   };
00028 };
00029 
00030 
00031 #endif
00032 


social_navigation_layers
Author(s): David V. Lu!!
autogenerated on Sat Jun 8 2019 19:17:50