Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
social_navigation_layers::SocialLayer Class Referenceabstract

#include <social_layer.h>

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

Public Member Functions

bool isDiscretized ()
 
virtual void onInitialize ()
 
 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 updateBoundsFromPeople (double *min_x, double *min_y, double *max_x, double *max_y)=0
 
virtual void updateCosts (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)=0
 
- 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 peopleCallback (const people_msgs::People &people)
 

Protected Attributes

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 13 of file social_layer.h.

Constructor & Destructor Documentation

social_navigation_layers::SocialLayer::SocialLayer ( )
inline

Definition at line 16 of file social_layer.h.

Member Function Documentation

bool social_navigation_layers::SocialLayer::isDiscretized ( )
inline

Definition at line 28 of file social_layer.h.

void social_navigation_layers::SocialLayer::onInitialize ( )
virtual

Reimplemented from costmap_2d::Layer.

Reimplemented in social_navigation_layers::ProxemicLayer.

Definition at line 16 of file social_layer.cpp.

void social_navigation_layers::SocialLayer::peopleCallback ( const people_msgs::People &  people)
protected

Definition at line 24 of file social_layer.cpp.

void social_navigation_layers::SocialLayer::updateBounds ( double  origin_x,
double  origin_y,
double  origin_yaw,
double *  min_x,
double *  min_y,
double *  max_x,
double *  max_y 
)
virtual

Reimplemented from costmap_2d::Layer.

Reimplemented in social_navigation_layers::PassingLayer.

Definition at line 31 of file social_layer.cpp.

virtual void social_navigation_layers::SocialLayer::updateBoundsFromPeople ( double *  min_x,
double *  min_y,
double *  max_x,
double *  max_y 
)
pure virtual
virtual void social_navigation_layers::SocialLayer::updateCosts ( costmap_2d::Costmap2D master_grid,
int  min_i,
int  min_j,
int  max_i,
int  max_j 
)
pure virtual

Member Data Documentation

bool social_navigation_layers::SocialLayer::first_time_
protected

Definition at line 41 of file social_layer.h.

double social_navigation_layers::SocialLayer::last_max_x_
protected

Definition at line 42 of file social_layer.h.

double social_navigation_layers::SocialLayer::last_max_y_
protected

Definition at line 42 of file social_layer.h.

double social_navigation_layers::SocialLayer::last_min_x_
protected

Definition at line 42 of file social_layer.h.

double social_navigation_layers::SocialLayer::last_min_y_
protected

Definition at line 42 of file social_layer.h.

boost::recursive_mutex social_navigation_layers::SocialLayer::lock_
protected

Definition at line 39 of file social_layer.h.

ros::Duration social_navigation_layers::SocialLayer::people_keep_time_
protected

Definition at line 38 of file social_layer.h.

people_msgs::People social_navigation_layers::SocialLayer::people_list_
protected

Definition at line 36 of file social_layer.h.

ros::Subscriber social_navigation_layers::SocialLayer::people_sub_
protected

Definition at line 35 of file social_layer.h.

tf::TransformListener social_navigation_layers::SocialLayer::tf_
protected

Definition at line 40 of file social_layer.h.

std::list<people_msgs::Person> social_navigation_layers::SocialLayer::transformed_people_
protected

Definition at line 37 of file social_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