Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
social_navigation_layers::ProxemicLayer Class Reference

#include <proxemic_layer.h>

Inheritance diagram for social_navigation_layers::ProxemicLayer:
Inheritance graph
[legend]

Public Member Functions

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)
 
- Public Member Functions inherited from social_navigation_layers::SocialLayer
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)
 
- Public Member Functions inherited from costmap_2d::Layer
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 ()
 

Protected Member Functions

void configure (ProxemicLayerConfig &config, uint32_t level)
 
- Protected Member Functions inherited from social_navigation_layers::SocialLayer
void peopleCallback (const people_msgs::People &people)
 

Protected Attributes

double amplitude_
 
double covar_
 
double cutoff_
 
dynamic_reconfigure::Server< ProxemicLayerConfig >::CallbackType f_
 
double factor_
 
dynamic_reconfigure::Server< ProxemicLayerConfig > * server_
 
- Protected Attributes inherited from social_navigation_layers::SocialLayer
bool first_time_
 
double last_max_x_
 
double last_max_y_
 
double last_min_x_
 
double last_min_y_
 
boost::recursive_mutex lock_
 
ros::Duration people_keep_time_
 
people_msgs::People people_list_
 
ros::Subscriber people_sub_
 
tf::TransformListener tf_
 
std::list< people_msgs::Person > transformed_people_
 
- Protected Attributes inherited from costmap_2d::Layer
bool current_
 
bool enabled_
 
LayeredCostmaplayered_costmap_
 
std::string name_
 
tf::TransformListenertf_
 

Detailed Description

Definition at line 14 of file proxemic_layer.h.

Constructor & Destructor Documentation

social_navigation_layers::ProxemicLayer::ProxemicLayer ( )
inline

Definition at line 17 of file proxemic_layer.h.

Member Function Documentation

void social_navigation_layers::ProxemicLayer::configure ( ProxemicLayerConfig &  config,
uint32_t  level 
)
protected

Definition at line 154 of file proxemic_layer.cpp.

void social_navigation_layers::ProxemicLayer::onInitialize ( )
virtual

Reimplemented from social_navigation_layers::SocialLayer.

Definition at line 34 of file proxemic_layer.cpp.

void social_navigation_layers::ProxemicLayer::updateBoundsFromPeople ( double *  min_x,
double *  min_y,
double *  max_x,
double *  max_y 
)
virtual

Implements social_navigation_layers::SocialLayer.

Definition at line 43 of file proxemic_layer.cpp.

void social_navigation_layers::ProxemicLayer::updateCosts ( costmap_2d::Costmap2D master_grid,
int  min_i,
int  min_j,
int  max_i,
int  max_j 
)
virtual

Member Data Documentation

double social_navigation_layers::ProxemicLayer::amplitude_
protected

Definition at line 28 of file proxemic_layer.h.

double social_navigation_layers::ProxemicLayer::covar_
protected

Definition at line 28 of file proxemic_layer.h.

double social_navigation_layers::ProxemicLayer::cutoff_
protected

Definition at line 28 of file proxemic_layer.h.

dynamic_reconfigure::Server<ProxemicLayerConfig>::CallbackType social_navigation_layers::ProxemicLayer::f_
protected

Definition at line 30 of file proxemic_layer.h.

double social_navigation_layers::ProxemicLayer::factor_
protected

Definition at line 28 of file proxemic_layer.h.

dynamic_reconfigure::Server<ProxemicLayerConfig>* social_navigation_layers::ProxemicLayer::server_
protected

Definition at line 29 of file proxemic_layer.h.


The documentation for this class was generated from the following files:


social_navigation_layers
Author(s): David V. Lu!!
autogenerated on Thu Mar 4 2021 04:02:57